diff --git a/crazyflie/CMakeLists.txt b/crazyflie/CMakeLists.txt index ed6c31903..c8899cfbe 100644 --- a/crazyflie/CMakeLists.txt +++ b/crazyflie/CMakeLists.txt @@ -112,10 +112,11 @@ install(PROGRAMS DESTINATION lib/${PROJECT_NAME} ) -# Install launch and config files. +# Install launch, config, and urdf files. install(DIRECTORY launch config + urdf DESTINATION share/${PROJECT_NAME}/ ) diff --git a/crazyflie/config/config.rviz b/crazyflie/config/config.rviz index d19a5dc9a..9d1b49a9e 100644 --- a/crazyflie/config/config.rviz +++ b/crazyflie/config/config.rviz @@ -52,7 +52,7 @@ Visualization Manager: Frame Timeout: 15 Frames: All Enabled: true - test: + cf231: Value: true world: Value: true @@ -60,13 +60,44 @@ Visualization Manager: Name: TF Show Arrows: true Show Axes: true - Show Names: false + Show Names: true Tree: world: - test: + cf231: {} Update Interval: 0 Value: true + - Alpha: 1 + Class: rviz_default_plugins/RobotModel + Collision Enabled: false + Description File: "" + Description Source: Topic + Description Topic: + Depth: 5 + Durability Policy: Volatile + History Policy: Keep Last + Reliability Policy: Reliable + Value: /cf231/robot_description + Enabled: true + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + cf231: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Mass Properties: + Inertia: false + Mass: false + Name: CF231 + TF Prefix: "" + Update Interval: 0 + Value: true + Visual Enabled: true Enabled: true Global Options: Background Color: 48; 48; 48 @@ -113,25 +144,25 @@ Visualization Manager: Views: Current: Class: rviz_default_plugins/Orbit - Distance: 6.814720153808594 + Distance: 3.1647839546203613 Enable Stereo Rendering: Stereo Eye Separation: 0.05999999865889549 Stereo Focal Distance: 1 Swap Stereo Eyes: false Value: false Focal Point: - X: 0 - Y: 0 - Z: 0 + X: -0.028163839131593704 + Y: -0.049007341265678406 + Z: -0.025782346725463867 Focal Shape Fixed Size: true Focal Shape Size: 0.05000000074505806 Invert Z Axis: false Name: Current View Near Clip Distance: 0.009999999776482582 - Pitch: 0.665398120880127 + Pitch: 0.4847976565361023 Target Frame: Value: Orbit (rviz) - Yaw: 2.8785719871520996 + Yaw: 2.9185757637023926 Saved: ~ Window Geometry: Displays: diff --git a/crazyflie/launch/launch.py b/crazyflie/launch/launch.py index e71b9cf51..8a9290c11 100644 --- a/crazyflie/launch/launch.py +++ b/crazyflie/launch/launch.py @@ -30,6 +30,15 @@ def generate_launch_description(): server_params = [crazyflies] + [server_yaml_contents["/crazyflie_server"]["ros__parameters"]] + # robot description + urdf = os.path.join( + get_package_share_directory('crazyflie'), + 'urdf', + 'crazyflie_description.urdf') + with open(urdf, 'r') as f: + robot_desc = f.read() + server_params[1]["robot_description"] = robot_desc + # construct motion_capture_configuration motion_capture_yaml = os.path.join( get_package_share_directory('crazyflie'), diff --git a/crazyflie/scripts/crazyflie_server.py b/crazyflie/scripts/crazyflie_server.py index ca44a9320..fbbe8fe72 100755 --- a/crazyflie/scripts/crazyflie_server.py +++ b/crazyflie/scripts/crazyflie_server.py @@ -30,6 +30,7 @@ from motion_capture_tracking_interfaces.msg import NamedPoseArray from std_srvs.srv import Empty +from std_msgs.msg import String from geometry_msgs.msg import Twist from geometry_msgs.msg import PoseStamped, TransformStamped from sensor_msgs.msg import LaserScan @@ -220,6 +221,16 @@ def __init__(self): for uri in self.cf_dict: name = self.cf_dict[uri] + + pub = self.create_publisher(String, name + '/robot_description', + rclpy.qos.QoSProfile( + depth=1, + durability=rclpy.qos.QoSDurabilityPolicy.TRANSIENT_LOCAL)) + + msg = String() + msg.data = self._ros_parameters['robot_description'].replace("$NAME", name) + pub.publish(msg) + self.create_service( Empty, name + "/emergency", partial(self._emergency_callback, uri=uri) diff --git a/crazyflie/src/crazyflie_server.cpp b/crazyflie/src/crazyflie_server.cpp index d79e307f7..4a71e0245 100644 --- a/crazyflie/src/crazyflie_server.cpp +++ b/crazyflie/src/crazyflie_server.cpp @@ -12,6 +12,7 @@ #include "crazyflie_interfaces/srv/land.hpp" #include "crazyflie_interfaces/srv/go_to.hpp" #include "crazyflie_interfaces/srv/notify_setpoints_stop.hpp" +#include "std_msgs/msg/string.hpp" #include "geometry_msgs/msg/twist.hpp" #include "geometry_msgs/msg/pose_stamped.hpp" #include "geometry_msgs/msg/transform_stamped.hpp" @@ -160,6 +161,15 @@ class CrazyflieROS subscription_cmd_full_state_ = node->create_subscription(name + "/cmd_full_state", rclcpp::SystemDefaultsQoS(), std::bind(&CrazyflieROS::cmd_full_state_changed, this, _1), sub_opt_cf_cmd); subscription_cmd_position_ = node->create_subscription(name + "/cmd_position", rclcpp::SystemDefaultsQoS(), std::bind(&CrazyflieROS::cmd_position_changed, this, _1), sub_opt_cf_cmd); + publisher_robot_description_ = node->create_publisher(name + "/robot_description", + rclcpp::QoS(1).transient_local()); + { + auto msg = std::make_unique(); + auto robot_desc = node->get_parameter("robot_description").get_parameter_value().get(); + msg->data = std::regex_replace(robot_desc, std::regex("\\$NAME"), name); + publisher_robot_description_->publish(std::move(msg)); + } + // spinning timer // used to process all incoming radio messages spin_timer_ = @@ -871,6 +881,8 @@ class CrazyflieROS rclcpp::Subscription::SharedPtr subscription_cmd_full_state_; rclcpp::Subscription::SharedPtr subscription_cmd_position_; + rclcpp::Publisher::SharedPtr publisher_robot_description_; + // logging std::unique_ptr> log_block_pose_; rclcpp::Publisher::SharedPtr publisher_pose_; @@ -953,6 +965,8 @@ class CrazyflieServer : public rclcpp::Node broadcasts_delay_between_repeats_ms_ = this->get_parameter("all.broadcasts.delay_between_repeats_ms").get_parameter_value().get(); mocap_enabled_ = false; + this->declare_parameter("robot_description", ""); + // Warnings this->declare_parameter("warnings.frequency", 1.0); float freq = this->get_parameter("warnings.frequency").get_parameter_value().get(); diff --git a/crazyflie/urdf/cf2_assembly_with_props.dae b/crazyflie/urdf/cf2_assembly_with_props.dae new file mode 100644 index 000000000..8e781721e --- /dev/null +++ b/crazyflie/urdf/cf2_assembly_with_props.dae @@ -0,0 +1,433 @@ + + + + + + Kimberly McGuire (Bitcraze AB) + Blender 3.1.2 commit date:2022-03-31, commit time:17:40, hash:cc66d1020c3b + + 2024-01-30T21:06:41 + 2024-01-30T21:06:41 + + Z_UP + + + + + + + + 0 0 0 1 + + + 0.009523815 0.009523815 0.009523815 1 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.1169535 0.1169535 0.1169535 1 + + + 0.8 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.3428556 0.3428556 0.3428556 1 + + + 0.6528497 + + + 1.45 + + + + + + + + + + + 0 0 0 1 + + + 0.8 0.8 0.8 1 + + + 0.5 + + + + + + + + + + + + + + + + + + + + + + + + + + -0.00999999 0.00999999 5e-4 -0.00999999 0.00999999 0.002499997 -0.00999999 0.01199996 0.002499997 -0.00999999 0.01199996 5e-4 0.00999999 0.01199996 0.002499997 0.00999999 0.01199996 5e-4 0.00999999 0.00999999 0.002499997 0.00999999 0.00999999 5e-4 -0.00999999 -0.00999999 5e-4 -0.00999999 -0.01199996 5e-4 -0.00999999 -0.01199996 0.002499997 -0.00999999 -0.00999999 0.002499997 0.00999999 -0.01199996 5e-4 0.00999999 -0.01199996 0.002499997 0.00999999 -0.00999999 5e-4 0.00999999 -0.00999999 0.002499997 -0.00999999 -0.01399999 -5e-4 -0.00999999 -0.01399999 5e-4 -0.00999999 0.01399999 5e-4 -0.00999999 0.01399999 -5e-4 0.00999999 0.01399999 5e-4 0.00999999 0.01399999 -5e-4 0.00999999 -0.01399999 5e-4 0.00999999 -0.01399999 -5e-4 -0.00109595 0.008999943 -5e-4 0.00109595 0.008999943 -5e-4 0.00109595 -0.008999943 -5e-4 -0.00109595 -0.008999943 -5e-4 -0.008095979 0.008999943 -5e-4 -0.008095979 -0.008999943 -5e-4 0.008095979 -0.008999943 -5e-4 0.008095979 0.008999943 -5e-4 -0.00109595 -0.008999943 5e-4 -0.008095979 -0.008999943 5e-4 -0.008095979 0.008999943 5e-4 -0.00109595 0.008999943 5e-4 0.00109595 0.008999943 5e-4 0.008095979 0.008999943 5e-4 0.008095979 -0.008999943 5e-4 0.00109595 -0.008999943 5e-4 + + + + + + + + + + -1 0 0 0 1 0 1 0 0 0 -1 0 0 0 -1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 -1 0 0 1 0 0 1 0 0 + + + + + + + + + + + + + + +

0 0 1 0 2 0 0 0 2 0 3 0 3 1 2 1 4 1 3 1 4 1 5 1 5 2 4 2 6 2 5 2 6 2 7 2 7 3 6 3 1 3 7 3 1 3 0 3 3 4 5 4 7 4 3 4 7 4 0 4 4 5 2 5 1 5 4 5 1 5 6 5 8 0 9 0 10 0 8 0 10 0 11 0 9 3 12 3 13 3 9 3 13 3 10 3 12 2 14 2 15 2 12 2 15 2 13 2 14 1 8 1 11 1 14 1 11 1 15 1 9 4 8 4 14 4 9 4 14 4 12 4 13 5 15 5 11 5 13 5 11 5 10 5 16 0 17 0 18 0 16 0 18 0 19 0 19 1 18 1 20 1 19 1 20 1 21 1 21 2 20 2 22 2 21 2 22 2 23 2 23 3 22 3 17 3 23 3 17 3 16 3 24 6 25 6 26 6 24 4 26 4 27 4 16 4 19 4 28 4 16 4 28 4 29 4 24 4 28 4 19 4 23 4 16 4 29 4 27 5 26 5 30 5 23 4 29 4 27 4 24 4 19 4 21 4 31 4 25 4 24 4 23 4 27 4 30 4 31 4 24 4 21 4 23 4 30 4 31 4 21 7 23 7 31 7 32 5 33 5 17 5 20 5 18 5 34 5 35 5 36 5 37 5 20 5 34 5 35 5 32 5 17 5 22 5 38 5 39 5 32 5 20 8 35 8 37 8 38 5 32 5 22 5 20 9 37 9 38 9 22 5 20 5 38 5 34 5 18 5 17 5 34 10 17 10 33 10 36 11 35 11 32 11 36 5 32 5 39 5 27 1 29 1 33 1 27 1 33 1 32 1 33 2 29 2 28 2 33 2 28 2 34 2 34 3 28 3 24 3 34 3 24 3 35 3 24 0 27 0 32 0 24 0 32 0 35 0 30 1 26 1 39 1 30 1 39 1 38 1 31 0 30 0 38 0 31 12 38 12 37 12 36 3 25 3 31 3 36 3 31 3 37 3 39 13 26 13 25 13 39 14 25 14 36 14

+
+
+
+ + + + -0.008816301 2.5e-4 0.01445657 -0.009316325 2.5e-4 0.01445657 -0.009316325 -2.5e-4 0.01445657 -0.008816301 -2.5e-4 0.01445657 -0.008816301 -2.5e-4 -0.003543376 -0.009316325 -2.5e-4 -0.003543376 -0.009316325 2.5e-4 -0.003543376 -0.008816301 2.5e-4 -0.003543376 -0.006816327 2.5e-4 0.01445657 -0.00731635 2.5e-4 0.01445657 -0.00731635 -2.5e-4 0.01445657 -0.006816327 -2.5e-4 0.01445657 -0.006816327 -2.5e-4 -0.003543376 -0.00731635 -2.5e-4 -0.003543376 -0.00731635 2.5e-4 -0.003543376 -0.006816327 2.5e-4 -0.003543376 -0.004816353 2.5e-4 0.01445657 -0.005316317 2.5e-4 0.01445657 -0.005316317 -2.5e-4 0.01445657 -0.004816353 -2.5e-4 0.01445657 -0.004816353 -2.5e-4 -0.003543376 -0.005316317 -2.5e-4 -0.003543376 -0.005316317 2.5e-4 -0.003543376 -0.004816353 2.5e-4 -0.003543376 -0.002816319 2.5e-4 0.01445657 -0.003316342 2.5e-4 0.01445657 -0.003316342 -2.5e-4 0.01445657 -0.002816319 -2.5e-4 0.01445657 -0.002816319 -2.5e-4 -0.003543376 -0.003316342 -2.5e-4 -0.003543376 -0.003316342 2.5e-4 -0.003543376 -0.002816319 2.5e-4 -0.003543376 -8.16359e-4 2.5e-4 0.01445657 -0.001316308 2.5e-4 0.01445657 -0.001316308 -2.5e-4 0.01445657 -8.16359e-4 -2.5e-4 0.01445657 -8.16359e-4 -2.5e-4 -0.003543376 -0.001316308 -2.5e-4 -0.003543376 -0.001316308 2.5e-4 -0.003543376 -8.16359e-4 2.5e-4 -0.003543376 0.001183629 2.5e-4 0.01445657 6.8364e-4 2.5e-4 0.01445657 6.8364e-4 -2.5e-4 0.01445657 0.001183629 -2.5e-4 0.01445657 0.001183629 -2.5e-4 -0.003543376 6.8364e-4 -2.5e-4 -0.003543376 6.8364e-4 2.5e-4 -0.003543376 0.001183629 2.5e-4 -0.003543376 0.003183603 2.5e-4 0.01445657 0.002683639 2.5e-4 0.01445657 0.002683639 -2.5e-4 0.01445657 0.003183603 -2.5e-4 0.01445657 0.003183603 -2.5e-4 -0.003543376 0.002683639 -2.5e-4 -0.003543376 0.002683639 2.5e-4 -0.003543376 0.003183603 2.5e-4 -0.003543376 0.005183637 2.5e-4 0.01445657 0.004683613 2.5e-4 0.01445657 0.004683613 -2.5e-4 0.01445657 0.005183637 -2.5e-4 0.01445657 0.005183637 -2.5e-4 -0.003543376 0.004683613 -2.5e-4 -0.003543376 0.004683613 2.5e-4 -0.003543376 0.005183637 2.5e-4 -0.003543376 0.007183611 2.5e-4 0.01445657 0.006683588 2.5e-4 0.01445657 0.006683588 -2.5e-4 0.01445657 0.007183611 -2.5e-4 0.01445657 0.007183611 -2.5e-4 -0.003543376 0.006683588 -2.5e-4 -0.003543376 0.006683588 2.5e-4 -0.003543376 0.007183611 2.5e-4 -0.003543376 0.009183585 2.5e-4 0.01445657 0.008683621 2.5e-4 0.01445657 0.008683621 -2.5e-4 0.01445657 0.009183585 -2.5e-4 0.01445657 0.009183585 -2.5e-4 -0.003543376 0.008683621 -2.5e-4 -0.003543376 0.008683621 2.5e-4 -0.003543376 0.009183585 2.5e-4 -0.003543376 -0.00999999 -0.000999987 -10e-4 -0.00999999 -0.000999987 0.000999987 -0.00999999 0.000999987 0.000999987 -0.00999999 0.000999987 -10e-4 0.00999999 0.000999987 0.000999987 0.00999999 0.000999987 -10e-4 0.00999999 -0.000999987 0.000999987 0.00999999 -0.000999987 -10e-4 -0.008816301 -0.02224999 0.01445657 -0.009316325 -0.02224999 0.01445657 -0.009316325 -0.02174997 0.01445657 -0.008816301 -0.02174997 0.01445657 -0.008816301 -0.02174997 -0.003543376 -0.009316325 -0.02174997 -0.003543376 -0.009316325 -0.02224999 -0.003543376 -0.008816301 -0.02224999 -0.003543376 -0.006816327 -0.02224999 0.01445657 -0.00731635 -0.02224999 0.01445657 -0.00731635 -0.02174997 0.01445657 -0.006816327 -0.02174997 0.01445657 -0.006816327 -0.02174997 -0.003543376 -0.00731635 -0.02174997 -0.003543376 -0.00731635 -0.02224999 -0.003543376 -0.006816327 -0.02224999 -0.003543376 -0.004816353 -0.02224999 0.01445657 -0.005316317 -0.02224999 0.01445657 -0.005316317 -0.02174997 0.01445657 -0.004816353 -0.02174997 0.01445657 -0.004816353 -0.02174997 -0.003543376 -0.005316317 -0.02174997 -0.003543376 -0.005316317 -0.02224999 -0.003543376 -0.004816353 -0.02224999 -0.003543376 -0.002816319 -0.02224999 0.01445657 -0.003316342 -0.02224999 0.01445657 -0.003316342 -0.02174997 0.01445657 -0.002816319 -0.02174997 0.01445657 -0.002816319 -0.02174997 -0.003543376 -0.003316342 -0.02174997 -0.003543376 -0.003316342 -0.02224999 -0.003543376 -0.002816319 -0.02224999 -0.003543376 -8.16359e-4 -0.02224999 0.01445657 -0.001316308 -0.02224999 0.01445657 -0.001316308 -0.02174997 0.01445657 -8.16359e-4 -0.02174997 0.01445657 -8.16359e-4 -0.02174997 -0.003543376 -0.001316308 -0.02174997 -0.003543376 -0.001316308 -0.02224999 -0.003543376 -8.16359e-4 -0.02224999 -0.003543376 0.001183629 -0.02224999 0.01445657 6.8364e-4 -0.02224999 0.01445657 6.8364e-4 -0.02174997 0.01445657 0.001183629 -0.02174997 0.01445657 0.001183629 -0.02174997 -0.003543376 6.8364e-4 -0.02174997 -0.003543376 6.8364e-4 -0.02224999 -0.003543376 0.001183629 -0.02224999 -0.003543376 0.003183603 -0.02224999 0.01445657 0.002683639 -0.02224999 0.01445657 0.002683639 -0.02174997 0.01445657 0.003183603 -0.02174997 0.01445657 0.003183603 -0.02174997 -0.003543376 0.002683639 -0.02174997 -0.003543376 0.002683639 -0.02224999 -0.003543376 0.003183603 -0.02224999 -0.003543376 0.005183637 -0.02224999 0.01445657 0.004683613 -0.02224999 0.01445657 0.004683613 -0.02174997 0.01445657 0.005183637 -0.02174997 0.01445657 0.005183637 -0.02174997 -0.003543376 0.004683613 -0.02174997 -0.003543376 0.004683613 -0.02224999 -0.003543376 0.005183637 -0.02224999 -0.003543376 0.007183611 -0.02224999 0.01445657 0.006683588 -0.02224999 0.01445657 0.006683588 -0.02174997 0.01445657 0.007183611 -0.02174997 0.01445657 0.007183611 -0.02174997 -0.003543376 0.006683588 -0.02174997 -0.003543376 0.006683588 -0.02224999 -0.003543376 0.007183611 -0.02224999 -0.003543376 0.009183585 -0.02224999 0.01445657 0.008683621 -0.02224999 0.01445657 0.008683621 -0.02174997 0.01445657 0.009183585 -0.02174997 0.01445657 0.009183585 -0.02174997 -0.003543376 0.008683621 -0.02174997 -0.003543376 0.008683621 -0.02224999 -0.003543376 0.009183585 -0.02224999 -0.003543376 -0.00999999 -0.02099996 -10e-4 -0.00999999 -0.02099996 0.000999987 -0.00999999 -0.023 0.000999987 -0.00999999 -0.023 -10e-4 0.00999999 -0.023 0.000999987 0.00999999 -0.023 -10e-4 0.00999999 -0.02099996 0.000999987 0.00999999 -0.02099996 -10e-4 + + + + + + + + + + 0 0 1 0 -1 0 -1 0 0 0 0 -1 1 0 0 0 1 0 + + + + + + + + + + + + + + +

0 0 1 0 2 0 0 0 2 0 3 0 4 1 3 1 2 1 4 1 2 1 5 1 5 2 2 2 1 2 5 2 1 2 6 2 6 3 7 3 4 3 6 3 4 3 5 3 7 4 0 4 3 4 7 4 3 4 4 4 6 5 1 5 0 5 6 5 0 5 7 5 8 0 9 0 10 0 8 0 10 0 11 0 12 1 11 1 10 1 12 1 10 1 13 1 13 2 10 2 9 2 13 2 9 2 14 2 14 3 15 3 12 3 14 3 12 3 13 3 15 4 8 4 11 4 15 4 11 4 12 4 14 5 9 5 8 5 14 5 8 5 15 5 16 0 17 0 18 0 16 0 18 0 19 0 20 1 19 1 18 1 20 1 18 1 21 1 21 2 18 2 17 2 21 2 17 2 22 2 22 3 23 3 20 3 22 3 20 3 21 3 23 4 16 4 19 4 23 4 19 4 20 4 22 5 17 5 16 5 22 5 16 5 23 5 24 0 25 0 26 0 24 0 26 0 27 0 28 1 27 1 26 1 28 1 26 1 29 1 29 2 26 2 25 2 29 2 25 2 30 2 30 3 31 3 28 3 30 3 28 3 29 3 31 4 24 4 27 4 31 4 27 4 28 4 30 5 25 5 24 5 30 5 24 5 31 5 32 0 33 0 34 0 32 0 34 0 35 0 36 1 35 1 34 1 36 1 34 1 37 1 37 2 34 2 33 2 37 2 33 2 38 2 38 3 39 3 36 3 38 3 36 3 37 3 39 4 32 4 35 4 39 4 35 4 36 4 38 5 33 5 32 5 38 5 32 5 39 5 40 0 41 0 42 0 40 0 42 0 43 0 44 1 43 1 42 1 44 1 42 1 45 1 45 2 42 2 41 2 45 2 41 2 46 2 46 3 47 3 44 3 46 3 44 3 45 3 47 4 40 4 43 4 47 4 43 4 44 4 46 5 41 5 40 5 46 5 40 5 47 5 48 0 49 0 50 0 48 0 50 0 51 0 52 1 51 1 50 1 52 1 50 1 53 1 53 2 50 2 49 2 53 2 49 2 54 2 54 3 55 3 52 3 54 3 52 3 53 3 55 4 48 4 51 4 55 4 51 4 52 4 54 5 49 5 48 5 54 5 48 5 55 5 56 0 57 0 58 0 56 0 58 0 59 0 60 1 59 1 58 1 60 1 58 1 61 1 61 2 58 2 57 2 61 2 57 2 62 2 62 3 63 3 60 3 62 3 60 3 61 3 63 4 56 4 59 4 63 4 59 4 60 4 62 5 57 5 56 5 62 5 56 5 63 5 64 0 65 0 66 0 64 0 66 0 67 0 68 1 67 1 66 1 68 1 66 1 69 1 69 2 66 2 65 2 69 2 65 2 70 2 70 3 71 3 68 3 70 3 68 3 69 3 71 4 64 4 67 4 71 4 67 4 68 4 70 5 65 5 64 5 70 5 64 5 71 5 72 0 73 0 74 0 72 0 74 0 75 0 76 1 75 1 74 1 76 1 74 1 77 1 77 2 74 2 73 2 77 2 73 2 78 2 78 3 79 3 76 3 78 3 76 3 77 3 79 4 72 4 75 4 79 4 75 4 76 4 78 5 73 5 72 5 78 5 72 5 79 5 80 2 81 2 82 2 80 2 82 2 83 2 83 5 82 5 84 5 83 5 84 5 85 5 85 4 84 4 86 4 85 4 86 4 87 4 87 1 86 1 81 1 87 1 81 1 80 1 83 3 85 3 87 3 83 3 87 3 80 3 84 0 82 0 81 0 84 0 81 0 86 0 88 0 90 0 89 0 88 0 91 0 90 0 92 5 90 5 91 5 92 5 93 5 90 5 93 2 89 2 90 2 93 2 94 2 89 2 94 3 92 3 95 3 94 3 93 3 92 3 95 4 91 4 88 4 95 4 92 4 91 4 94 1 88 1 89 1 94 1 95 1 88 1 96 0 98 0 97 0 96 0 99 0 98 0 100 5 98 5 99 5 100 5 101 5 98 5 101 2 97 2 98 2 101 2 102 2 97 2 102 3 100 3 103 3 102 3 101 3 100 3 103 4 99 4 96 4 103 4 100 4 99 4 102 1 96 1 97 1 102 1 103 1 96 1 104 0 106 0 105 0 104 0 107 0 106 0 108 5 106 5 107 5 108 5 109 5 106 5 109 2 105 2 106 2 109 2 110 2 105 2 110 3 108 3 111 3 110 3 109 3 108 3 111 4 107 4 104 4 111 4 108 4 107 4 110 1 104 1 105 1 110 1 111 1 104 1 112 0 114 0 113 0 112 0 115 0 114 0 116 5 114 5 115 5 116 5 117 5 114 5 117 2 113 2 114 2 117 2 118 2 113 2 118 3 116 3 119 3 118 3 117 3 116 3 119 4 115 4 112 4 119 4 116 4 115 4 118 1 112 1 113 1 118 1 119 1 112 1 120 0 122 0 121 0 120 0 123 0 122 0 124 5 122 5 123 5 124 5 125 5 122 5 125 2 121 2 122 2 125 2 126 2 121 2 126 3 124 3 127 3 126 3 125 3 124 3 127 4 123 4 120 4 127 4 124 4 123 4 126 1 120 1 121 1 126 1 127 1 120 1 128 0 130 0 129 0 128 0 131 0 130 0 132 5 130 5 131 5 132 5 133 5 130 5 133 2 129 2 130 2 133 2 134 2 129 2 134 3 132 3 135 3 134 3 133 3 132 3 135 4 131 4 128 4 135 4 132 4 131 4 134 1 128 1 129 1 134 1 135 1 128 1 136 0 138 0 137 0 136 0 139 0 138 0 140 5 138 5 139 5 140 5 141 5 138 5 141 2 137 2 138 2 141 2 142 2 137 2 142 3 140 3 143 3 142 3 141 3 140 3 143 4 139 4 136 4 143 4 140 4 139 4 142 1 136 1 137 1 142 1 143 1 136 1 144 0 146 0 145 0 144 0 147 0 146 0 148 5 146 5 147 5 148 5 149 5 146 5 149 2 145 2 146 2 149 2 150 2 145 2 150 3 148 3 151 3 150 3 149 3 148 3 151 4 147 4 144 4 151 4 148 4 147 4 150 1 144 1 145 1 150 1 151 1 144 1 152 0 154 0 153 0 152 0 155 0 154 0 156 5 154 5 155 5 156 5 157 5 154 5 157 2 153 2 154 2 157 2 158 2 153 2 158 3 156 3 159 3 158 3 157 3 156 3 159 4 155 4 152 4 159 4 156 4 155 4 158 1 152 1 153 1 158 1 159 1 152 1 160 0 162 0 161 0 160 0 163 0 162 0 164 5 162 5 163 5 164 5 165 5 162 5 165 2 161 2 162 2 165 2 166 2 161 2 166 3 164 3 167 3 166 3 165 3 164 3 167 4 163 4 160 4 167 4 164 4 163 4 166 1 160 1 161 1 166 1 167 1 160 1 168 2 170 2 169 2 168 2 171 2 170 2 171 1 172 1 170 1 171 1 173 1 172 1 173 4 174 4 172 4 173 4 175 4 174 4 175 5 169 5 174 5 175 5 168 5 169 5 171 3 175 3 173 3 171 3 168 3 175 3 172 0 169 0 170 0 172 0 174 0 169 0

+
+
+
+ + + + 0.01091998 -0.008999943 -0.001559972 0.01091998 -0.008999943 0.001559972 -0.01091998 -0.008999943 0.001559972 -0.01091998 -0.008999943 -0.001559972 0.01399999 0.007019996 -0.001559972 0.01399999 0.007019996 0.001559972 0.01399999 -0.007019996 0.001559972 0.01399999 -0.007019996 -0.001559972 0.01091998 0.007019996 0.001999974 -0.01091998 0.007019996 0.001999974 -0.01091998 -0.007019996 0.001999974 0.01091998 -0.007019996 0.001999974 -0.01399999 -0.007019996 -0.001559972 -0.01399999 -0.007019996 0.001559972 -0.01399999 0.007019996 0.001559972 -0.01399999 0.007019996 -0.001559972 -0.01091998 0.008999943 -0.001559972 -0.01091998 0.008999943 0.001559972 0.01091998 0.008999943 0.001559972 0.01091998 0.008999943 -0.001559972 -0.01091998 -0.007019996 -0.001999974 -0.01091998 0.007019996 -0.001999974 0.01091998 -0.007019996 -0.001999974 0.01091998 0.007019996 -0.001999974 + + + + + + + + + + 0 -1 0 1 0 0 0 0 1 -1 0 0 0 1 0 -0.1381187 -0.2148514 -0.966831 -0.1381187 -0.2148514 0.966831 -0.1381187 0.2148514 -0.966831 -0.1381187 0.2148514 0.966831 0.1381187 -0.2148514 -0.966831 0.1381187 -0.2148514 0.966831 0.1381187 0.2148514 -0.966831 0.1381187 0.2148514 0.966831 -0.1414214 0 -0.9899496 -0.5407575 -0.8411786 0 -0.5407578 -0.8411785 0 -0.1414214 0 0.9899496 -0.5407575 0.8411786 0 -0.5407578 0.8411785 0 0 0.2169303 -0.9761872 0 0.2169306 -0.9761871 0 0.2169303 0.9761872 0 0.2169306 0.9761871 0.5407578 0.8411785 0 0.5407575 0.8411786 0 0.1414214 0 -0.9899496 0.1414214 0 0.9899496 0.5407575 -0.8411786 0 0.5407578 -0.8411785 0 0 -0.2169303 -0.9761872 0 -0.2169306 -0.9761871 0 -0.2169303 0.9761872 0 -0.2169306 0.9761871 0 0 -1 + + + + + + + + + + + + + + +

0 0 1 0 2 0 0 0 2 0 3 0 4 1 5 1 6 1 4 1 6 1 7 1 8 2 9 2 10 2 8 2 10 2 11 2 12 3 13 3 14 3 12 3 14 3 15 3 16 4 17 4 18 4 16 4 18 4 19 4 20 5 3 5 12 5 2 6 10 6 13 6 21 7 15 7 16 7 9 8 17 8 14 8 22 9 7 9 0 9 11 10 1 10 6 10 23 11 19 11 4 11 8 12 5 12 18 12 21 13 20 13 12 13 21 13 12 13 15 13 3 14 2 14 13 14 3 15 13 15 12 15 10 16 9 16 14 16 10 16 14 16 13 16 17 17 16 17 15 17 17 18 15 18 14 18 23 19 21 19 16 19 23 20 16 20 19 20 9 21 8 21 18 21 9 22 18 22 17 22 5 23 4 23 19 23 5 24 19 24 18 24 22 25 23 25 4 25 22 25 4 25 7 25 8 26 11 26 6 26 8 26 6 26 5 26 1 27 0 27 7 27 1 28 7 28 6 28 20 29 22 29 0 29 20 30 0 30 3 30 11 31 10 31 2 31 11 32 2 32 1 32 21 33 23 33 22 33 21 33 22 33 20 33

+
+
+
+ + + + 0.01349288 0.003098845 0.001246988 0.002614974 0.01389831 0.001246988 0.002614974 0.01389831 -0.001246988 0.01349288 0.003098845 -0.001246988 0.0288853 0.02750301 0.001246988 0.0288853 0.02750301 -0.001246988 0.0269072 0.02946692 -0.001246988 0.0269072 0.02946692 0.001246988 0.01658421 0.01987266 0.001246988 0.01658421 0.01987266 -0.001246988 0.01936602 0.01711088 0.001246988 0.01936602 0.01711088 -0.001246988 0.01064378 0.01584881 -0.001246988 0.01538521 0.01114153 -0.001246988 0.01538521 0.01114153 0.001246988 0.01064378 0.01584881 0.001246988 -0.01349288 0.003098845 0.001246988 -0.01349288 0.003098845 -0.001246988 -0.002614974 0.01389831 -0.001246988 -0.002614974 0.01389831 0.001246988 -0.0288853 0.02750301 0.001246988 -0.0269072 0.02946692 0.001246988 -0.0269072 0.02946692 -0.001246988 -0.0288853 0.02750301 -0.001246988 -0.01658421 0.01987266 0.001246988 -0.01658421 0.01987266 -0.001246988 -0.01936602 0.01711088 0.001246988 -0.01936602 0.01711088 -0.001246988 -0.01064378 0.01584881 -0.001246988 -0.01538521 0.01114153 -0.001246988 -0.01538521 0.01114153 0.001246988 -0.01064378 0.01584881 0.001246988 0.01349288 -0.003098845 0.001246988 0.01349288 -0.003098845 -0.001246988 0.002614974 -0.01389831 -0.001246988 0.002614974 -0.01389831 0.001246988 0.0288853 -0.02750301 0.001246988 0.0269072 -0.02946692 0.001246988 0.0269072 -0.02946692 -0.001246988 0.0288853 -0.02750301 -0.001246988 0.01658421 -0.01987266 0.001246988 0.01658421 -0.01987266 -0.001246988 0.01936602 -0.01711088 0.001246988 0.01936602 -0.01711088 -0.001246988 0.01064378 -0.01584881 -0.001246988 0.01538521 -0.01114153 -0.001246988 0.01538521 -0.01114153 0.001246988 0.01064378 -0.01584881 0.001246988 -0.01349288 -0.003098845 0.001246988 -0.002614974 -0.01389831 0.001246988 -0.002614974 -0.01389831 -0.001246988 -0.01349288 -0.003098845 -0.001246988 -0.0288853 -0.02750301 0.001246988 -0.0288853 -0.02750301 -0.001246988 -0.0269072 -0.02946692 -0.001246988 -0.0269072 -0.02946692 0.001246988 -0.01658421 -0.01987266 0.001246988 -0.01658421 -0.01987266 -0.001246988 -0.01936602 -0.01711088 0.001246988 -0.01936602 -0.01711088 -0.001246988 -0.01064378 -0.01584881 -0.001246988 -0.01538521 -0.01114153 -0.001246988 -0.01538521 -0.01114153 0.001246988 -0.01064378 -0.01584881 0.001246988 -0.01551216 0.004768252 0.001246988 -0.0129494 0.006718754 0.001246988 -0.008020222 0.0102784 0.001246988 -0.003097176 0.01383805 0.001246988 -0.003097176 0.01383805 -0.001246988 -0.01551216 0.004768252 -0.001246988 0.006261169 0.0102784 0.001246988 0.006261169 0.0102784 -0.001246988 0.002675712 0.01383805 -0.001246988 0.002675712 0.01383805 0.001246988 0.01824802 0.001543164 0.001246988 0.01824802 0 0.001246988 0.01824802 0 -0.001246988 0.01824802 0.001543164 -0.001246988 -0.01551216 0 0.001246988 -0.01551216 0 -0.001246988 -0.01551216 0.001327097 0.001246988 -0.01551216 0.001327097 -0.001246988 0.0134322 0.003159105 0.001246988 0.0134322 0.003159105 -0.001246988 0.009846687 0.006718754 -0.001246988 0.009846687 0.006718754 0.001246988 -0.008020222 -0.0102784 0.001246988 -0.0129494 -0.006718754 0.001246988 -0.01551216 -0.004768252 0.001246988 -0.01551216 -0.004768252 -0.001246988 -0.003097176 -0.01383805 -0.001246988 -0.003097176 -0.01383805 0.001246988 0.006261169 -0.0102784 0.001246988 0.002675712 -0.01383805 0.001246988 0.002675712 -0.01383805 -0.001246988 0.006261169 -0.0102784 -0.001246988 0.01824802 -0.001543164 0.001246988 0.01824802 -0.001543164 -0.001246988 -0.01551216 -0.001327097 0.001246988 -0.01551216 -0.001327097 -0.001246988 0.0134322 -0.003159105 0.001246988 0.009846687 -0.006718754 0.001246988 0.009846687 -0.006718754 -0.001246988 0.0134322 -0.003159105 -0.001246988 -0.00999999 0.00999999 0.001311063 -0.00999999 0.01199996 0.001311063 -0.00999999 0.01199996 0.003311097 -0.00999999 0.00999999 0.003311097 0.00999999 0.01199996 0.001311063 0.00999999 0.01199996 0.003311097 0.00999999 0.00999999 0.001311063 0.00999999 0.00999999 0.003311097 -0.00999999 -0.00999999 0.001311063 -0.00999999 -0.00999999 0.003311097 -0.00999999 -0.01199996 0.003311097 -0.00999999 -0.01199996 0.001311063 0.00999999 -0.01199996 0.003311097 0.00999999 -0.01199996 0.001311063 0.00999999 -0.00999999 0.003311097 0.00999999 -0.00999999 0.001311063 -0.01551216 0.004768252 0.001246988 -0.0129494 0.006718754 0.001246988 -0.008020222 0.0102784 0.001246988 -0.01551216 0.004768252 -0.001246988 0.006261169 0.0102784 0.001246988 0.006261169 0.0102784 -0.001246988 0.01824802 0.001543164 0.001246988 0.01824802 0 0.001246988 0.01824802 0 -0.001246988 0.01824802 0.001543164 -0.001246988 -0.01551216 0 0.001246988 -0.01551216 0 -0.001246988 -0.01551216 0.001327097 0.001246988 -0.01551216 0.001327097 -0.001246988 0.0134322 0.003159105 0.001246988 0.0134322 0.003159105 -0.001246988 0.009846687 0.006718754 -0.001246988 0.009846687 0.006718754 0.001246988 -0.008020222 -0.0102784 0.001246988 -0.0129494 -0.006718754 0.001246988 -0.01551216 -0.004768252 0.001246988 -0.01551216 -0.004768252 -0.001246988 -0.003097176 -0.01383805 -0.001246988 -0.003097176 -0.01383805 0.001246988 0.006261169 -0.0102784 0.001246988 0.002675712 -0.01383805 0.001246988 0.002675712 -0.01383805 -0.001246988 0.006261169 -0.0102784 -0.001246988 0.01824802 -0.001543164 0.001246988 0.01824802 -0.001543164 -0.001246988 -0.01551216 -0.001327097 0.001246988 -0.01551216 -0.001327097 -0.001246988 0.0134322 -0.003159105 0.001246988 0.009846687 -0.006718754 0.001246988 0.009846687 -0.006718754 -0.001246988 0.0134322 -0.003159105 -0.001246988 -0.00999999 0.00999999 0.001311063 -0.00999999 0.00999999 0.003311097 -0.00999999 0.01199996 0.003311097 0.00999999 0.01199996 0.003311097 0.00999999 0.00999999 0.003311097 0.00999999 0.00999999 0.001311063 -0.00999999 -0.00999999 0.001311063 -0.00999999 -0.01199996 0.001311063 -0.00999999 -0.01199996 0.003311097 -0.00999999 -0.00999999 0.003311097 0.00999999 -0.01199996 0.001311063 0.00999999 -0.01199996 0.003311097 0.00999999 -0.00999999 0.001311063 0.00999999 -0.00999999 0.003311097 + + + + + + + + + + -0.7045438 -0.7096605 0 -0.7045438 -0.7096605 0 0.7045443 0.70966 0 0.7045433 0.7096611 0 -0.6807795 0.7324885 0 -0.6807794 0.7324886 0 0 0 1 0 0 1 0.7373957 -0.6754611 0 0.7373957 -0.675461 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.8319734 -0.5548156 0 0.8319732 -0.5548159 0 0 0 1 0 0 1 -0.5608213 0.827937 0 -0.5608218 0.8279366 0 -0.2360691 0.9717363 0 -0.236069 0.9717363 0 0 0 1 0 0 1 0.9734192 -0.229031 0 0.9734191 -0.2290314 0 0 0 -1 0.7045438 -0.7096605 0 0.7045439 -0.7096605 0 -0.7045432 0.7096611 0 -0.7045443 0.7096601 0 0.6807794 0.7324886 0 0.6807794 0.7324885 0 0 0 1 0 0 1 -0.7373958 -0.6754609 0 -0.7373957 -0.6754611 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.8319733 -0.5548158 0 -0.831973 -0.5548161 0 0 0 1 0 0 1 0.5608217 0.8279367 0 0.5608213 0.827937 0 0.2360689 0.9717363 0 0 0 1 0 0 1 -0.9734192 -0.2290311 0 -0.9734191 -0.2290314 0 0 0 -1 0 0 -1 -0.7045438 0.7096605 0 0.7045429 -0.7096614 0 0.704544 -0.7096604 0 -0.6807792 -0.7324887 0 -0.6807792 -0.7324886 0 0 0 1 0 0 1 0.7373957 0.6754611 0 0.7373955 0.6754612 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0.8319733 0.5548158 0 0.8319734 0.5548156 0 0 0 1 0 0 1 -0.5608217 -0.8279367 0 -0.5608213 -0.827937 0 -0.2360693 -0.9717363 0 -0.2360693 -0.9717363 0 0 0 1 0 0 1 0.9734191 0.2290314 0 0.9734192 0.2290311 0 0 0 -1 0.7045438 0.7096605 0 0.7045438 0.7096605 0 -0.7045439 -0.7096604 0 0.6807792 -0.7324886 0 0.6807791 -0.7324888 0 0 0 1 0 0 1 -0.7373958 0.6754609 0 -0.7373956 0.6754612 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 -0.8319734 0.5548156 0 -0.8319731 0.5548161 0 0 0 1 0 0 1 0.5608215 -0.8279368 0 0.5608215 -0.8279367 0 0.2360691 -0.9717363 0 0.236069 -0.9717363 0 -0.973419 0.2290314 0 -0.9734191 0.2290311 0 -3.70063e-6 1.16742e-6 -1 -0.5859354 0.8103578 0 -0.589901 0.8074757 0 -0.5923686 0.8054254 -0.01973915 0.7045438 0.7096606 0 1 0 0 0 -1 0 0 0 1 0 0 -1 0.7045436 0.7096607 0 0 0 1 0 0 1 -1 0 0 -1 -1.10705e-6 0 0 0 -1 0 0 1 0 0 1 0.3181167 0.9480516 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 0 0 1 -1.01069e-6 0.7045438 0.7096605 0 0.704544 0.7096604 0 -9.25141e-7 -1.1674e-6 -1 -0.589901 -0.8074756 0 -0.5859354 -0.8103578 4.80206e-7 -0.5923684 -0.8054255 -0.01973885 0.7045437 -0.7096606 0 0.7045438 -0.7096605 0 1 1.10391e-6 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0.7045435 -0.7096607 0 0 0 1 0 0 1 0 0 -1 0 0 -1 0 0 1 0 0 1 0.3181167 -0.9480516 0 0 0 -1 0 0 -1 0 0 -1 -1.85029e-6 0 -1 -0.5859355 0.8103576 0 -0.5899011 0.8074756 0 -0.5923686 0.8054254 -0.01973855 0.7045439 0.7096605 0 0 0 1 0 0 -1 0 0 1 -1 -2.19824e-6 0 -1 1.09118e-6 0 0 0 -1 0 0 1 0 0 -1 0 0 -1 0 0 -1 -2.7754e-6 -1.16739e-6 -1 -0.5899009 -0.8074757 0 -0.5859354 -0.8103578 4.80206e-7 -0.5923684 -0.8054254 -0.01973885 0.7045438 -0.7096606 0 0.7045438 -0.7096605 0 0 0 -1 0.7045436 -0.7096608 0 0.7045437 -0.7096607 0 0 0 1 0 0 -1 0 0 1 0 0 1 0.3181168 -0.9480515 0 0 0 -1 0 0 -1 0 0 -1 0.7045437 -0.7096607 0 + + + + + + + + + + + + + + +

0 0 1 0 2 0 0 1 2 1 3 1 4 2 5 2 6 2 4 3 6 3 7 3 8 4 7 4 6 4 8 5 6 5 9 5 10 6 4 6 7 6 10 7 7 7 8 7 11 8 5 8 4 8 11 9 4 9 10 9 9 10 6 10 5 10 9 11 5 11 11 11 12 12 9 12 11 12 12 13 11 13 13 13 13 14 11 14 10 14 13 15 10 15 14 15 14 16 10 16 8 16 14 17 8 17 15 17 15 18 8 18 9 18 15 19 9 19 12 19 1 20 15 20 12 20 1 21 12 21 2 21 0 22 14 22 15 22 0 23 15 23 1 23 3 24 13 24 14 24 3 25 14 25 0 25 2 26 12 26 13 26 2 26 13 26 3 26 16 27 17 27 18 27 16 28 18 28 19 28 20 29 21 29 22 29 20 30 22 30 23 30 24 31 25 31 22 31 24 32 22 32 21 32 26 33 24 33 21 33 26 34 21 34 20 34 27 35 26 35 20 35 27 36 20 36 23 36 25 37 27 37 23 37 25 38 23 38 22 38 28 39 29 39 27 39 28 40 27 40 25 40 29 41 30 41 26 41 29 42 26 42 27 42 30 43 31 43 24 43 30 44 24 44 26 44 31 45 28 45 25 45 31 46 25 46 24 46 19 47 18 47 28 47 19 47 28 47 31 47 16 48 19 48 31 48 16 49 31 49 30 49 17 50 16 50 30 50 17 51 30 51 29 51 18 52 17 52 29 52 18 53 29 53 28 53 32 54 33 54 34 54 32 54 34 54 35 54 36 55 37 55 38 55 36 56 38 56 39 56 40 57 41 57 38 57 40 58 38 58 37 58 42 59 40 59 37 59 42 60 37 60 36 60 43 61 42 61 36 61 43 62 36 62 39 62 41 63 43 63 39 63 41 64 39 64 38 64 44 65 45 65 43 65 44 66 43 66 41 66 45 67 46 67 42 67 45 68 42 68 43 68 46 69 47 69 40 69 46 70 40 70 42 70 47 71 44 71 41 71 47 72 41 72 40 72 35 73 34 73 44 73 35 74 44 74 47 74 32 75 35 75 47 75 32 76 47 76 46 76 33 77 32 77 46 77 33 78 46 78 45 78 34 26 33 26 45 26 34 79 45 79 44 79 48 80 49 80 50 80 48 81 50 81 51 81 52 82 53 82 54 82 52 82 54 82 55 82 56 83 55 83 54 83 56 84 54 84 57 84 58 85 52 85 55 85 58 86 55 86 56 86 59 87 53 87 52 87 59 88 52 88 58 88 57 89 54 89 53 89 57 90 53 90 59 90 60 91 57 91 59 91 60 92 59 92 61 92 61 93 59 93 58 93 61 94 58 94 62 94 62 95 58 95 56 95 62 96 56 96 63 96 63 97 56 97 57 97 63 98 57 98 60 98 49 99 63 99 60 99 49 100 60 100 50 100 48 49 62 49 63 49 48 23 63 23 49 23 51 101 61 101 62 101 51 102 62 102 48 102 50 79 60 79 61 79 50 26 61 26 51 26 64 103 65 103 66 103 66 104 67 104 68 104 68 105 69 105 64 105 66 106 68 106 64 106 70 81 71 81 72 81 70 107 72 107 73 107 74 108 75 108 76 108 74 108 76 108 77 108 75 109 78 109 79 109 75 109 79 109 76 109 80 110 78 110 75 110 80 16 75 16 74 16 77 26 76 26 79 26 77 111 79 111 81 111 82 107 83 107 84 107 82 112 84 112 85 112 64 113 82 113 85 113 64 114 85 114 65 114 65 16 85 16 70 16 65 16 70 16 66 16 80 115 64 115 69 115 80 115 69 115 81 115 78 115 80 115 81 115 78 116 81 116 79 116 83 117 77 117 81 117 83 26 81 26 69 26 64 118 80 118 74 118 64 119 74 119 82 119 82 120 74 120 77 120 82 120 77 120 83 120 84 121 83 121 69 121 69 122 68 122 72 122 71 123 84 123 69 123 69 124 72 124 71 124 66 16 70 16 73 16 66 16 73 16 67 16 67 125 73 125 72 125 67 126 72 126 68 126 85 127 84 127 71 127 85 128 71 128 70 128 86 129 87 129 88 129 88 130 89 130 90 130 90 131 91 131 86 131 88 132 90 132 86 132 92 133 93 133 94 133 92 134 94 134 95 134 96 135 97 135 76 135 96 108 76 108 75 108 98 136 96 136 75 136 98 137 75 137 78 137 97 138 99 138 79 138 97 139 79 139 76 139 100 140 101 140 102 140 100 140 102 140 103 140 88 141 87 141 101 141 88 142 101 142 100 142 87 16 86 16 92 16 87 16 92 16 101 16 98 115 99 115 89 115 98 115 89 115 88 115 78 115 79 115 99 115 78 115 99 115 98 115 103 143 89 143 99 143 103 144 99 144 97 144 88 145 100 145 96 145 88 146 96 146 98 146 100 147 103 147 97 147 100 147 97 147 96 147 89 148 103 148 102 148 95 26 94 26 90 26 89 149 102 149 95 149 95 150 90 150 89 150 86 16 91 16 93 16 86 16 93 16 92 16 91 109 90 109 94 109 91 109 94 109 93 109 101 134 92 134 95 134 101 133 95 133 102 133 104 108 105 108 106 108 104 108 106 108 107 108 105 109 108 109 109 109 105 109 109 109 106 109 108 115 110 115 111 115 108 115 111 115 109 115 110 125 104 125 107 125 110 125 107 125 111 125 105 16 104 16 110 16 105 16 110 16 108 16 109 26 111 26 107 26 109 26 107 26 106 26 112 108 113 108 114 108 112 108 114 108 115 108 115 125 114 125 116 125 115 125 116 125 117 125 117 115 116 115 118 115 117 115 118 115 119 115 119 109 118 109 113 109 119 109 113 109 112 109 115 16 117 16 119 16 115 16 119 16 112 16 116 26 114 26 113 26 116 26 113 26 118 26 120 151 121 151 122 151 122 152 67 152 68 152 68 153 123 153 120 153 122 154 68 154 120 154 124 128 125 128 72 128 124 155 72 155 73 155 126 108 127 108 128 108 126 108 128 108 129 108 127 109 130 109 131 109 127 109 131 109 128 109 132 156 130 156 127 156 132 16 127 16 126 16 129 26 128 26 131 26 129 157 131 157 133 157 134 107 135 107 136 107 134 112 136 112 137 112 120 158 134 158 137 158 120 16 137 16 121 16 121 16 137 16 124 16 121 16 124 16 122 16 132 115 120 115 123 115 132 115 123 115 133 115 130 159 132 159 133 159 130 160 133 160 131 160 135 161 129 161 133 161 135 26 133 26 123 26 120 162 132 162 126 162 120 16 126 16 134 16 134 120 126 120 129 120 134 120 129 120 135 120 136 163 135 163 123 163 123 26 68 26 72 26 125 164 136 164 123 164 123 165 72 165 125 165 122 16 124 16 73 16 122 16 73 16 67 16 137 107 136 107 125 107 137 155 125 155 124 155 138 166 139 166 140 166 140 167 141 167 142 167 142 168 143 168 138 168 140 169 142 169 138 169 144 170 145 170 146 170 144 171 146 171 147 171 148 108 149 108 128 108 148 108 128 108 127 108 150 16 148 16 127 16 150 16 127 16 130 16 149 172 151 172 131 172 149 26 131 26 128 26 152 173 153 173 154 173 152 174 154 174 155 174 140 141 139 141 153 141 140 175 153 175 152 175 139 16 138 16 144 16 139 16 144 16 153 16 150 115 151 115 141 115 150 115 141 115 140 115 130 115 131 115 151 115 130 115 151 115 150 115 155 26 141 26 151 26 155 176 151 176 149 176 140 177 152 177 148 177 140 178 148 178 150 178 152 179 155 179 149 179 152 179 149 179 148 179 141 180 155 180 154 180 147 26 146 26 142 26 141 181 154 181 147 181 147 182 142 182 141 182 138 16 143 16 145 16 138 16 145 16 144 16 143 109 142 109 146 109 143 109 146 109 145 109 153 27 144 27 147 27 153 183 147 183 154 183 156 115 157 115 158 115 156 115 158 115 105 115 105 125 158 125 159 125 105 125 159 125 108 125 108 108 159 108 160 108 108 108 160 108 161 108 161 109 160 109 157 109 161 109 157 109 156 109 105 26 108 26 161 26 105 26 161 26 156 26 159 16 158 16 157 16 159 16 157 16 160 16 162 115 163 115 164 115 162 115 164 115 165 115 163 109 166 109 167 109 163 109 167 109 164 109 166 108 168 108 169 108 166 108 169 108 167 108 168 125 162 125 165 125 168 125 165 125 169 125 163 26 162 26 168 26 163 26 168 26 166 26 167 16 169 16 165 16 167 16 165 16 164 16

+
+
+
+ + + + 0 0.003999948 -0.007499992 0 0.003999948 0.007499992 0.001530706 0.003695487 -0.007499992 0.001530706 0.003695487 0.007499992 0.002828419 0.002828419 -0.007499992 0.002828419 0.002828419 0.007499992 0.003695487 0.001530706 -0.007499992 0.003695487 0.001530706 0.007499992 0.003999948 0 -0.007499992 0.003999948 0 0.007499992 0.003695487 -0.001530706 -0.007499992 0.003695487 -0.001530706 0.007499992 0.002828419 -0.002828419 -0.007499992 0.002828419 -0.002828419 0.007499992 0.001530706 -0.003695487 -0.007499992 0.001530706 -0.003695487 0.007499992 0 -0.003999948 -0.007499992 0 -0.003999948 0.007499992 -0.001530706 -0.003695487 -0.007499992 -0.001530706 -0.003695487 0.007499992 -0.002828419 -0.002828419 -0.007499992 -0.002828419 -0.002828419 0.007499992 -0.003695487 -0.001530706 -0.007499992 -0.003695487 -0.001530706 0.007499992 -0.003999948 0 -0.007499992 -0.003999948 0 0.007499992 -0.003695487 0.001530706 -0.007499992 -0.003695487 0.001530706 0.007499992 -0.002828419 0.002828419 -0.007499992 -0.002828419 0.002828419 0.007499992 -0.001530706 0.003695487 -0.007499992 -0.001530706 0.003695487 0.007499992 -0.08789849 0.003999948 -0.007499992 -0.08789849 0.003999948 0.007499992 -0.08942919 0.003695487 -0.007499992 -0.08942919 0.003695487 0.007499992 -0.09072691 0.002828419 -0.007499992 -0.09072691 0.002828419 0.007499992 -0.09159398 0.001530706 -0.007499992 -0.09159398 0.001530706 0.007499992 -0.0918985 0 -0.007499992 -0.0918985 0 0.007499992 -0.09159398 -0.001530706 -0.007499992 -0.09159398 -0.001530706 0.007499992 -0.09072691 -0.002828419 -0.007499992 -0.09072691 -0.002828419 0.007499992 -0.08942919 -0.003695487 -0.007499992 -0.08942919 -0.003695487 0.007499992 -0.08789849 -0.003999948 -0.007499992 -0.08789849 -0.003999948 0.007499992 -0.08636772 -0.003695487 -0.007499992 -0.08636772 -0.003695487 0.007499992 -0.08507007 -0.002828419 -0.007499992 -0.08507007 -0.002828419 0.007499992 -0.08420294 -0.001530706 -0.007499992 -0.08420294 -0.001530706 0.007499992 -0.08389848 0 -0.007499992 -0.08389848 0 0.007499992 -0.08420294 0.001530706 -0.007499992 -0.08420294 0.001530706 0.007499992 -0.08507007 0.002828419 -0.007499992 -0.08507007 0.002828419 0.007499992 -0.08636772 0.003695487 -0.007499992 -0.08636772 0.003695487 0.007499992 0 -0.0918985 -0.007499992 0 -0.0918985 0.007499992 0.001530706 -0.09159398 -0.007499992 0.001530706 -0.09159398 0.007499992 0.002828419 -0.09072691 -0.007499992 0.002828419 -0.09072691 0.007499992 0.003695487 -0.08942919 -0.007499992 0.003695487 -0.08942919 0.007499992 0.003999948 -0.08789849 -0.007499992 0.003999948 -0.08789849 0.007499992 0.003695487 -0.08636772 -0.007499992 0.003695487 -0.08636772 0.007499992 0.002828419 -0.08507007 -0.007499992 0.002828419 -0.08507007 0.007499992 0.001530706 -0.08420294 -0.007499992 0.001530706 -0.08420294 0.007499992 0 -0.08389848 -0.007499992 0 -0.08389848 0.007499992 -0.001530706 -0.08420294 -0.007499992 -0.001530706 -0.08420294 0.007499992 -0.002828419 -0.08507007 -0.007499992 -0.002828419 -0.08507007 0.007499992 -0.003695487 -0.08636772 -0.007499992 -0.003695487 -0.08636772 0.007499992 -0.003999948 -0.08789849 -0.007499992 -0.003999948 -0.08789849 0.007499992 -0.003695487 -0.08942919 -0.007499992 -0.003695487 -0.08942919 0.007499992 -0.002828419 -0.09072691 -0.007499992 -0.002828419 -0.09072691 0.007499992 -0.001530706 -0.09159398 -0.007499992 -0.001530706 -0.09159398 0.007499992 -0.08789849 -0.0918985 -0.007499992 -0.08789849 -0.0918985 0.007499992 -0.08942919 -0.09159398 -0.007499992 -0.08942919 -0.09159398 0.007499992 -0.09072691 -0.09072691 -0.007499992 -0.09072691 -0.09072691 0.007499992 -0.09159398 -0.08942919 -0.007499992 -0.09159398 -0.08942919 0.007499992 -0.09189844 -0.08789849 -0.007499992 -0.09189844 -0.08789849 0.007499992 -0.09159398 -0.08636772 -0.007499992 -0.09159398 -0.08636772 0.007499992 -0.09072691 -0.08507007 -0.007499992 -0.09072691 -0.08507007 0.007499992 -0.08942919 -0.08420294 -0.007499992 -0.08942919 -0.08420294 0.007499992 -0.08789849 -0.08389848 -0.007499992 -0.08789849 -0.08389848 0.007499992 -0.08636772 -0.08420294 -0.007499992 -0.08636772 -0.08420294 0.007499992 -0.08507001 -0.08507007 -0.007499992 -0.08507001 -0.08507007 0.007499992 -0.08420294 -0.08636772 -0.007499992 -0.08420294 -0.08636772 0.007499992 -0.08389848 -0.08789849 -0.007499992 -0.08389848 -0.08789849 0.007499992 -0.08420294 -0.08942919 -0.007499992 -0.08420294 -0.08942919 0.007499992 -0.08507001 -0.09072691 -0.007499992 -0.08507001 -0.09072691 0.007499992 -0.08636772 -0.09159398 -0.007499992 -0.08636772 -0.09159398 0.007499992 + + + + + + + + + + 0.1950904 0.9807854 0 0.5555704 0.8314697 0 0.8314695 0.5555704 0 0.9807853 0.1950905 0 0.9807854 -0.1950903 0 0.8314695 -0.5555704 0 0.5555704 -0.8314697 0 0.1950903 -0.9807854 0 -0.1950904 -0.9807853 0 -0.5555703 -0.8314696 0 -0.8314693 -0.5555707 0 -0.9807853 -0.1950905 0 -0.9807854 0.1950902 0 -0.8314696 0.5555703 0 0 0 1 -0.5555704 0.8314695 0 -0.1950902 0.9807853 0 3.21555e-7 0 -1 -0.1950899 0.9807854 0 -0.5555716 0.8314688 0 -0.8314738 0.5555639 0 -0.9807836 0.1950989 0 -0.9807875 -0.1950799 0 -0.8314647 -0.5555776 0 -0.5555716 -0.8314688 0 -0.1950899 -0.9807854 0 0.1950899 -0.9807854 0 0.555576 -0.8314658 0 0.8314738 -0.5555641 0 0.9807856 -0.1950893 0 0.9807856 0.1950893 0 0.8314645 0.555578 0 -3.21555e-7 0 1 0.5555672 0.8314718 0 0.1950898 0.9807854 0 0 0 -1 0.1950909 -0.9807853 0 0.5555703 -0.8314696 0 0.831469 -0.5555712 0 0.9807854 -0.1950899 0 0.9807854 0.1950899 0 0.8314687 0.5555716 0 0.5555704 0.8314695 0 0.1950908 0.9807852 0 -0.195091 0.9807852 0 -0.5555705 0.8314695 0 -0.8314687 0.5555716 0 -0.9807854 0.1950899 0 -0.9807854 -0.1950899 0 -0.8314692 -0.555571 0 -2.27374e-7 0 1 -0.5555703 -0.8314696 0 -0.1950909 -0.9807853 0 0 0 -1 -0.1950859 -0.9807862 0 -0.5555715 -0.8314688 0 -0.83147 -0.5555697 0 -0.9807856 -0.1950891 0 -0.9807873 0.1950803 0 -0.8314655 0.5555766 0 -0.5555762 0.8314658 0 -0.1950859 0.9807862 0 0.1950859 0.9807862 0 0.5555715 0.8314688 0 0.8314746 0.5555627 0 0.9807856 0.1950891 0 0.9807835 -0.1950995 0 0.83147 -0.5555697 0 -5.48928e-7 0 1 0.5555669 -0.8314719 0 0.1950859 -0.9807862 0 0.8314697 0.5555703 0 0.9807853 0.1950902 0 0.5555704 -0.8314695 0 -0.8314696 -0.5555703 0 -0.9807854 -0.1950902 0 -0.9807852 0.1950908 0 1.95137e-6 0 1 1.95137e-6 0 1 -1.95137e-6 0 1 -0.5555704 0.8314696 0 -1.95137e-6 0 -1 -3.90274e-6 0 -1 1.95137e-6 0 -1 1.95137e-6 0 -1 3.90274e-6 0 -1 -4.54747e-7 0 -1 -0.1950899 0.9807854 0 -0.5555715 0.8314688 0 -0.8314647 0.5555778 0 -0.9807875 0.1950798 0 -0.9807836 -0.1950989 0 -0.8314738 -0.5555639 0 -0.1950899 -0.9807854 0 0.1950899 -0.9807854 0 0.5555669 -0.831472 0 0.8314646 -0.5555779 0 0.8314736 0.5555643 0 9.75681e-7 0 1 -7.41687e-7 0 1 9.75679e-7 0 1 -9.75679e-7 0 1 4.54747e-7 0 1 0.5555763 0.8314656 0 0.1950898 0.9807854 0 7.41687e-7 0 -1 -1.95136e-6 0 -1 -1.48338e-6 0 -1 1.95136e-6 0 -1 -2.27374e-7 0 -1 0.195091 -0.9807853 0 0.8314689 -0.5555714 0 0.9807854 -0.1950899 0 0.9807855 0.1950896 0 0.8314689 0.5555712 0 0.1950908 0.9807852 0 -0.195091 0.9807852 0 -0.5555704 0.8314697 0 -0.8314689 0.5555712 0 -0.9807854 0.1950899 0 -0.9807853 -0.1950902 0 -0.8314691 -0.555571 0 -1.95136e-6 0 1 -1.95133e-6 0 1 -4.87839e-7 0 1 1.95133e-6 0 1 1.95136e-6 0 1 -0.5555702 -0.8314698 0 -0.195091 -0.9807853 0 -1.95142e-6 0 -1 1.95142e-6 0 -1 9.75709e-7 0 -1 -0.5555762 -0.8314658 0 -0.8314655 -0.5555766 0 -0.9807875 -0.1950795 0 -0.83147 0.5555697 0 0.5555669 0.8314719 0 0.83147 0.5555697 0 0.9807837 0.1950986 0 0.8314746 -0.5555627 0 0.5555715 -0.8314688 0 9.75724e-7 0 -1 -1.95132e-6 0 -1 -9.75633e-7 0 -1 + + + + + + + + + + 1 1 0.9375 0.5 1 0.5 0.9375 1 0.875 0.5 0.9375 0.5 0.875 1 0.8125 0.5 0.875 0.5 0.8125 1 0.75 0.5 0.8125 0.5 0.75 1 0.6875 0.5 0.75 0.5 0.6875 1 0.625 0.5 0.6875 0.5 0.625 1 0.5625 0.5 0.625 0.5 0.5625 1 0.5 0.5 0.5625 0.5 0.5 1 0.4375 0.5 0.5 0.5 0.4375 1 0.375 0.5 0.4375 0.5 0.375 1 0.3125 0.5 0.375 0.5 0.3125 1 0.25 0.5 0.3125 0.5 0.25 1 0.1875 0.5 0.25 0.5 0.1875 1 0.125 0.5 0.1875 0.5 0.08029437 0.08029437 0.4197056 0.08029437 0.4197056 0.4197056 0.125 1 0.0625 0.5 0.125 0.5 0.0625 1 0 0.5 0.0625 0.5 0.5282689 0.341844 0.658156 0.4717311 0.841844 0.02826887 0.9375 0.5 1 1 1 0.5 0.875 0.5 0.9375 1 0.9375 0.5 0.8125 0.5 0.875 1 0.875 0.5 0.75 0.5 0.8125 1 0.8125 0.5 0.6875 0.5 0.75 1 0.75 0.5 0.625 0.5 0.6875 1 0.6875 0.5 0.5625 0.5 0.625 1 0.625 0.5 0.5 0.5 0.5625 1 0.5625 0.5 0.4375 0.5 0.5 1 0.5 0.5 0.375 0.5 0.4375 1 0.4375 0.5 0.3125 0.5 0.375 1 0.375 0.5 0.25 0.5 0.3125 1 0.3125 0.5 0.1875 0.5 0.25 1 0.25 0.5 0.125 0.5 0.1875 1 0.1875 0.5 0.08029431 0.4197056 0.25 0.49 0.25 0.00999999 0.0625 0.5 0.125 1 0.125 0.5 0 0.5 0.0625 1 0.0625 0.5 0.5282689 0.341844 0.658156 0.02826887 0.9717311 0.1581559 0.9375 0.5 1 1 1 0.5 0.875 0.5 0.9375 1 0.9375 0.5 0.8125 0.5 0.875 1 0.875 0.5 0.75 0.5 0.8125 1 0.8125 0.5 0.6875 0.5 0.75 1 0.75 0.5 0.625 0.5 0.6875 1 0.6875 0.5 0.5625 0.5 0.625 1 0.625 0.5 0.5 0.5 0.5625 1 0.5625 0.5 0.4375 0.5 0.5 1 0.5 0.5 0.375 0.5 0.4375 1 0.4375 0.5 0.3125 0.5 0.375 1 0.375 0.5 0.25 0.5 0.3125 1 0.3125 0.5 0.1875 0.5 0.25 1 0.25 0.5 0.125 0.5 0.1875 1 0.1875 0.5 0.08029437 0.08029437 0.00999999 0.25 0.25 0.49 0.0625 0.5 0.125 1 0.125 0.5 0 0.5 0.0625 1 0.0625 0.5 0.841844 0.02826887 0.9717311 0.1581559 0.841844 0.4717311 1 1 0.9375 0.5 1 0.5 0.9375 1 0.875 0.5 0.9375 0.5 0.875 1 0.8125 0.5 0.875 0.5 0.8125 1 0.75 0.5 0.8125 0.5 0.75 1 0.6875 0.5 0.75 0.5 0.6875 1 0.625 0.5 0.6875 0.5 0.625 1 0.5625 0.5 0.625 0.5 0.5625 1 0.5 0.5 0.5625 0.5 0.5 1 0.4375 0.5 0.5 0.5 0.4375 1 0.375 0.5 0.4375 0.5 0.375 1 0.3125 0.5 0.375 0.5 0.3125 1 0.25 0.5 0.3125 0.5 0.25 1 0.1875 0.5 0.25 0.5 0.1875 1 0.125 0.5 0.1875 0.5 0.4197056 0.08029437 0.49 0.25 0.4197056 0.4197056 0.125 1 0.0625 0.5 0.125 0.5 0.0625 1 0 0.5 0.0625 0.5 0.9717311 0.341844 0.841844 0.02826887 0.5282689 0.1581559 1 1 0.9375 1 0.9375 0.5 0.9375 1 0.875 1 0.875 0.5 0.875 1 0.8125 1 0.8125 0.5 0.8125 1 0.75 1 0.75 0.5 0.75 1 0.6875 1 0.6875 0.5 0.6875 1 0.625 1 0.625 0.5 0.625 1 0.5625 1 0.5625 0.5 0.5625 1 0.5 1 0.5 0.5 0.5 1 0.4375 1 0.4375 0.5 0.4375 1 0.375 1 0.375 0.5 0.375 1 0.3125 1 0.3125 0.5 0.3125 1 0.25 1 0.25 0.5 0.25 1 0.1875 1 0.1875 0.5 0.1875 1 0.125 1 0.125 0.5 0.4197056 0.4197056 0.341844 0.4717311 0.25 0.49 0.25 0.49 0.1581559 0.4717311 0.08029431 0.4197056 0.08029431 0.4197056 0.02826893 0.341844 0.00999999 0.25 0.00999999 0.25 0.02826887 0.1581559 0.08029437 0.08029437 0.08029437 0.08029437 0.1581559 0.02826887 0.4197056 0.08029437 0.1581559 0.02826887 0.25 0.00999999 0.4197056 0.08029437 0.25 0.00999999 0.341844 0.02826887 0.4197056 0.08029437 0.4197056 0.08029437 0.4717311 0.1581559 0.49 0.25 0.49 0.25 0.4717311 0.341844 0.4197056 0.08029437 0.4717311 0.341844 0.4197056 0.4197056 0.4197056 0.08029437 0.4197056 0.4197056 0.25 0.49 0.08029437 0.08029437 0.25 0.49 0.08029431 0.4197056 0.08029437 0.08029437 0.08029431 0.4197056 0.00999999 0.25 0.08029437 0.08029437 0.125 1 0.0625 1 0.0625 0.5 0.0625 1 0 1 0 0.5 0.658156 0.4717311 0.75 0.49 0.841844 0.4717311 0.841844 0.4717311 0.9197056 0.4197056 0.9717311 0.341844 0.9717311 0.341844 0.99 0.25 0.9717311 0.1581559 0.9717311 0.1581559 0.9197056 0.08029437 0.9717311 0.341844 0.9197056 0.08029437 0.841844 0.02826887 0.9717311 0.341844 0.841844 0.02826887 0.75 0.00999999 0.658156 0.02826887 0.658156 0.02826887 0.5802944 0.08029437 0.5282689 0.1581559 0.5282689 0.1581559 0.51 0.25 0.5282689 0.341844 0.5282689 0.341844 0.5802944 0.4197056 0.658156 0.4717311 0.658156 0.4717311 0.841844 0.4717311 0.841844 0.02826887 0.841844 0.4717311 0.9717311 0.341844 0.841844 0.02826887 0.841844 0.02826887 0.658156 0.02826887 0.5282689 0.1581559 0.5282689 0.1581559 0.5282689 0.341844 0.841844 0.02826887 0.9375 0.5 0.9375 1 1 1 0.875 0.5 0.875 1 0.9375 1 0.8125 0.5 0.8125 1 0.875 1 0.75 0.5 0.75 1 0.8125 1 0.6875 0.5 0.6875 1 0.75 1 0.625 0.5 0.625 1 0.6875 1 0.5625 0.5 0.5625 1 0.625 1 0.5 0.5 0.5 1 0.5625 1 0.4375 0.5 0.4375 1 0.5 1 0.375 0.5 0.375 1 0.4375 1 0.3125 0.5 0.3125 1 0.375 1 0.25 0.5 0.25 1 0.3125 1 0.1875 0.5 0.1875 1 0.25 1 0.125 0.5 0.125 1 0.1875 1 0.25 0.49 0.341844 0.4717311 0.4197056 0.4197056 0.4197056 0.4197056 0.4717311 0.341844 0.49 0.25 0.49 0.25 0.4717311 0.1581559 0.25 0.00999999 0.4717311 0.1581559 0.4197056 0.08029437 0.25 0.00999999 0.4197056 0.08029437 0.341844 0.02826887 0.25 0.00999999 0.25 0.00999999 0.1581559 0.02826887 0.08029437 0.08029437 0.08029437 0.08029437 0.02826887 0.1581559 0.00999999 0.25 0.00999999 0.25 0.02826893 0.341844 0.08029431 0.4197056 0.08029431 0.4197056 0.1581559 0.4717311 0.25 0.49 0.25 0.49 0.4197056 0.4197056 0.25 0.00999999 0.4197056 0.4197056 0.49 0.25 0.25 0.00999999 0.25 0.00999999 0.08029437 0.08029437 0.00999999 0.25 0.00999999 0.25 0.08029431 0.4197056 0.25 0.00999999 0.0625 0.5 0.0625 1 0.125 1 0 0.5 0 1 0.0625 1 0.841844 0.4717311 0.75 0.49 0.658156 0.4717311 0.658156 0.4717311 0.5802944 0.4197056 0.841844 0.4717311 0.5802944 0.4197056 0.5282689 0.341844 0.841844 0.4717311 0.5282689 0.341844 0.51 0.25 0.5282689 0.1581559 0.5282689 0.1581559 0.5802944 0.08029437 0.5282689 0.341844 0.5802944 0.08029437 0.658156 0.02826887 0.5282689 0.341844 0.658156 0.02826887 0.75 0.00999999 0.9717311 0.1581559 0.75 0.00999999 0.841844 0.02826887 0.9717311 0.1581559 0.841844 0.02826887 0.9197056 0.08029437 0.9717311 0.1581559 0.9717311 0.1581559 0.99 0.25 0.9717311 0.341844 0.9717311 0.341844 0.9197056 0.4197056 0.9717311 0.1581559 0.9197056 0.4197056 0.841844 0.4717311 0.9717311 0.1581559 0.841844 0.4717311 0.5282689 0.341844 0.9717311 0.1581559 0.9375 0.5 0.9375 1 1 1 0.875 0.5 0.875 1 0.9375 1 0.8125 0.5 0.8125 1 0.875 1 0.75 0.5 0.75 1 0.8125 1 0.6875 0.5 0.6875 1 0.75 1 0.625 0.5 0.625 1 0.6875 1 0.5625 0.5 0.5625 1 0.625 1 0.5 0.5 0.5 1 0.5625 1 0.4375 0.5 0.4375 1 0.5 1 0.375 0.5 0.375 1 0.4375 1 0.3125 0.5 0.3125 1 0.375 1 0.25 0.5 0.25 1 0.3125 1 0.1875 0.5 0.1875 1 0.25 1 0.125 0.5 0.125 1 0.1875 1 0.25 0.49 0.341844 0.4717311 0.49 0.25 0.341844 0.4717311 0.4197056 0.4197056 0.49 0.25 0.4197056 0.4197056 0.4717311 0.341844 0.49 0.25 0.49 0.25 0.4717311 0.1581559 0.4197056 0.08029437 0.4197056 0.08029437 0.341844 0.02826887 0.25 0.00999999 0.25 0.00999999 0.1581559 0.02826887 0.08029437 0.08029437 0.08029437 0.08029437 0.02826887 0.1581559 0.00999999 0.25 0.00999999 0.25 0.02826893 0.341844 0.08029431 0.4197056 0.08029431 0.4197056 0.1581559 0.4717311 0.00999999 0.25 0.1581559 0.4717311 0.25 0.49 0.00999999 0.25 0.49 0.25 0.4197056 0.08029437 0.25 0.49 0.4197056 0.08029437 0.25 0.00999999 0.25 0.49 0.25 0.00999999 0.08029437 0.08029437 0.25 0.49 0.0625 0.5 0.0625 1 0.125 1 0 0.5 0 1 0.0625 1 0.841844 0.4717311 0.75 0.49 0.658156 0.4717311 0.658156 0.4717311 0.5802944 0.4197056 0.5282689 0.341844 0.5282689 0.341844 0.51 0.25 0.5282689 0.1581559 0.5282689 0.1581559 0.5802944 0.08029437 0.5282689 0.341844 0.5802944 0.08029437 0.658156 0.02826887 0.5282689 0.341844 0.658156 0.02826887 0.75 0.00999999 0.841844 0.02826887 0.841844 0.02826887 0.9197056 0.08029437 0.9717311 0.1581559 0.9717311 0.1581559 0.99 0.25 0.841844 0.4717311 0.99 0.25 0.9717311 0.341844 0.841844 0.4717311 0.9717311 0.341844 0.9197056 0.4197056 0.841844 0.4717311 0.841844 0.4717311 0.658156 0.4717311 0.658156 0.02826887 0.658156 0.4717311 0.5282689 0.341844 0.658156 0.02826887 0.658156 0.02826887 0.841844 0.02826887 0.841844 0.4717311 1 1 0.9375 1 0.9375 0.5 0.9375 1 0.875 1 0.875 0.5 0.875 1 0.8125 1 0.8125 0.5 0.8125 1 0.75 1 0.75 0.5 0.75 1 0.6875 1 0.6875 0.5 0.6875 1 0.625 1 0.625 0.5 0.625 1 0.5625 1 0.5625 0.5 0.5625 1 0.5 1 0.5 0.5 0.5 1 0.4375 1 0.4375 0.5 0.4375 1 0.375 1 0.375 0.5 0.375 1 0.3125 1 0.3125 0.5 0.3125 1 0.25 1 0.25 0.5 0.25 1 0.1875 1 0.1875 0.5 0.1875 1 0.125 1 0.125 0.5 0.4197056 0.4197056 0.341844 0.4717311 0.25 0.49 0.25 0.49 0.1581559 0.4717311 0.08029431 0.4197056 0.08029431 0.4197056 0.02826893 0.341844 0.00999999 0.25 0.00999999 0.25 0.02826887 0.1581559 0.08029431 0.4197056 0.02826887 0.1581559 0.08029437 0.08029437 0.08029431 0.4197056 0.08029437 0.08029437 0.1581559 0.02826887 0.25 0.00999999 0.25 0.00999999 0.341844 0.02826887 0.4197056 0.08029437 0.4197056 0.08029437 0.4717311 0.1581559 0.49 0.25 0.49 0.25 0.4717311 0.341844 0.4197056 0.4197056 0.4197056 0.4197056 0.25 0.49 0.08029437 0.08029437 0.25 0.49 0.08029431 0.4197056 0.08029437 0.08029437 0.08029437 0.08029437 0.25 0.00999999 0.4197056 0.4197056 0.25 0.00999999 0.4197056 0.08029437 0.4197056 0.4197056 0.125 1 0.0625 1 0.0625 0.5 0.0625 1 0 1 0 0.5 0.658156 0.4717311 0.75 0.49 0.9717311 0.341844 0.75 0.49 0.841844 0.4717311 0.9717311 0.341844 0.841844 0.4717311 0.9197056 0.4197056 0.9717311 0.341844 0.9717311 0.341844 0.99 0.25 0.841844 0.02826887 0.99 0.25 0.9717311 0.1581559 0.841844 0.02826887 0.9717311 0.1581559 0.9197056 0.08029437 0.841844 0.02826887 0.841844 0.02826887 0.75 0.00999999 0.5282689 0.1581559 0.75 0.00999999 0.658156 0.02826887 0.5282689 0.1581559 0.658156 0.02826887 0.5802944 0.08029437 0.5282689 0.1581559 0.5282689 0.1581559 0.51 0.25 0.5282689 0.341844 0.5282689 0.341844 0.5802944 0.4197056 0.658156 0.4717311 0.5282689 0.1581559 0.5282689 0.341844 0.658156 0.4717311 0.658156 0.4717311 0.9717311 0.341844 0.5282689 0.1581559 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.005317986 0.00486803 0.003593802 0.004800558 0.004358887 0.004319727 0.002978742 0.002566218 0.004319727 0.002978742 0.002566218 -0.005680263 0.005317986 0.00486803 -0.005680263 0.004953145 0.00523889 0.003593802 0.004953145 0.00523889 -0.005680263 0.002613842 0.002937018 -0.005680263 0.002613842 0.002937018 0.004319727 0.004435718 0.004729688 0.004319727 0.004017651 0.003588497 -0.01271951 0.005317986 0.00486803 -0.01089519 0.002978742 0.002566218 -0.01271951 0.003652751 0.003959298 -0.01271951 0.002613842 0.002937018 -0.01271951 0.004953145 0.00523889 -0.01089519 -0.004823744 0.005358219 0.003593802 -0.004318952 0.004836559 0.004319727 -0.002541422 0.002999961 0.004319727 -0.002541422 0.002999961 -0.005680263 -0.004823744 0.005358219 -0.005680263 -0.005197584 0.004996418 0.003593802 -0.005197584 0.004996418 -0.005680263 -0.002915203 0.002638161 -0.005680263 -0.002915203 0.002638161 0.004319727 -0.004692733 0.004474759 0.004319727 -0.003555059 0.004047274 -0.01271951 -0.004823744 0.005358219 -0.01089519 -0.002541422 0.002999961 -0.01271951 -0.003928899 0.003685474 -0.01271951 -0.002915203 0.002638161 -0.01271951 -0.005197584 0.004996418 -0.01089519 0.002129197 -0.02311611 0.003208577 0.001975595 -0.02311611 0.003463387 0.001409769 -0.02311611 0.003463387 0.001409769 -0.02311611 0.003119826 0.001999974 -0.02311611 0.003119826 -0.002499997 -0.02311611 2.79243e-5 -0.002499997 -0.02311611 0.003103077 -0.002499997 -0.01974391 0.003103077 -0.002499997 -0.01974391 2.79243e-5 0.002499997 -0.01974391 2.79243e-5 0.002499997 -0.01974391 0.003103077 0.002499997 -0.02311611 0.003103077 0.002499997 -0.02311611 2.79243e-5 0.001409769 -0.01974391 0.003463387 -0.001409769 -0.01974391 0.003463387 -0.001409769 -0.02311611 0.003463387 0.001409769 -0.006255149 0.003463387 -0.001409769 -0.006255149 0.003463387 -0.001409769 -0.009627342 0.003463387 0.001409769 -0.009627342 0.003463387 0.001409769 -0.01299953 0.003463387 -0.001409769 -0.01299953 0.003463387 -0.001409769 -0.01637172 0.003463387 0.001409769 -0.01637172 0.003463387 0.002217113 -0.002882957 0.003183543 0.002499997 -0.002882957 0.003103077 0.002499997 -0.002882957 2.79243e-5 0.002217113 -0.002882957 2.79243e-5 0.002499997 -0.009627342 2.79243e-5 0.002499997 -0.009627342 0.003103077 0.002499997 -0.01299953 0.003103077 0.002499997 -0.01299953 2.79243e-5 0.002499997 -0.01637172 0.003103077 0.002499997 -0.01637172 2.79243e-5 -0.002499997 -0.006255149 2.79243e-5 -0.002499997 -0.006255149 0.003103077 -0.002499997 -0.002882957 0.003103077 -0.002499997 -0.002882957 2.79243e-5 0.002499997 -0.006255149 2.79243e-5 0.002499997 -0.006255149 0.003103077 -0.002499997 -0.009627342 2.79243e-5 -0.002499997 -0.009627342 0.003103077 -0.002499997 -0.01299953 2.79243e-5 -0.002499997 -0.01299953 0.003103077 -0.002499997 -0.01637172 2.79243e-5 -0.002499997 -0.01637172 0.003103077 0.001975595 -0.006255149 0.003463387 0.001975595 -0.009627342 0.003463387 0.001975595 -0.01299953 0.003463387 0.001975595 -0.01637172 0.003463387 0.001975595 -0.01974391 0.003463387 -0.001975595 -0.02311611 0.003463387 -0.002129197 -0.02311611 0.003208577 -0.001999974 -0.02311611 0.003119826 -0.001409769 -0.02311611 0.003119826 -0.001975595 -0.01637172 0.003463387 -0.001975595 -0.01974391 0.003463387 -0.001975595 -0.01299953 0.003463387 -0.001975595 -0.009627342 0.003463387 -0.001975595 -0.006255149 0.003463387 -0.001999974 -0.003028035 0.003119826 -0.001999974 -0.006255149 0.003119826 -0.001999974 -0.006255149 2.79243e-5 -0.001999974 -0.003028035 2.79243e-5 0.001999974 -0.01974391 2.79243e-5 0.001999974 -0.02311611 2.79243e-5 0.001999974 -0.01974391 0.003119826 -0.001409769 -0.01974391 0.003119826 -0.001999974 -0.01974391 0.003119826 0.001409769 -0.01974391 0.003119826 0.001409769 -0.006255149 0.003119826 0.001409769 -0.009627342 0.003119826 -0.001409769 -0.009627342 0.003119826 -0.001409769 -0.006255149 0.003119826 0.001409769 -0.01299953 0.003119826 0.001409769 -0.01637172 0.003119826 -0.001409769 -0.01637172 0.003119826 -0.001409769 -0.01299953 0.003119826 0.001999974 -0.003028035 0.003119826 0.001999974 -0.006255149 0.003119826 0.001409769 -0.003419578 0.003119826 0.001415908 -0.003418326 0.003119826 0.001999974 -0.009627342 0.003119826 0.001999974 -0.01299953 0.003119826 0.001999974 -0.01637172 0.003119826 -0.001409769 -0.003419578 0.003119826 -0.001415908 -0.003418326 0.003119826 -0.001999974 -0.009627342 0.003119826 -0.001999974 -0.01299953 0.003119826 -0.001999974 -0.01637172 0.003119826 0.001999974 -0.006255149 2.79243e-5 0.001999974 -0.003028035 2.79243e-5 0.001999974 -0.009627342 2.79243e-5 0.001999974 -0.01299953 2.79243e-5 0.001999974 -0.01637172 2.79243e-5 -0.001999974 -0.02311611 2.79243e-5 -0.001999974 -0.01974391 2.79243e-5 -0.001999974 -0.01637172 2.79243e-5 -0.001999974 -0.01299953 2.79243e-5 -0.001999974 -0.009627342 2.79243e-5 0.001415908 -0.003418326 0.003463387 0.001409769 -0.003419578 0.003463387 0.001975595 -0.003044307 0.003463387 -0.001415908 -0.003418326 0.003463387 -0.001975595 -0.003044307 0.003463387 -0.001409769 -0.003419578 0.003463387 -0.002217113 -0.002882957 2.79243e-5 -0.002217113 -0.002882957 0.003183603 -0.002217113 -0.002882957 0.003297388 0.002217113 -0.002882957 0.003297388 -0.003361761 -0.002167582 -0.005680263 -0.003361761 -0.002167582 0.004319727 -0.003935337 -7.16104e-4 0.004319727 -0.003935337 -7.16104e-4 -0.005680263 -0.003909826 8.4441e-4 0.004319727 -0.003909826 8.4441e-4 -0.005680263 -0.003289043 0.00227636 0.004319727 -0.003289043 0.00227636 -0.005680263 -0.002167582 0.003361761 0.004319727 -0.002167582 0.003361761 -0.005680263 -7.16104e-4 0.003935337 0.004319727 -7.16104e-4 0.003935337 -0.005680263 8.4441e-4 0.003909826 0.004319727 8.4441e-4 0.003909826 -0.005680263 0.00227636 0.003289043 0.004319727 0.00227636 0.003289043 -0.005680263 0.003361761 0.002167582 0.004319727 0.003361761 0.002167582 -0.005680263 0.003935337 7.16104e-4 0.004319727 0.003935337 7.16104e-4 -0.005680263 0.003909826 -8.4441e-4 0.004319727 0.003909826 -8.4441e-4 -0.005680263 0.003289043 -0.00227636 0.004319727 0.003289043 -0.00227636 -0.005680263 0.002167582 -0.003361761 0.004319727 0.002167582 -0.003361761 -0.005680263 7.16103e-4 -0.003935337 0.004319727 7.16103e-4 -0.003935337 -0.005680263 -8.44409e-4 -0.003909826 0.004319727 -8.44409e-4 -0.003909826 -0.005680263 -0.00227636 -0.003289043 0.004319727 -0.00227636 -0.003289043 -0.005680263 -0.002991139 -0.001928627 0.004319727 -0.003501534 -6.37161e-4 0.004319727 -0.003478825 7.51323e-4 0.004319727 -0.002926468 0.002025365 0.004319727 -0.001928627 0.002991139 0.004319727 -6.37161e-4 0.003501534 0.004319727 7.51323e-4 0.003478825 0.004319727 0.002025365 0.002926468 0.004319727 0.002991139 0.001928627 0.004319727 0.003501534 6.37161e-4 0.004319727 0.003478825 -7.51322e-4 0.004319727 0.002926468 -0.002025365 0.004319727 0.001928627 -0.002991139 0.004319727 6.3716e-4 -0.003501534 0.004319727 -7.51322e-4 -0.003478825 0.004319727 -0.002025365 -0.002926468 0.004319727 -7.51322e-4 -0.003478825 -0.00413084 -0.002025365 -0.002926468 -0.00413084 -0.002999961 0 -0.00413084 -0.0028764 6.21222e-4 -0.00413084 -0.003478825 7.51323e-4 -0.00413084 -0.003501534 -6.37161e-4 -0.00413084 -0.002991139 -0.001928627 -0.00413084 6.3716e-4 -0.003501534 -0.00413084 0.001928627 -0.002991139 -0.00413084 0.002926468 -0.002025365 -0.00413084 0.003478825 -7.51322e-4 -0.00413084 0.0028764 -6.21221e-4 -0.00413084 0.002771615 -0.001148045 -0.00413084 0.002121269 -0.002121269 -0.00413084 -0.002771615 -0.001148045 -0.00413084 0.001148045 -0.002771615 -0.00413084 -0.002121269 -0.002121269 -0.00413084 -0.001148045 -0.002771615 -0.00413084 0 -0.002999961 -0.00413084 0.002999961 0 -0.00413084 0.003501534 6.37161e-4 -0.00413084 0.002991139 0.001928627 -0.00413084 0.002025365 0.002926468 -0.00413084 7.51323e-4 0.003478825 -0.00413084 -6.37161e-4 0.003501534 -0.00413084 -0.001928627 0.002991139 -0.00413084 -0.002926468 0.002025365 -0.00413084 -0.002771615 0.001148045 -0.00413084 -0.002121269 0.002121269 -0.00413084 0.002771615 0.001148045 -0.00413084 -0.001148045 0.002771615 -0.00413084 0.002121269 0.002121269 -0.00413084 0.001148045 0.002771615 -0.00413084 0 0.002999961 -0.00413084 -0.001674652 -0.00241971 -0.005680263 0.001674652 0.00241971 -0.005680263 0.001148045 0.002771615 -0.005680263 -0.002121269 -0.002121269 -0.005680263 -0.002771615 -0.001148045 -0.005680263 0 0.002999961 -0.005680263 -0.001148045 0.002771615 -0.005680263 -0.002999961 0 -0.005680263 -0.002121269 0.002121269 -0.005680263 -0.002771615 0.001148045 -0.005680263 0.002121269 0.002121269 -0.005680263 -0.001148045 -0.002771615 -0.005680263 0 -0.002999961 -0.005680263 0.002771615 0.001148045 -0.005680263 0.001148045 -0.002771615 -0.005680263 0.002999961 0 -0.005680263 0.002771615 -0.001148045 -0.005680263 0.002121269 -0.002121269 -0.005680263 -0.04870867 -0.04915863 0.003593802 -0.04819953 -0.0486412 0.004319727 -0.0464068 -0.04681938 0.004319727 -0.0464068 -0.04681938 -0.005680263 -0.04870867 -0.04915863 -0.005680263 -0.04907947 -0.04879373 0.003593802 -0.04907947 -0.04879373 -0.005680263 -0.04677766 -0.04645448 -0.005680263 -0.04677766 -0.04645448 0.004319727 -0.04857033 -0.0482763 0.004319727 -0.04742914 -0.04785829 -0.01271951 -0.04870867 -0.04915863 -0.01089519 -0.0464068 -0.04681938 -0.01271951 -0.04779994 -0.04749339 -0.01271951 -0.04677766 -0.04645448 -0.01271951 -0.04907947 -0.04879373 -0.01089519 -0.04919886 -0.03901678 0.003593802 -0.0486772 -0.03952163 0.004319727 -0.04684054 -0.04129916 0.004319727 -0.04684054 -0.04129916 -0.005680263 -0.04919886 -0.03901678 -0.005680263 -0.048837 -0.03864294 0.003593802 -0.048837 -0.03864294 -0.005680263 -0.04647874 -0.04092532 -0.005680263 -0.04647874 -0.04092532 0.004319727 -0.0483154 -0.03914779 0.004319727 -0.04788792 -0.04028552 -0.01271951 -0.04919886 -0.03901678 -0.01089519 -0.04684054 -0.04129916 -0.01271951 -0.04752612 -0.03991168 -0.01271951 -0.04647874 -0.04092532 -0.01271951 -0.048837 -0.03864294 -0.01089519 -0.02072447 -0.04596984 0.003208577 -0.02072447 -0.04581624 0.003463327 -0.02072447 -0.04525035 0.003463327 -0.02072447 -0.04525035 0.003119826 -0.02072447 -0.04584062 0.003119826 -0.02072447 -0.04134058 2.79233e-5 -0.02072447 -0.04134058 0.003103077 -0.02409666 -0.04134058 0.003103077 -0.02409666 -0.04134058 2.79233e-5 -0.02409666 -0.04634058 2.79233e-5 -0.02409666 -0.04634058 0.003103077 -0.02072447 -0.04634058 0.003103077 -0.02072447 -0.04634058 2.79233e-5 -0.02409666 -0.04525035 0.003463327 -0.02409666 -0.04243081 0.003463327 -0.02072447 -0.04243081 0.003463327 -0.03758543 -0.04525035 0.003463327 -0.03758543 -0.04243081 0.003463327 -0.03421324 -0.04243081 0.003463327 -0.03421324 -0.04525035 0.003463327 -0.03084105 -0.04525035 0.003463327 -0.03084105 -0.04243081 0.003463327 -0.02746886 -0.04243081 0.003463327 -0.02746886 -0.04525035 0.003463327 -0.04095762 -0.04605776 0.003183543 -0.04095762 -0.04634058 0.003103077 -0.04095762 -0.04634058 2.79233e-5 -0.04095762 -0.04605776 2.79233e-5 -0.03421324 -0.04634058 2.79233e-5 -0.03421324 -0.04634058 0.003103077 -0.03084105 -0.04634058 0.003103077 -0.03084105 -0.04634058 2.79233e-5 -0.02746886 -0.04634058 0.003103077 -0.02746886 -0.04634058 2.79233e-5 -0.03758543 -0.04134058 2.79233e-5 -0.03758543 -0.04134058 0.003103077 -0.04095762 -0.04134058 0.003103077 -0.04095762 -0.04134058 2.79233e-5 -0.03758543 -0.04634058 2.79233e-5 -0.03758543 -0.04634058 0.003103077 -0.03421324 -0.04134058 2.79233e-5 -0.03421324 -0.04134058 0.003103077 -0.03084105 -0.04134058 2.79233e-5 -0.03084105 -0.04134058 0.003103077 -0.02746886 -0.04134058 2.79233e-5 -0.02746886 -0.04134058 0.003103077 -0.03758543 -0.04581624 0.003463327 -0.03421324 -0.04581624 0.003463327 -0.03084105 -0.04581624 0.003463327 -0.02746886 -0.04581624 0.003463327 -0.02409666 -0.04581624 0.003463327 -0.02072447 -0.04186493 0.003463327 -0.02072447 -0.04171139 0.003208577 -0.02072447 -0.04184061 0.003119826 -0.02072447 -0.04243081 0.003119826 -0.02746886 -0.04186493 0.003463327 -0.02409666 -0.04186493 0.003463327 -0.03084105 -0.04186493 0.003463327 -0.03421324 -0.04186493 0.003463327 -0.03758543 -0.04186493 0.003463327 -0.04081249 -0.04184061 0.003119826 -0.03758543 -0.04184061 0.003119826 -0.03758543 -0.04184061 2.79233e-5 -0.04081249 -0.04184061 2.79233e-5 -0.02409666 -0.04584062 2.79233e-5 -0.02072447 -0.04584062 2.79233e-5 -0.02409666 -0.04584062 0.003119826 -0.02409666 -0.04243081 0.003119826 -0.02409666 -0.04184061 0.003119826 -0.02409666 -0.04525035 0.003119826 -0.03758543 -0.04525035 0.003119826 -0.03421324 -0.04525035 0.003119826 -0.03421324 -0.04243081 0.003119826 -0.03758543 -0.04243081 0.003119826 -0.03084105 -0.04525035 0.003119826 -0.02746886 -0.04525035 0.003119826 -0.02746886 -0.04243081 0.003119826 -0.03084105 -0.04243081 0.003119826 -0.04081249 -0.04584062 0.003119826 -0.03758543 -0.04584062 0.003119826 -0.040421 -0.04525035 0.003119826 -0.04042226 -0.04525655 0.003119826 -0.03421324 -0.04584062 0.003119826 -0.03084105 -0.04584062 0.003119826 -0.02746886 -0.04584062 0.003119826 -0.040421 -0.04243081 0.003119826 -0.04042226 -0.04242467 0.003119826 -0.03421324 -0.04184061 0.003119826 -0.03084105 -0.04184061 0.003119826 -0.02746886 -0.04184061 0.003119826 -0.03758543 -0.04584062 2.79233e-5 -0.04081249 -0.04584062 2.79233e-5 -0.03421324 -0.04584062 2.79233e-5 -0.03084105 -0.04584062 2.79233e-5 -0.02746886 -0.04584062 2.79233e-5 -0.02072447 -0.04184061 2.79233e-5 -0.02409666 -0.04184061 2.79233e-5 -0.02746886 -0.04184061 2.79233e-5 -0.03084105 -0.04184061 2.79233e-5 -0.03421324 -0.04184061 2.79233e-5 -0.04042226 -0.04525655 0.003463327 -0.040421 -0.04525035 0.003463327 -0.04079622 -0.04581624 0.003463327 -0.04042226 -0.04242467 0.003463327 -0.04079622 -0.04186493 0.003463327 -0.040421 -0.04243081 0.003463327 -0.04095762 -0.04162341 2.79233e-5 -0.04095762 -0.04162341 0.003183543 -0.04095762 -0.04162341 0.003297388 -0.04095762 -0.04605776 0.003297388 -0.041673 -0.04047882 -0.005680263 -0.041673 -0.04047882 0.004319727 -0.04312449 -0.03990525 0.004319727 -0.04312449 -0.03990525 -0.005680263 -0.044685 -0.03993076 0.004319727 -0.044685 -0.03993076 -0.005680263 -0.04611694 -0.04055148 0.004319727 -0.04611694 -0.04055148 -0.005680263 -0.04720234 -0.041673 0.004319727 -0.04720234 -0.041673 -0.005680263 -0.04777598 -0.04312449 0.004319727 -0.04777598 -0.04312449 -0.005680263 -0.04775047 -0.044685 0.004319727 -0.04775047 -0.044685 -0.005680263 -0.04712969 -0.04611694 0.004319727 -0.04712969 -0.04611694 -0.005680263 -0.04600816 -0.04720234 0.004319727 -0.04600816 -0.04720234 -0.005680263 -0.04455667 -0.04777598 0.004319727 -0.04455667 -0.04777598 -0.005680263 -0.04299616 -0.04775047 0.004319727 -0.04299616 -0.04775047 -0.005680263 -0.04156422 -0.04712969 0.004319727 -0.04156422 -0.04712969 -0.005680263 -0.04047882 -0.04600816 0.004319727 -0.04047882 -0.04600816 -0.005680263 -0.03990525 -0.04455667 0.004319727 -0.03990525 -0.04455667 -0.005680263 -0.03993076 -0.04299616 0.004319727 -0.03993076 -0.04299616 -0.005680263 -0.04055148 -0.04156422 0.004319727 -0.04055148 -0.04156422 -0.005680263 -0.04191195 -0.04084944 0.004319727 -0.04320341 -0.04033905 0.004319727 -0.0445919 -0.04036176 0.004319727 -0.04586601 -0.04091411 0.004319727 -0.04683178 -0.04191195 0.004319727 -0.04734212 -0.04320341 0.004319727 -0.04731941 -0.0445919 0.004319727 -0.04676711 -0.04586601 0.004319727 -0.04576921 -0.04683178 0.004319727 -0.04447776 -0.04734212 0.004319727 -0.04308927 -0.04731941 0.004319727 -0.04181516 -0.04676711 0.004319727 -0.04084944 -0.04576921 0.004319727 -0.04033905 -0.04447776 0.004319727 -0.04036176 -0.04308927 0.004319727 -0.04091411 -0.04181516 0.004319727 -0.04036176 -0.04308927 -0.00413084 -0.04091411 -0.04181516 -0.00413084 -0.04384058 -0.04084062 -0.00413084 -0.04446184 -0.04096418 -0.00413084 -0.0445919 -0.04036176 -0.00413084 -0.04320341 -0.04033905 -0.00413084 -0.04191195 -0.04084944 -0.00413084 -0.04033905 -0.04447776 -0.00413084 -0.04084944 -0.04576921 -0.00413084 -0.04181516 -0.04676711 -0.00413084 -0.04308927 -0.04731941 -0.00413084 -0.04321938 -0.04671704 -0.00413084 -0.04269254 -0.04661226 -0.00413084 -0.04171925 -0.04596191 -0.00413084 -0.04269254 -0.04106897 -0.00413084 -0.04106897 -0.04498863 -0.00413084 -0.04171925 -0.04171925 -0.00413084 -0.04106897 -0.04269254 -0.00413084 -0.04084062 -0.04384058 -0.00413084 -0.04384058 -0.0468406 -0.00413084 -0.04447776 -0.04734212 -0.00413084 -0.04576921 -0.04683178 -0.00413084 -0.04676711 -0.04586601 -0.00413084 -0.04731941 -0.0445919 -0.00413084 -0.04734212 -0.04320341 -0.00413084 -0.04683178 -0.04191195 -0.00413084 -0.04586601 -0.04091411 -0.00413084 -0.04498863 -0.04106897 -0.00413084 -0.04596191 -0.04171925 -0.00413084 -0.04498863 -0.04661226 -0.00413084 -0.04661226 -0.04269254 -0.00413084 -0.04596191 -0.04596191 -0.00413084 -0.04661226 -0.04498863 -0.00413084 -0.0468406 -0.04384058 -0.00413084 -0.04142087 -0.04216587 -0.005680263 -0.04626035 -0.04551529 -0.005680263 -0.04661226 -0.04498863 -0.005680263 -0.04171925 -0.04171925 -0.005680263 -0.04269254 -0.04106897 -0.005680263 -0.0468406 -0.04384058 -0.005680263 -0.04661226 -0.04269254 -0.005680263 -0.04384058 -0.04084062 -0.005680263 -0.04596191 -0.04171925 -0.005680263 -0.04498863 -0.04106897 -0.005680263 -0.04596191 -0.04596191 -0.005680263 -0.04106897 -0.04269254 -0.005680263 -0.04084062 -0.04384058 -0.005680263 -0.04498863 -0.04661226 -0.005680263 -0.04106897 -0.04498863 -0.005680263 -0.04384058 -0.0468406 -0.005680263 -0.04269254 -0.04661226 -0.005680263 -0.04171925 -0.04596191 -0.005680263 0.04870867 -0.03852254 0.003593802 0.04819953 -0.03903996 0.004319727 0.0464068 -0.04086178 0.004319727 0.0464068 -0.04086178 -0.005680263 0.04870867 -0.03852254 -0.005680263 0.04907947 -0.03888744 0.003593802 0.04907947 -0.03888744 -0.005680263 0.04677766 -0.04122668 -0.005680263 0.04677766 -0.04122668 0.004319727 0.04857033 -0.03940486 0.004319727 0.04742914 -0.03982287 -0.01271951 0.04870867 -0.03852254 -0.01089519 0.0464068 -0.04086178 -0.01271951 0.04779994 -0.04018777 -0.01271951 0.04677766 -0.04122668 -0.01271951 0.04907947 -0.03888744 -0.01089519 0.04919886 -0.04866439 0.003593802 0.0486772 -0.04815953 0.004319727 0.04684054 -0.046382 0.004319727 0.04684054 -0.046382 -0.005680263 0.04919886 -0.04866439 -0.005680263 0.048837 -0.04903823 0.003593802 0.048837 -0.04903823 -0.005680263 0.04647874 -0.04675585 -0.005680263 0.04647874 -0.04675585 0.004319727 0.0483154 -0.04853338 0.004319727 0.04788792 -0.04739564 -0.01271951 0.04919886 -0.04866439 -0.01089519 0.04684054 -0.046382 -0.01271951 0.04752612 -0.04776948 -0.01271951 0.04647874 -0.04675585 -0.01271951 0.048837 -0.04903823 -0.01089519 0.02072447 -0.04171139 0.003208577 0.02072447 -0.04186493 0.003463327 0.02072447 -0.04243081 0.003463327 0.02072447 -0.04243081 0.003119826 0.02072447 -0.04184061 0.003119826 0.02072447 -0.04634058 2.79233e-5 0.02072447 -0.04634058 0.003103077 0.02409666 -0.04634058 0.003103077 0.02409666 -0.04634058 2.79233e-5 0.02409666 -0.04134058 2.79233e-5 0.02409666 -0.04134058 0.003103077 0.02072447 -0.04134058 0.003103077 0.02072447 -0.04134058 2.79233e-5 0.02409666 -0.04243081 0.003463327 0.02409666 -0.04525035 0.003463327 0.02072447 -0.04525035 0.003463327 0.03758543 -0.04243081 0.003463327 0.03758543 -0.04525035 0.003463327 0.03421324 -0.04525035 0.003463327 0.03421324 -0.04243081 0.003463327 0.03084105 -0.04243081 0.003463327 0.03084105 -0.04525035 0.003463327 0.02746886 -0.04525035 0.003463327 0.02746886 -0.04243081 0.003463327 0.04095762 -0.04162341 0.003183543 0.04095762 -0.04134058 0.003103077 0.04095762 -0.04134058 2.79233e-5 0.04095762 -0.04162341 2.79233e-5 0.03421324 -0.04134058 2.79233e-5 0.03421324 -0.04134058 0.003103077 0.03084105 -0.04134058 0.003103077 0.03084105 -0.04134058 2.79233e-5 0.02746886 -0.04134058 0.003103077 0.02746886 -0.04134058 2.79233e-5 0.03758543 -0.04634058 2.79233e-5 0.03758543 -0.04634058 0.003103077 0.04095762 -0.04634058 0.003103077 0.04095762 -0.04634058 2.79233e-5 0.03758543 -0.04134058 2.79233e-5 0.03758543 -0.04134058 0.003103077 0.03421324 -0.04634058 2.79233e-5 0.03421324 -0.04634058 0.003103077 0.03084105 -0.04634058 2.79233e-5 0.03084105 -0.04634058 0.003103077 0.02746886 -0.04634058 2.79233e-5 0.02746886 -0.04634058 0.003103077 0.03758543 -0.04186493 0.003463327 0.03421324 -0.04186493 0.003463327 0.03084105 -0.04186493 0.003463327 0.02746886 -0.04186493 0.003463327 0.02409666 -0.04186493 0.003463327 0.02072447 -0.04581624 0.003463327 0.02072447 -0.04596984 0.003208577 0.02072447 -0.04584062 0.003119826 0.02072447 -0.04525035 0.003119826 0.02746886 -0.04581624 0.003463327 0.02409666 -0.04581624 0.003463327 0.03084105 -0.04581624 0.003463327 0.03421324 -0.04581624 0.003463327 0.03758543 -0.04581624 0.003463327 0.04081249 -0.04584062 0.003119826 0.03758543 -0.04584062 0.003119826 0.03758543 -0.04584062 2.79233e-5 0.04081249 -0.04584062 2.79233e-5 0.02409666 -0.04184061 2.79233e-5 0.02072447 -0.04184061 2.79233e-5 0.02409666 -0.04184061 0.003119826 0.02409666 -0.04525035 0.003119826 0.02409666 -0.04584062 0.003119826 0.02409666 -0.04243081 0.003119826 0.03758543 -0.04243081 0.003119826 0.03421324 -0.04243081 0.003119826 0.03421324 -0.04525035 0.003119826 0.03758543 -0.04525035 0.003119826 0.03084105 -0.04243081 0.003119826 0.02746886 -0.04243081 0.003119826 0.02746886 -0.04525035 0.003119826 0.03084105 -0.04525035 0.003119826 0.04081249 -0.04184061 0.003119826 0.03758543 -0.04184061 0.003119826 0.040421 -0.04243081 0.003119826 0.04042226 -0.04242467 0.003119826 0.03421324 -0.04184061 0.003119826 0.03084105 -0.04184061 0.003119826 0.02746886 -0.04184061 0.003119826 0.040421 -0.04525035 0.003119826 0.04042226 -0.04525655 0.003119826 0.03421324 -0.04584062 0.003119826 0.03084105 -0.04584062 0.003119826 0.02746886 -0.04584062 0.003119826 0.03758543 -0.04184061 2.79233e-5 0.04081249 -0.04184061 2.79233e-5 0.03421324 -0.04184061 2.79233e-5 0.03084105 -0.04184061 2.79233e-5 0.02746886 -0.04184061 2.79233e-5 0.02072447 -0.04584062 2.79233e-5 0.02409666 -0.04584062 2.79233e-5 0.02746886 -0.04584062 2.79233e-5 0.03084105 -0.04584062 2.79233e-5 0.03421324 -0.04584062 2.79233e-5 0.04042226 -0.04242467 0.003463327 0.040421 -0.04243081 0.003463327 0.04079622 -0.04186493 0.003463327 0.04042226 -0.04525655 0.003463327 0.04079622 -0.04581624 0.003463327 0.040421 -0.04525035 0.003463327 0.04095762 -0.04605776 2.79233e-5 0.04095762 -0.04605776 0.003183543 0.04095762 -0.04605776 0.003297388 0.04095762 -0.04162341 0.003297388 0.041673 -0.04720234 -0.005680263 0.041673 -0.04720234 0.004319727 0.04312449 -0.04777598 0.004319727 0.04312449 -0.04777598 -0.005680263 0.044685 -0.04775047 0.004319727 0.044685 -0.04775047 -0.005680263 0.04611694 -0.04712969 0.004319727 0.04611694 -0.04712969 -0.005680263 0.04720234 -0.04600816 0.004319727 0.04720234 -0.04600816 -0.005680263 0.04777598 -0.04455667 0.004319727 0.04777598 -0.04455667 -0.005680263 0.04775047 -0.04299616 0.004319727 0.04775047 -0.04299616 -0.005680263 0.04712969 -0.04156422 0.004319727 0.04712969 -0.04156422 -0.005680263 0.04600816 -0.04047882 0.004319727 0.04600816 -0.04047882 -0.005680263 0.04455667 -0.03990525 0.004319727 0.04455667 -0.03990525 -0.005680263 0.04299616 -0.03993076 0.004319727 0.04299616 -0.03993076 -0.005680263 0.04156422 -0.04055148 0.004319727 0.04156422 -0.04055148 -0.005680263 0.04047882 -0.041673 0.004319727 0.04047882 -0.041673 -0.005680263 0.03990525 -0.04312449 0.004319727 0.03990525 -0.04312449 -0.005680263 0.03993076 -0.044685 0.004319727 0.03993076 -0.044685 -0.005680263 0.04055148 -0.04611694 0.004319727 0.04055148 -0.04611694 -0.005680263 0.04191195 -0.04683178 0.004319727 0.04320341 -0.04734212 0.004319727 0.0445919 -0.04731941 0.004319727 0.04586601 -0.04676711 0.004319727 0.04683178 -0.04576921 0.004319727 0.04734212 -0.04447776 0.004319727 0.04731941 -0.04308927 0.004319727 0.04676711 -0.04181516 0.004319727 0.04576921 -0.04084944 0.004319727 0.04447776 -0.04033905 0.004319727 0.04308927 -0.04036176 0.004319727 0.04181516 -0.04091411 0.004319727 0.04084944 -0.04191195 0.004319727 0.04033905 -0.04320341 0.004319727 0.04036176 -0.0445919 0.004319727 0.04091411 -0.04586601 0.004319727 0.04036176 -0.0445919 -0.00413084 0.04091411 -0.04586601 -0.00413084 0.04384058 -0.0468406 -0.00413084 0.04446184 -0.04671704 -0.00413084 0.0445919 -0.04731941 -0.00413084 0.04320341 -0.04734212 -0.00413084 0.04191195 -0.04683178 -0.00413084 0.04033905 -0.04320341 -0.00413084 0.04084944 -0.04191195 -0.00413084 0.04181516 -0.04091411 -0.00413084 0.04308927 -0.04036176 -0.00413084 0.04321938 -0.04096418 -0.00413084 0.04269254 -0.04106897 -0.00413084 0.04171925 -0.04171925 -0.00413084 0.04269254 -0.04661226 -0.00413084 0.04106897 -0.04269254 -0.00413084 0.04171925 -0.04596191 -0.00413084 0.04106897 -0.04498863 -0.00413084 0.04084062 -0.04384058 -0.00413084 0.04384058 -0.04084062 -0.00413084 0.04447776 -0.04033905 -0.00413084 0.04576921 -0.04084944 -0.00413084 0.04676711 -0.04181516 -0.00413084 0.04731941 -0.04308927 -0.00413084 0.04734212 -0.04447776 -0.00413084 0.04683178 -0.04576921 -0.00413084 0.04586601 -0.04676711 -0.00413084 0.04498863 -0.04661226 -0.00413084 0.04596191 -0.04596191 -0.00413084 0.04498863 -0.04106897 -0.00413084 0.04661226 -0.04498863 -0.00413084 0.04596191 -0.04171925 -0.00413084 0.04661226 -0.04269254 -0.00413084 0.0468406 -0.04384058 -0.00413084 0.04142087 -0.04551529 -0.005680263 0.04626035 -0.04216587 -0.005680263 0.04661226 -0.04269254 -0.005680263 0.04171925 -0.04596191 -0.005680263 0.04269254 -0.04661226 -0.005680263 0.0468406 -0.04384058 -0.005680263 0.04661226 -0.04498863 -0.005680263 0.04384058 -0.0468406 -0.005680263 0.04596191 -0.04596191 -0.005680263 0.04498863 -0.04661226 -0.005680263 0.04596191 -0.04171925 -0.005680263 0.04106897 -0.04498863 -0.005680263 0.04084062 -0.04384058 -0.005680263 0.04498863 -0.04106897 -0.005680263 0.04106897 -0.04269254 -0.005680263 0.04384058 -0.04084062 -0.005680263 0.04269254 -0.04106897 -0.005680263 0.04171925 -0.04171925 -0.005680263 -0.005317986 -0.09254932 0.003593802 -0.004800558 -0.09204012 0.004319727 -0.002978742 -0.09024745 0.004319727 -0.002978742 -0.09024745 -0.005680263 -0.005317986 -0.09254932 -0.005680263 -0.004953145 -0.09292012 0.003593802 -0.004953145 -0.09292012 -0.005680263 -0.002613842 -0.09061825 -0.005680263 -0.002613842 -0.09061825 0.004319727 -0.004435718 -0.09241098 0.004319727 -0.004017651 -0.09126973 -0.01271951 -0.005317986 -0.09254932 -0.01089519 -0.002978742 -0.09024745 -0.01271951 -0.003652751 -0.09164059 -0.01271951 -0.002613842 -0.09061825 -0.01271951 -0.004953145 -0.09292012 -0.01089519 0.004823744 -0.09303945 0.003593802 0.004318952 -0.09251785 0.004319727 0.002541422 -0.09068119 0.004319727 0.002541422 -0.09068119 -0.005680263 0.004823744 -0.09303945 -0.005680263 0.005197584 -0.09267765 0.003593802 0.005197584 -0.09267765 -0.005680263 0.002915263 -0.09031939 -0.005680263 0.002915263 -0.09031939 0.004319727 0.004692733 -0.09215605 0.004319727 0.003555059 -0.09172856 -0.01271951 0.004823744 -0.09303945 -0.01089519 0.002541422 -0.09068119 -0.01271951 0.003928899 -0.09136676 -0.01271951 0.002915263 -0.09031939 -0.01271951 0.005197584 -0.09267765 -0.01089519 -0.002129197 -0.06456512 0.003208577 -0.001975595 -0.06456512 0.003463327 -0.001409769 -0.06456512 0.003463327 -0.001409769 -0.06456512 0.003119826 -0.001999974 -0.06456512 0.003119826 0.002499997 -0.06456512 2.79224e-5 0.002499997 -0.06456512 0.003103077 0.002499997 -0.06793731 0.003103077 0.002499997 -0.06793731 2.79224e-5 -0.002499997 -0.06793731 2.79224e-5 -0.002499997 -0.06793731 0.003103077 -0.002499997 -0.06456512 0.003103077 -0.002499997 -0.06456512 2.79224e-5 -0.001409769 -0.06793731 0.003463327 0.001409769 -0.06793731 0.003463327 0.001409769 -0.06456512 0.003463327 -0.001409769 -0.08142608 0.003463327 0.001409769 -0.08142608 0.003463327 0.001409769 -0.07805389 0.003463327 -0.001409769 -0.07805389 0.003463327 -0.001409769 -0.07468169 0.003463327 0.001409769 -0.07468169 0.003463327 0.001409769 -0.0713095 0.003463327 -0.001409769 -0.0713095 0.003463327 -0.002217173 -0.08479827 0.003183543 -0.002499997 -0.08479827 0.003103077 -0.002499997 -0.08479827 2.79224e-5 -0.002217173 -0.08479827 2.79224e-5 -0.002499997 -0.07805389 2.79224e-5 -0.002499997 -0.07805389 0.003103077 -0.002499997 -0.07468169 0.003103077 -0.002499997 -0.07468169 2.79224e-5 -0.002499997 -0.0713095 0.003103077 -0.002499997 -0.0713095 2.79224e-5 0.002499997 -0.08142608 2.79224e-5 0.002499997 -0.08142608 0.003103077 0.002499997 -0.08479827 0.003103077 0.002499997 -0.08479827 2.79224e-5 -0.002499997 -0.08142608 2.79224e-5 -0.002499997 -0.08142608 0.003103077 0.002499997 -0.07805389 2.79224e-5 0.002499997 -0.07805389 0.003103077 0.002499997 -0.07468169 2.79224e-5 0.002499997 -0.07468169 0.003103077 0.002499997 -0.0713095 2.79224e-5 0.002499997 -0.0713095 0.003103077 -0.001975595 -0.08142608 0.003463327 -0.001975595 -0.07805389 0.003463327 -0.001975595 -0.07468169 0.003463327 -0.001975595 -0.0713095 0.003463327 -0.001975595 -0.06793731 0.003463327 0.001975595 -0.06456512 0.003463327 0.002129197 -0.06456512 0.003208577 0.001999974 -0.06456512 0.003119826 0.001409769 -0.06456512 0.003119826 0.001975595 -0.0713095 0.003463327 0.001975595 -0.06793731 0.003463327 0.001975595 -0.07468169 0.003463327 0.001975595 -0.07805389 0.003463327 0.001975595 -0.08142608 0.003463327 0.001999974 -0.08465313 0.003119826 0.001999974 -0.08142608 0.003119826 0.001999974 -0.08142608 2.79224e-5 0.001999974 -0.08465313 2.79224e-5 -0.001999974 -0.06793731 2.79224e-5 -0.001999974 -0.06456512 2.79224e-5 -0.001999974 -0.06793731 0.003119826 0.001409769 -0.06793731 0.003119826 0.001999974 -0.06793731 0.003119826 -0.001409769 -0.06793731 0.003119826 -0.001409769 -0.08142608 0.003119826 -0.001409769 -0.07805389 0.003119826 0.001409769 -0.07805389 0.003119826 0.001409769 -0.08142608 0.003119826 -0.001409769 -0.07468169 0.003119826 -0.001409769 -0.0713095 0.003119826 0.001409769 -0.0713095 0.003119826 0.001409769 -0.07468169 0.003119826 -0.001999974 -0.08465313 0.003119826 -0.001999974 -0.08142608 0.003119826 -0.001409769 -0.08426165 0.003119826 -0.001415908 -0.08426284 0.003119826 -0.001999974 -0.07805389 0.003119826 -0.001999974 -0.07468169 0.003119826 -0.001999974 -0.0713095 0.003119826 0.001409769 -0.08426165 0.003119826 0.001415908 -0.08426284 0.003119826 0.001999974 -0.07805389 0.003119826 0.001999974 -0.07468169 0.003119826 0.001999974 -0.0713095 0.003119826 -0.001999974 -0.08142608 2.79224e-5 -0.001999974 -0.08465313 2.79224e-5 -0.001999974 -0.07805389 2.79224e-5 -0.001999974 -0.07468169 2.79224e-5 -0.001999974 -0.0713095 2.79224e-5 0.001999974 -0.06456512 2.79224e-5 0.001999974 -0.06793731 2.79224e-5 0.001999974 -0.0713095 2.79224e-5 0.001999974 -0.07468169 2.79224e-5 0.001999974 -0.07805389 2.79224e-5 -0.001415908 -0.08426284 0.003463327 -0.001409769 -0.08426165 0.003463327 -0.001975595 -0.08463686 0.003463327 0.001415908 -0.08426284 0.003463327 0.001975595 -0.08463686 0.003463327 0.001409769 -0.08426165 0.003463327 0.002217113 -0.08479827 2.79224e-5 0.002217113 -0.08479827 0.003183543 0.002217113 -0.08479827 0.003297388 -0.002217173 -0.08479827 0.003297388 0.003361761 -0.08551365 -0.005680263 0.003361761 -0.08551365 0.004319727 0.003935337 -0.08696514 0.004319727 0.003935337 -0.08696514 -0.005680263 0.003909826 -0.08852565 0.004319727 0.003909826 -0.08852565 -0.005680263 0.003289043 -0.08995759 0.004319727 0.003289043 -0.08995759 -0.005680263 0.002167582 -0.09104299 0.004319727 0.002167582 -0.09104299 -0.005680263 7.16105e-4 -0.09161663 0.004319727 7.16105e-4 -0.09161663 -0.005680263 -8.44412e-4 -0.09159106 0.004319727 -8.44412e-4 -0.09159106 -0.005680263 -0.00227636 -0.09097033 0.004319727 -0.00227636 -0.09097033 -0.005680263 -0.003361761 -0.08984881 0.004319727 -0.003361761 -0.08984881 -0.005680263 -0.003935337 -0.08839732 0.004319727 -0.003935337 -0.08839732 -0.005680263 -0.003909826 -0.08683681 0.004319727 -0.003909826 -0.08683681 -0.005680263 -0.003289043 -0.08540487 0.004319727 -0.003289043 -0.08540487 -0.005680263 -0.002167582 -0.08431947 0.004319727 -0.002167582 -0.08431947 -0.005680263 -7.16105e-4 -0.08374583 0.004319727 -7.16105e-4 -0.08374583 -0.005680263 8.44408e-4 -0.08377134 0.004319727 8.44408e-4 -0.08377134 -0.005680263 0.00227636 -0.08439213 0.004319727 0.00227636 -0.08439213 -0.005680263 0.002991139 -0.0857526 0.004319727 0.003501534 -0.08704406 0.004319727 0.003478825 -0.08843255 0.004319727 0.002926468 -0.08970665 0.004319727 0.001928627 -0.09067237 0.004319727 6.37162e-4 -0.09118276 0.004319727 -7.51324e-4 -0.09116005 0.004319727 -0.002025425 -0.09060776 0.004319727 -0.002991139 -0.08960986 0.004319727 -0.003501534 -0.0883184 0.004319727 -0.003478825 -0.08692991 0.004319727 -0.002926468 -0.0856558 0.004319727 -0.001928627 -0.08469003 0.004319727 -6.37159e-4 -0.08417969 0.004319727 7.51324e-4 -0.0842024 0.004319727 0.002025425 -0.0847547 0.004319727 7.51324e-4 -0.0842024 -0.00413084 0.002025425 -0.0847547 -0.00413084 0.002999961 -0.08768123 -0.00413084 0.0028764 -0.08830243 -0.00413084 0.003478825 -0.08843255 -0.00413084 0.003501534 -0.08704406 -0.00413084 0.002991139 -0.0857526 -0.00413084 -6.37159e-4 -0.08417969 -0.00413084 -0.001928627 -0.08469003 -0.00413084 -0.002926468 -0.0856558 -0.00413084 -0.003478825 -0.08692991 -0.00413084 -0.0028764 -0.08706003 -0.00413084 -0.002771615 -0.08653318 -0.00413084 -0.002121269 -0.0855599 -0.00413084 0.002771615 -0.08653318 -0.00413084 -0.001148045 -0.08490961 -0.00413084 0.002121269 -0.0855599 -0.00413084 0.001148045 -0.08490961 -0.00413084 0 -0.08468121 -0.00413084 -0.002999961 -0.08768123 -0.00413084 -0.003501534 -0.0883184 -0.00413084 -0.002991139 -0.08960986 -0.00413084 -0.002025425 -0.09060776 -0.00413084 -7.51324e-4 -0.09116005 -0.00413084 6.37162e-4 -0.09118276 -0.00413084 0.001928627 -0.09067237 -0.00413084 0.002926468 -0.08970665 -0.00413084 0.002771615 -0.08882927 -0.00413084 0.002121269 -0.08980256 -0.00413084 -0.002771615 -0.08882927 -0.00413084 0.001148045 -0.09045284 -0.00413084 -0.002121269 -0.08980256 -0.00413084 -0.001148045 -0.09045284 -0.00413084 0 -0.09068125 -0.00413084 0.001674652 -0.08526146 -0.005680263 -0.001674652 -0.09010094 -0.005680263 -0.001148045 -0.09045284 -0.005680263 0.002121269 -0.0855599 -0.005680263 0.002771615 -0.08653318 -0.005680263 0 -0.09068125 -0.005680263 0.001148045 -0.09045284 -0.005680263 0.002999961 -0.08768123 -0.005680263 0.002121269 -0.08980256 -0.005680263 0.002771615 -0.08882927 -0.005680263 -0.002121269 -0.08980256 -0.005680263 0.001148045 -0.08490961 -0.005680263 0 -0.08468121 -0.005680263 -0.002771615 -0.08882927 -0.005680263 -0.001148045 -0.08490961 -0.005680263 -0.002999961 -0.08768123 -0.005680263 -0.002771615 -0.08653318 -0.005680263 -0.002121269 -0.0855599 -0.005680263 + + + + + + + + + + 0.7013857 -0.712782 -4.90183e-7 0.7013856 -0.7127822 0 0.7013857 -0.712782 0 -0.7013856 0.7127821 0 -0.7013856 0.712782 0 -0.7013857 0.7127819 0 0.712782 0.7013857 0 0.7127824 0.7013853 0 0.701386 -0.7127817 0 0.7013857 -0.712782 0 0.7013853 -0.7127824 0 -0.7013857 0.712782 0 -0.7013857 0.712782 0 -0.7127825 -0.7013853 0 -0.712782 -0.7013857 0 0 0 -1 0.5040131 0.495955 -0.7071065 0.5040118 0.4959551 -0.7071073 0.7127831 0.7013846 0 0.7127822 0.7013854 0 0.5040128 0.4959534 0.7071079 0.5040138 0.4959544 0.7071064 0 0 1 1.70996e-7 0 1 0.7185755 0.6954489 -4.90183e-7 0.7185751 0.6954494 0 0.7185753 0.6954492 0 -0.7185752 -0.6954492 0 -0.7185752 -0.6954494 0 -0.7185751 -0.6954494 0 -0.6954478 0.7185766 0 -0.6954493 0.7185752 0 0.7185752 0.6954494 0 0.7185753 0.6954492 0 -0.7185751 -0.6954494 0 -0.7185754 -0.6954491 0 -0.7185751 -0.6954494 1.76021e-7 0.6954499 -0.7185747 0 0.6954489 -0.7185757 0 2.39887e-6 0 -1 -1.19943e-6 0 -1 -0.491756 0.5081108 -0.7071064 -0.4917582 0.5081082 -0.7071067 -0.6954489 0.7185757 0 -0.6954481 0.7185765 0 -0.4917567 0.5081105 0.7071062 -0.4917556 0.5081106 0.707107 -1.70996e-7 0 1 0 -1 1.26179e-5 0 -1 0 6.6104e-6 -1 -1.87907e-5 -1 0 0 1 -7.01628e-7 -3.02851e-7 1 -3.50814e-7 0 1.91311e-7 0 1 0 1 0 1 0 1.51425e-7 1 0 0 1 0 -1.51425e-7 1 1.75407e-7 -1.51425e-7 1 0 -3.02851e-7 -1 0 0 1 0 1.51425e-7 -1 1.75407e-7 -1.51425e-7 -1 0 -1.51425e-7 0 -1 6.30892e-6 0 -1 -3.4709e-5 0 0 1 -9.53226e-7 0 1 -4.3228e-7 0 1 1 -1.82302e-7 0 1 -2.73454e-7 0 -1 1.74458e-7 0 -1 0 0 -3.84519e-7 0 -1 3.63647e-5 0 -1 4.12282e-7 0 -1 -9.13896e-7 0 -1 4.37606e-7 0 -1 -2.41265e-7 0 -1 2.48112e-5 0 -1 9.13897e-7 0 -1 -1.77951e-7 0 -1 5.57993e-7 0 -1 -1 -1.82302e-7 0 -1 3.48915e-7 2.25909e-7 -1 0 0 -1 -3.48915e-7 0 -1 0 2.25909e-7 -1 0 -1.50606e-7 -1 3.48915e-7 0 -1 0 -1.50606e-7 1 0 -1.50606e-7 1 -1.74458e-7 0 1 0 1.50606e-7 1 2.61686e-7 -1.50606e-7 1 0 1.50606e-7 1 0 0 -1.04161e-4 0 1 -2.86813e-7 0 1 1 -1.75407e-7 0 0 0 -1 0 0 -1 -2.05466e-5 0 1 -5.0237e-6 -1 0 1.44137e-5 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 1 0 0 1 -1.96265e-7 0 1 0 0 -3.3031e-7 1 0 -3.3031e-7 1 0 -6.6062e-7 1 0 -6.6062e-7 1 0 0 -1 -2.32458e-5 -8.57603e-6 -1 2.3246e-5 -0.5663009 1.02645e-6 0.8241986 -0.5663006 0 0.8241988 -0.5663008 0 0.8241987 0.5663009 -3.17949e-7 0.8241986 0.5663 -4.23932e-7 0.8241993 -0.5663006 1.58975e-7 0.8241989 -0.5663008 0 0.8241987 -0.5663006 0 0.8241989 -0.5663003 0 0.824199 -0.5663007 0 0.8241987 -0.5663002 0 0.8241991 -0.5663003 0 0.8241991 -0.5663006 0 0.8241989 0.5662989 -1.20828e-7 0.8242 0.5663 0 0.8241991 0.5663019 -2.45611e-7 0.824198 0.5663002 0 0.8241991 0.5663006 0 0.8241989 0.5663006 0 0.8241989 0.5663001 0 0.8241992 0.5663002 0 0.8241991 0.5662998 0 0.8241994 0.5663006 1.58975e-7 0.8241989 0.5662993 0 0.8241998 -0.5555694 0.8314703 0 -0.5555698 0.83147 0 -0.555571 0.8314692 -2.03536e-6 -0.55557 0.8314698 0 -0.5555703 0.8314697 0 -0.5555699 0.8314698 -3.3805e-6 -0.1951152 0.9807804 0 0.195197 0.9807642 0 0.1951962 0.9807642 0 0.5555705 0.8314694 0 0.555571 0.8314692 0 0.5555695 0.8314701 0 0.5555721 0.8314684 0 0.5555698 0.83147 -9.83177e-7 0.5555709 0.8314692 -2.48229e-6 -0.930014 -0.367524 0 -0.9300139 -0.3675245 0 -0.9998663 0.01635259 0 -0.9174984 0.3977398 0 -0.9174985 0.3977394 0 -0.6954492 0.7185752 0 -0.3675243 0.9300139 0 -0.3675245 0.9300138 0 0.01635265 0.9998663 0 0.01635265 0.9998663 0 0.3977396 0.9174984 0 0.3977397 0.9174984 0 0.930014 0.3675242 0 0.9300139 0.3675246 0 0.9998663 -0.01635259 0 0.9998663 -0.01635211 0 0.9174985 -0.3977394 0 0.9174983 -0.3977398 0 0.6954492 -0.7185752 0 0.3675244 -0.9300139 0 0.3675245 -0.9300138 0 -0.01635265 -0.9998664 0 -0.01635265 -0.9998664 0 -0.3977397 -0.9174984 0 -0.3977397 -0.9174984 0 -0.7185753 -0.6954492 0 -0.7185752 -0.6954493 0 2.83943e-7 0 1 -1.34742e-6 0 1 1.89296e-7 0 1 -3.7859e-7 0 1 -1.13577e-6 0 1 6.7371e-7 0 1 1.26321e-7 0 1 3.78591e-7 0 1 1.23042e-6 0 1 -1.89295e-7 0 1 7.57181e-7 0 1 -1.34742e-6 0 1 -3.7859e-7 0 1 -1.26321e-7 0 1 0.3977401 0.9174982 0 0.39774 0.9174983 0 8.73836e-7 0 1 2.46486e-6 0 1 -6.16215e-7 0 1 6.16216e-7 0 1 -1.98391e-6 0 1 4.22733e-6 0 1 6.30456e-7 0 1 3.00637e-7 0 1 -2.34646e-7 0 1 2.91279e-7 0 1 6.16215e-7 0 1 -1.23243e-6 0 1 -4.22732e-6 0 1 9.91959e-7 0 1 1.20255e-6 0 1 3.51968e-7 0 1 -3.00637e-7 0 1 -0.7185752 -0.6954493 0 -0.7185754 -0.6954491 0 0.9300138 0.3675247 0 0.930014 0.3675245 0 0.7185752 0.6954492 0 0.7185753 0.6954492 0 -0.9300138 -0.3675245 0 -0.9300138 -0.3675245 0 0.9998663 -0.01635235 0 0.9998664 -0.01635265 0 -0.9998664 0.01635235 0 -0.9998664 0.01635235 0 0.9174982 -0.3977398 0 0.9174982 -0.3977401 0 -0.9174984 0.3977396 0 0.6954491 -0.7185754 0 0.6954494 -0.7185752 0 -0.6954491 0.7185754 0 0.3675246 -0.9300138 0 0.3675246 -0.9300139 0 -0.3675245 0.9300138 0 -0.3675245 0.930014 0 -0.01635229 -0.9998663 0 0.01635229 0.9998663 0 -0.3977401 -0.9174982 0 -0.3977398 -0.9174982 0 -5.61982e-7 0 -1 9.75682e-7 0 -1 0 0 -1 -5.61982e-7 0 -1 1.84636e-6 0 -1 5.81742e-7 0 -1 2.29691e-7 0 -1 -1.83753e-7 0 -1 -1.55716e-6 0 -1 2.13564e-6 0 -1 1.06782e-6 0 -1 -7.78582e-7 0 -1 1.95137e-6 0 -1 9.75684e-7 0 -1 6.79168e-7 0 -1 7.78582e-7 0 -1 0 0 -1 -1.83752e-7 0 -1 3.67505e-7 0 -1 -1.59723e-6 0 -1 -0.1950901 -0.9807854 0 -0.1950902 -0.9807853 0 -0.5555704 -0.8314695 0 -0.5555704 -0.8314695 0 -0.5555701 -0.8314697 0 -0.8314696 -0.5555703 0 -0.8314699 -0.55557 0 -0.9807853 -0.1950905 0 -0.9807853 -0.1950906 0 -0.9807853 0.1950906 0 -0.9807854 0.1950899 0 -0.9807854 0.1950904 -1.88245e-7 -0.8314696 0.5555703 0 -0.8314698 0.5555701 0 -0.5555704 0.8314695 0 -0.5555704 0.8314695 0 -0.1950901 0.9807854 0 -0.1950899 0.9807854 0 0.1950902 0.9807853 0 0.1950901 0.9807854 0 0.5555704 0.8314695 0 0.5555707 0.8314693 0 0.5555698 0.83147 0 0.8314696 0.5555703 0 0.8314693 0.5555709 0 0.9807854 0.1950901 0 0.9807853 -0.1950905 0 0.9807853 -0.1950902 0 0.9807854 -0.1950898 -2.21972e-7 0.8314698 -0.5555702 0 0.8314698 -0.55557 0 0.5555704 -0.8314697 0 0.5555704 -0.8314695 0 0.1950899 -0.9807854 0 0.19509 -0.9807854 0 0.7127842 -0.7013834 0 0.7127819 -0.7013857 0 0.7127828 -0.7013849 0 -0.7127833 0.7013843 0 -0.7127836 0.7013841 0 -0.7127807 0.701387 3.99133e-7 -0.7013818 -0.7127858 0 -0.7013878 -0.7127799 0 0.7127835 -0.7013842 0 0.7127824 -0.7013853 0 0.7127807 -0.7013871 7.09159e-7 -0.7127846 0.7013831 0 -0.7127819 0.7013859 0 -0.7127814 0.7013863 -9.38778e-7 0.7013827 0.712785 0 0.7013906 0.7127771 0 -1.19945e-6 0 -1 -0.4959464 -0.5040152 -0.707111 -0.4959524 -0.5040099 -0.7071105 -0.7013871 -0.7127806 0 -0.7013764 -0.712791 0 -0.4959497 -0.5040273 0.7071 -0.4959513 -0.5040145 0.707108 6.8398e-7 0 1 -0.6954489 -0.7185757 0 -0.6954488 -0.7185758 0 -0.6954491 -0.7185755 0 0.69545 0.7185745 0 0.6954479 0.7185766 0 0.6954531 0.7185716 7.98274e-7 -0.7185749 0.6954497 0 -0.7185688 0.6954559 0 -0.6954453 -0.7185791 0 -0.6954485 -0.7185759 0 -0.6954512 -0.7185734 0 0.6954511 0.7185735 0 0.6954486 0.7185759 0 0.6954494 0.7185751 0 0.7185823 -0.695442 0 0.7185743 -0.6954502 0 1.19943e-6 0 -1 -0.5081086 0.4917579 -0.7071067 -0.5081101 0.4917587 -0.7071051 -0.718569 0.6954557 0 -0.7185797 0.6954446 0 -0.5081138 0.4917591 0.7071021 -0.5081086 0.4917545 0.707109 1.36796e-6 0 1 -8.54984e-7 0 1 1 0 -7.3115e-6 1 0 1.13572e-5 1.10471e-6 -1 0 1.10471e-6 -1 0 0 0 1 0 0 1 0 -1 -1.91965e-7 0 0 -1 0 0 -1 5.86466e-7 0 -1 0 1 3.69571e-7 0 0 -1 -5.66917e-6 0 1 -1 -1.01901e-6 0 1 -5.58369e-6 0 1 0 5.85603e-7 1.10471e-6 -1 0 1.10471e-6 -1 0 -1 1.87787e-6 0 -1 2.82485e-5 0 1 0 -1.24816e-5 -1 -2.82488e-5 0 -1.6423e-5 0.5662661 0.8242226 0 0.5663031 0.8241971 0 0.5663009 0.8241987 0 -0.5662971 0.8242012 6.69537e-7 -0.5663037 0.8241968 0 0.5662974 0.8242011 0 0.5663034 0.8241969 0 0.5663037 0.8241968 0 0.5662968 0.8242015 0 -0.5663089 0.8241931 0 -0.5662968 0.8242015 3.92974e-7 -0.5662972 0.8242012 0 -0.5662974 0.8242011 1 8.19451e-6 0 -0.8314558 0.5555908 0 -0.8314718 0.555567 0 -0.8314681 0.5555726 -2.44244e-5 -0.8314711 0.5555682 0 -0.8314747 0.5555629 0 -0.8314654 0.5555768 0 -0.9805393 0.1963231 0 -0.9810232 0.1938903 0 -0.9805394 -0.1963225 0 -0.9810231 -0.1938909 0 -0.8314718 -0.555567 0 -0.8314515 -0.5555974 0 -0.8314532 -0.5555949 0 -0.8314667 -0.5555747 0 -0.8314673 -0.5555739 0 -0.8314737 -0.5555644 -9.9293e-6 0.367525 0.9300137 0 0.3675262 0.9300132 0 -0.01635259 0.9998663 0 -0.3977403 0.9174981 0 -0.7185757 0.6954488 0 -0.930013 0.3675268 0 -0.9998664 -0.0163502 0 -0.9998663 -0.01635766 0 -0.9174993 -0.3977373 0 -0.9174979 -0.3977405 0 -0.6954489 -0.7185755 0 -0.367525 -0.9300137 0 -0.3675262 -0.9300132 0 0.01635265 -0.9998663 0 0.3977376 -0.9174993 0 0.3977403 -0.9174981 0 0.7185757 -0.6954488 0 0.930013 -0.3675268 0 0.9998664 0.01635026 0 0.9998663 0.01635396 0 0.9174983 0.3977397 0 0.6954489 0.7185755 0 -3.78597e-7 0 1 1.47371e-7 0 1 -5.67882e-7 0 1 0 0 1 1.51435e-6 0 1 3.78588e-7 0 1 -1.34745e-6 0 1 3.78594e-7 0 1 -1.47374e-7 0 1 7.57176e-7 0 1 -1.51437e-6 0 1 1.34743e-6 0 1 -3.78591e-7 0 1 1.34742e-6 0 1 -0.9174966 -0.3977438 0 -0.9175001 -0.3977354 0 1.23244e-6 0 1 -1.23244e-6 0 1 -3.43467e-7 0 1 0 0 1 1.26091e-6 0 1 4.72845e-7 0 1 -1.23244e-6 0 1 3.43467e-7 0 1 0 0 1 -1.26091e-6 0 1 -4.7284e-7 0 1 0.6954481 0.7185763 0 -0.3675239 -0.9300142 0 -0.6954481 -0.7185763 0 0.3675239 0.9300142 0 0.01635068 -0.9998664 0 0.01635056 -0.9998664 0 -0.01635062 0.9998664 0 -0.01635062 0.9998664 0 0.3977404 -0.9174981 0 0.3977404 -0.9174981 0 -0.3977404 0.9174981 0 -0.3977404 0.9174981 0 0.7185762 -0.6954483 0 0.7185762 -0.6954482 0 -0.7185762 0.6954483 0 -0.7185738 0.6954509 0 0.9300128 -0.3675273 0 0.9300146 -0.367523 0 -0.9300148 0.367522 0 -0.9300148 0.3675221 0 0.9998664 0.01635354 0 0.9998664 0.0163486 0 -0.9998663 -0.0163536 0 -0.9998664 -0.01634865 0 0.9174966 0.3977438 0 0.9175001 0.3977354 0 0 0 -1 9.23191e-7 0 -1 -1.94646e-7 0 -1 -1.95137e-6 0 -1 7.78579e-7 0 -1 -1.99653e-7 0 -1 9.99089e-7 0 -1 0.9807851 0.1950918 0 0.9807866 0.195084 0 0.8314734 0.5555646 0 0.8314704 0.5555693 0 0.8314692 0.555571 6.5567e-6 0.55557 0.8314699 0 0.5555662 0.8314723 0 0.1950894 0.9807856 0 0.1950893 0.9807856 0 -0.195091 0.9807852 0 -0.1950938 0.9807847 0 -0.1950855 0.9807863 3.7069e-6 -0.55557 0.8314699 0 -0.5555662 0.8314723 0 -0.8314698 0.5555702 0 -0.8314698 0.5555699 0 -0.9807851 0.1950918 0 -0.9807866 0.195084 0 -0.9807866 -0.195084 0 -0.9807851 -0.1950918 0 -0.8314698 -0.5555702 0 -0.831469 -0.5555712 0 -0.8314705 -0.5555691 3.70696e-6 -0.55557 -0.8314699 0 -0.1950893 -0.9807856 0 -0.1950894 -0.9807856 0 0.1950879 -0.9807858 0 0.1950883 -0.9807857 0 0.1950904 -0.9807853 0 0.55557 -0.8314699 0 0.8314735 -0.5555644 0 0.9807866 -0.195084 0 0.9807851 -0.1950918 0 -0.7127842 0.7013834 0 -0.7127819 0.7013857 0 -0.7127828 0.7013849 0 0.7127833 -0.7013843 0 0.7127836 -0.7013841 0 0.7127807 -0.701387 1.59653e-6 0.7013818 0.7127858 0 0.7013878 0.7127799 0 -0.7127835 0.7013842 0 -0.7127824 0.7013853 0 -0.7127807 0.7013871 0 0.7127846 -0.7013831 0 0.7127819 -0.7013859 0 0.7127814 -0.7013863 -9.38778e-7 -0.7013827 -0.712785 0 -0.7013906 -0.7127771 0 1.19944e-6 0 -1 0.4959502 0.5040191 -0.7071056 0.4959539 0.5040113 -0.7071085 0.7013871 0.7127806 0 0.7013764 0.712791 0 0.4959521 0.5040298 0.7070966 0.4959513 0.5040145 0.707108 -6.83984e-7 0 1 0.6954489 0.7185757 7.84291e-6 0.6954488 0.7185758 0 0.6954491 0.7185755 0 -0.69545 -0.7185745 0 -0.6954479 -0.7185766 0 -0.6954531 -0.7185716 0 0.7185749 -0.6954497 0 0.7185688 -0.6954559 0 0.6954453 0.7185791 0 0.6954485 0.7185759 0 0.6954512 0.7185734 -7.09161e-7 -0.6954511 -0.7185735 0 -0.6954486 -0.7185759 0 -0.6954494 -0.7185751 9.38781e-7 -0.7185823 0.695442 0 -0.7185743 0.6954502 0 -1.19943e-6 0 -1 0.5081086 -0.4917579 -0.7071067 0.5081111 -0.4917597 -0.7071037 0.718569 -0.6954557 0 0.7185797 -0.6954446 0 0.5081114 -0.4917567 0.7071055 0.5081086 -0.4917545 0.707109 -1.36797e-6 0 1 8.54986e-7 0 1 -1 0 -7.3115e-6 -1 0 1.13572e-5 -1.10471e-6 1 -2.80651e-6 -1.10471e-6 1 0 0 0 1 0 1 1.98813e-6 0 -1 2.79132e-6 0 0 -1 -5.8634e-7 0 -1 0 -1 9.92594e-7 0 0 -1 5.66795e-6 0 1 1 1.01901e-6 0 -1 5.58369e-6 0 -1 0 5.85603e-7 -1.10471e-6 1 0 -1.10471e-6 1 0 1 -1.87787e-6 0 1 -2.82485e-5 0 -1 0 -1.24816e-5 1 2.82488e-5 0 1.6423e-5 -0.5662661 0.8242226 0 -0.5663009 0.8241987 -6.69529e-7 0.5662974 0.8242011 0 0.5663089 0.8241931 -3.92974e-7 0.5662972 0.8242012 -1 -8.19451e-6 0 0.8314558 -0.5555908 0 0.8314718 -0.555567 0 0.8314681 -0.5555726 -3.25658e-5 0.8314711 -0.5555682 0 0.8314747 -0.5555629 0 0.8314654 -0.5555768 0 0.9805393 -0.1963231 0 0.9810232 -0.1938903 0 0.9805394 0.1963225 0 0.9810231 0.1938909 0 0.8314718 0.555567 0 0.8314515 0.5555974 0 0.8314532 0.5555949 0 0.8314667 0.5555747 0 0.8314673 0.5555739 0 0.8314737 0.5555644 -9.9293e-6 0.01635259 -0.9998663 0 0.9998664 0.0163502 0 0.9998663 0.01635766 0 0.9174993 0.3977373 0 0.9174979 0.3977405 0 -0.01635265 0.9998663 0 -0.3977376 0.9174993 0 -0.9998664 -0.01635026 0 -0.9998663 -0.01635396 0 -0.9174983 -0.3977397 0 -1.47371e-7 0 1 5.67886e-7 0 1 0 0 1 1.47374e-7 0 1 -7.57181e-7 0 1 -1.34743e-6 0 1 3.43471e-7 0 1 -3.43463e-7 0 1 4.7284e-7 0 1 -0.01635068 0.9998664 0 -0.01635056 0.9998664 0 0.01635062 -0.9998664 0 0.01635062 -0.9998664 0 -0.7185762 0.6954482 0 0.7185738 -0.6954509 0 -0.9300128 0.3675273 0 -0.9300146 0.367523 0 0.9300148 -0.367522 0 0.9300148 -0.3675221 0 -0.9998664 -0.01635354 0 -0.9998664 -0.0163486 0 0.9998663 0.0163536 0 0.9998664 0.01634865 0 0 0 -1 -9.2317e-7 0 -1 1.94646e-7 0 -1 1.95137e-6 0 -1 -7.78579e-7 0 -1 1.99652e-7 0 -1 -9.99089e-7 0 -1 -0.8314734 -0.5555646 0 -0.8314704 -0.5555693 0 -0.8314692 -0.555571 4.37113e-6 -0.5555662 -0.8314723 0 0.195091 -0.9807852 0 0.1950938 -0.9807847 0 0.1950855 -0.9807863 0 0.5555662 -0.8314723 0 0.8314698 -0.5555699 0 0.8314698 0.5555702 0 0.831469 0.5555712 0 0.8314705 0.5555691 5.56044e-6 -0.1950879 0.9807858 0 -0.1950883 0.9807857 0 -0.1950904 0.9807853 0 -0.8314735 0.5555644 0 -0.7013851 0.7127826 -1.56859e-5 -0.7013856 0.7127821 0 -0.7013855 0.7127822 0 0.7013839 -0.7127838 0 0.7013843 -0.7127835 0 0.7013829 -0.7127847 -1.59654e-6 -0.7127801 -0.7013877 0 -0.7013856 0.7127822 0 -0.7013856 0.712782 2.83665e-6 0.7013841 -0.7127836 0 0.701384 -0.7127837 0 0.7013837 -0.712784 0 0.7127836 0.701384 0 -0.5040076 -0.4959549 -0.7071104 -0.5040181 -0.4959505 -0.7071061 -0.7127806 -0.7013871 0 -0.7127798 -0.701388 0 -0.5039986 -0.4959433 0.7071249 -0.5040261 -0.4959602 0.7070934 -0.718575 -0.6954495 0 -0.7185746 -0.69545 0 -0.7185745 -0.69545 0 0.7185745 0.69545 0 0.7185747 0.6954498 0 0.7185744 0.6954502 7.9827e-7 0.6954474 -0.7185771 0 0.6954481 -0.7185764 0 -0.7185764 -0.6954481 0 -0.7185725 -0.695452 0 0.7185726 0.695452 0 0.7185755 0.695449 0 -0.6954475 0.718577 0 -0.6954481 0.7185764 0 0.4917559 -0.5081093 -0.7071076 0.4917549 -0.5081096 -0.7071081 0.6954478 -0.7185767 0 0.6954476 -0.7185768 0 0.4917593 -0.5081132 0.7071024 0.4917588 -0.5081139 0.7071022 -1.70995e-7 0 1 0 1 5.04712e-5 -1 1.05244e-6 0 -1 1.05244e-6 0 0 1 3.78536e-5 4.85978e-5 0 -1 -4.12284e-7 0 -1 3.61898e-7 0 -1 -4.66855e-5 0 -1 0 0 -1 1.66236e-6 0 1 0 0 -1 -1 1.07946e-6 0 -1 1.07946e-6 0 0 1 -4.64914e-5 0 1 -2.3246e-5 0.5663058 -1.5397e-5 0.8241953 0.5662984 0 0.8242003 0.5663009 0 0.8241987 -0.5663021 0 0.8241978 -0.5662997 6.35898e-7 0.8241994 0.5663006 0 0.8241989 0.566299 0 0.8241999 0.5663 0 0.8241993 -0.5662988 0 0.8242001 -0.5662984 0 0.8242003 -0.5663031 4.421e-7 0.8241972 -0.5663 0 0.8241993 -0.566299 0 0.8241999 0 1 -8.1945e-6 0.5555825 -0.8314615 0 0.5555688 -0.8314707 0 0.5555754 -0.8314662 -3.25657e-5 0.5555819 -0.8314617 0 0.5555734 -0.8314676 0 0.5555776 -0.8314648 0 0.1945151 -0.9808996 0 0.1945252 -0.9808976 0 -0.1945151 -0.9808996 0 -0.1945252 -0.9808976 0 -0.5555688 -0.8314707 0 -0.5555887 -0.8314573 0 -0.5555695 -0.8314702 0 -0.5555887 -0.8314573 0 -0.5555762 -0.8314657 0 -0.5555846 -0.8314599 -3.97166e-5 0.9300134 0.3675255 0 0.9300134 0.367526 0 0.9998663 -0.01635301 0 0.9998664 -0.01635253 0 0.9174984 -0.3977397 0 0.9174983 -0.3977397 0 0.6954502 -0.7185744 0 0.3675256 -0.9300134 0 0.3675256 -0.9300135 0 -0.01635497 -0.9998663 0 -0.3977398 -0.9174984 0 -0.3977398 -0.9174984 0 -0.7185756 -0.6954489 0 -0.7185757 -0.6954488 0 -0.9300134 -0.3675255 0 -0.9300134 -0.367526 0 -0.9998663 0.01635307 0 -0.9998663 0.01635265 0 -0.917499 0.397738 0 -0.9174991 0.397738 0 -0.6954502 0.7185744 0 -0.3675256 0.9300134 0 -0.3675256 0.9300135 0 0.01635503 0.9998663 0 0.3977389 0.9174987 0 0.3977389 0.9174987 0 0.7185756 0.6954489 0 0.7185757 0.6954488 0 1.89293e-7 0 1 1.34743e-6 0 1 1.34742e-6 0 1 7.57181e-7 0 1 -1.34742e-6 0 1 1.13574e-6 0 1 3.78578e-7 0 1 -1.34739e-6 0 1 0 0 1 -1.89295e-7 0 1 -1.13575e-6 0 1 -3.78574e-7 0 1 1.34739e-6 0 1 0 0 1 -0.3977428 -0.917497 0 -0.3977428 -0.917497 0 2.91278e-7 0 1 1.23243e-6 0 1 -6.16213e-7 0 1 -6.30447e-7 0 1 6.30466e-7 0 1 3.00643e-7 0 1 2.34648e-7 0 1 -2.91272e-7 0 1 6.16237e-7 0 1 2.11366e-6 0 1 6.3046e-7 0 1 -3.00643e-7 0 1 -2.34641e-7 0 1 0.7185757 0.6954488 0 0.7185757 0.6954488 0 -0.9300144 -0.3675231 0 -0.7185757 -0.6954488 0 -0.7185757 -0.6954488 0 0.9300144 0.3675231 0 -0.9998664 0.0163508 0 -0.9998664 0.0163505 0 0.9998664 -0.0163508 0 0.9998664 -0.0163505 0 -0.917498 0.3977406 0 -0.9174981 0.3977404 0 0.917498 -0.3977406 0 0.9174981 -0.3977404 0 -0.6954474 0.7185771 0 -0.6954473 0.7185772 0 0.6954473 -0.7185772 0 -0.3675263 0.9300132 0 -0.3675264 0.9300131 0 0.3675253 -0.9300135 0 0.3675254 -0.9300135 0 0.01634788 0.9998664 0 -0.01634794 -0.9998664 0 0.3977428 0.917497 0 0.3977428 0.917497 0 -5.6198e-7 0 -1 -1.95137e-6 0 -1 9.75663e-7 0 -1 1.8294e-7 0 -1 -9.23177e-7 0 -1 2.29693e-7 0 -1 2.13558e-6 0 -1 1.06782e-6 0 -1 -7.78586e-7 0 -1 4.87832e-7 0 -1 6.79178e-7 0 -1 -2.66953e-7 0 -1 7.78583e-7 0 -1 0 0 -1 -3.99301e-7 0 -1 -4.99544e-7 0 -1 0.1950896 0.9807855 0 0.5555679 0.8314712 0 0.5555739 0.8314672 0 0.5555611 0.8314758 0 0.8314721 0.5555665 0 0.831472 0.5555666 0 0.9807853 0.1950905 0 0.9807854 0.19509 0 0.9807853 -0.1950905 0 0.9807853 -0.1950909 0 0.9807856 -0.1950892 1.85348e-6 0.8314723 -0.5555663 0 0.8314719 -0.5555669 0 0.5555681 -0.8314712 0 0.5555679 -0.8314712 0 0.1950896 -0.9807855 0 -0.1950896 -0.9807855 0 -0.5555681 -0.8314712 0 -0.5555608 -0.831476 0 -0.5555739 -0.8314672 -7.41388e-6 -0.8314701 -0.5555697 0 -0.8314703 -0.5555693 0 -0.9807855 -0.1950892 0 -0.9807857 -0.1950887 0 -0.9807857 0.1950887 0 -0.9807856 0.1950892 0 -0.9807856 0.1950894 2.18557e-6 -0.8314701 0.5555697 0 -0.8314703 0.5555693 0 -0.5555679 0.8314712 0 -0.5555681 0.8314712 0 -0.1950896 0.9807855 0 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0 -0.001999974 -0.001999974 0 -0.001999974 0.001421093 -7.65367e-4 -0.001847743 0.00131154 -7.65367e-4 -0.001847743 -0.001999974 -0.001414179 -0.001414179 9.99604e-4 -0.001414179 -0.001414179 -0.001999974 -0.001847743 -7.65367e-4 5.32729e-4 -0.001847743 -7.65367e-4 -0.001999974 -0.001999974 0 -1.79885e-5 -0.001999974 0 -0.001999974 -0.001847743 7.65367e-4 -5.68705e-4 -0.001847743 7.65367e-4 -0.001999974 -0.001414179 0.001414179 -0.001035571 -0.001414179 0.001414179 -0.001999974 -7.65367e-4 0.001847743 -0.001347482 -7.65367e-4 0.001847743 -0.001999974 0 0.001999974 -0.001457035 0 0.001999974 -0.001999974 7.65367e-4 0.001847743 -0.001999974 0 0.001999974 0.001999974 7.65367e-4 0.001847743 0.001999974 0.001414179 0.001414179 0.001999974 0.001414179 0.001414179 -0.001999974 0.001847743 7.65367e-4 0.001999974 0.001847743 7.65367e-4 -0.001999974 0.001999974 0 0.001999974 0.001999974 0 -0.001999974 0.001847743 -7.65367e-4 0.001999974 0.001847743 -7.65367e-4 -0.001999974 0.001414179 -0.001414179 0.001999974 0.001414179 -0.001414179 -0.001999974 -0.001414179 -0.001414179 0.001999974 -7.65367e-4 -0.001847743 0.001999974 0 -0.001999974 0.001999974 7.65367e-4 -0.001847743 0.001999974 -7.65367e-4 0.001847743 0.001999974 -0.001414179 0.001414179 0.001999974 -0.001847743 7.65367e-4 0.001999974 -0.001999974 0 0.001999974 -0.001847743 -7.65367e-4 0.001999974 7.65367e-4 -0.001847743 -0.001999974 7.65367e-4 -0.001847743 -0.001347482 0 -0.001999974 -0.001457035 0.01653528 -0.004334032 -9.65724e-4 0.02133989 -0.003939688 -4.56432e-4 0.001847743 7.65367e-4 5.32729e-4 0.001999974 0 -1.79885e-5 0.02345544 -4.78913e-4 0.001098155 0.0231958 7.50976e-4 0.001266658 0.001414179 0.001414179 9.99604e-4 0.02240127 0.002166092 0.001186668 7.65366e-4 0.001847743 0.00131154 0.02022266 0.003809988 0.001138865 0.001847743 -7.65367e-4 -5.68705e-4 0.02341061 -0.002114474 5.80571e-4 0 0.001999974 0.001421093 0.01448982 0.004217267 0.001118838 0.001414179 -0.001414179 -0.001035571 0.02314895 -0.003187358 1.38679e-4 0 0 0 -7.65368e-4 0.001847743 -0.001347482 0 0.001999974 -0.001457035 -0.01653528 0.004334032 -9.65724e-4 -0.02133989 0.003939688 -4.56432e-4 -0.001847743 -7.65367e-4 5.32729e-4 -0.001999974 0 -1.79885e-5 -0.02345544 4.78909e-4 0.001098155 -0.0231958 -7.50979e-4 0.001266658 -0.001414179 -0.001414179 9.99604e-4 -0.02240127 -0.002166092 0.001186668 -7.65366e-4 -0.001847743 0.00131154 -0.02022266 -0.003809988 0.001138865 -0.001847743 7.65367e-4 -5.68705e-4 -0.02341061 0.002114474 5.80571e-4 -0.01448982 -0.004217267 0.001118838 -0.001414179 0.001414179 -0.001035571 -0.02314895 0.003187358 1.38679e-4 8.03577e-4 -0.001669585 -0.001813113 0.02138286 -0.003702402 -8.94434e-4 0.01657199 -0.004173696 -0.001437842 3.67138e-5 -0.001839578 -0.001929223 0.001862168 8.94353e-4 4.98801e-5 0.02321308 8.96381e-4 7.88594e-4 0.02348321 -2.90873e-4 6.35759e-4 0.002027451 1.872e-4 -4.80802e-4 0.001414418 0.001484632 5.04594e-4 0.02240705 0.002253592 6.94454e-4 7.59125e-4 0.001859784 8.11758e-4 0.02021872 0.003864169 6.41829e-4 0.02344667 -0.001904726 1.28149e-4 0.001884579 -5.53324e-4 -0.001019954 -6.9277e-6 0.001999497 9.21166e-4 0.01448291 0.00421679 6.18956e-4 0.001456499 -0.001178562 -0.001474499 0.02318966 -0.002962052 -3.05808e-4 0 0 -5e-4 -8.03577e-4 0.001669585 -0.001813113 -0.02138286 0.003702402 -8.94434e-4 -0.01657199 0.004173696 -0.001437842 -3.67141e-5 0.001839578 -0.001929223 -0.001862168 -8.94354e-4 4.98801e-5 -0.02321308 -8.96385e-4 7.88594e-4 -0.02348321 2.90869e-4 6.35759e-4 -0.002027451 -1.87201e-4 -4.80802e-4 -0.001414418 -0.001484632 5.04594e-4 -0.02240705 -0.002253592 6.94454e-4 -7.59125e-4 -0.001859784 8.11758e-4 -0.02021872 -0.003864169 6.41829e-4 -0.02344667 0.001904726 1.28149e-4 -0.001884579 5.53324e-4 -0.001019954 6.928e-6 -0.001999497 9.21166e-4 -0.01448291 -0.00421679 6.18956e-4 -0.001456499 0.001178562 -0.001474499 -0.02318966 0.002962052 -3.05808e-4 -8.03577e-4 0.001669585 -0.001813113 -3.6714e-5 0.001839578 -0.001929223 -0.02318966 0.002962052 -3.05808e-4 -0.0408982 -0.04467964 -0.001999974 -0.0408982 -0.04467964 0.001421093 -0.04108291 -0.04392147 0.00131154 -0.04108291 -0.04392147 -0.001999974 -0.04154372 -0.04329168 9.99604e-4 -0.04154372 -0.04329168 -0.001999974 -0.04221045 -0.04288619 5.32729e-4 -0.04221045 -0.04288619 -0.001999974 -0.04298162 -0.04276669 -1.79885e-5 -0.04298162 -0.04276669 -0.001999974 -0.04373979 -0.0429514 -5.68705e-4 -0.04373979 -0.0429514 -0.001999974 -0.04436957 -0.0434122 -0.001035571 -0.04436957 -0.0434122 -0.001999974 -0.04477506 -0.04407894 -0.001347482 -0.04477506 -0.04407894 -0.001999974 -0.04489457 -0.04485011 -0.001457035 -0.04489457 -0.04485011 -0.001999974 -0.04470986 -0.04560828 -0.001999974 -0.04489457 -0.04485011 0.001999974 -0.04470986 -0.04560828 0.001999974 -0.04424905 -0.04623806 0.001999974 -0.04424905 -0.04623806 -0.001999974 -0.04358232 -0.04664355 0.001999974 -0.04358232 -0.04664355 -0.001999974 -0.04281115 -0.04676306 0.001999974 -0.04281115 -0.04676306 -0.001999974 -0.04205298 -0.04657834 0.001999974 -0.04205298 -0.04657834 -0.001999974 -0.0414232 -0.04611754 0.001999974 -0.0414232 -0.04611754 -0.001999974 -0.04154372 -0.04329168 0.001999974 -0.04108291 -0.04392147 0.001999974 -0.0408982 -0.04467964 0.001999974 -0.04101771 -0.0454508 0.001999974 -0.04477506 -0.04407894 0.001999974 -0.04436957 -0.0434122 0.001999974 -0.04373979 -0.0429514 0.001999974 -0.04298162 -0.04276669 0.001999974 -0.04221045 -0.04288619 0.001999974 -0.04101771 -0.0454508 -0.001999974 -0.04101771 -0.0454508 -0.001347482 -0.0408982 -0.04467964 -0.001457035 -0.03786164 -0.06110048 -9.65724e-4 -0.038051 -0.06591755 -4.56432e-4 -0.04358232 -0.04664355 5.32729e-4 -0.04281115 -0.04676306 -1.79885e-5 -0.04141849 -0.06817865 0.001098155 -0.04265832 -0.06797164 0.001266658 -0.04424905 -0.04623806 9.99604e-4 -0.044106 -0.06723815 0.001186668 -0.04470986 -0.04560828 0.00131154 -0.04584127 -0.06513154 0.001138865 -0.04205298 -0.04657834 -5.68705e-4 -0.03978627 -0.06806421 5.80571e-4 -0.04489457 -0.04485011 0.001421093 -0.04649245 -0.0594213 0.001118838 -0.0414232 -0.04611754 -0.001035571 -0.03872555 -0.06775707 1.38679e-4 -0.04289638 -0.04476487 0 -0.04477506 -0.04407894 -0.001347482 -0.04489457 -0.04485011 -0.001457035 -0.04793113 -0.02842926 -9.65724e-4 -0.04774183 -0.0236122 -4.56432e-4 -0.04221045 -0.04288619 5.32729e-4 -0.04298162 -0.04276669 -1.79885e-5 -0.04437434 -0.02135109 0.001098155 -0.04313451 -0.02155816 0.001266658 -0.04154372 -0.04329168 9.99604e-4 -0.04168677 -0.02229166 0.001186668 -0.04108291 -0.04392147 0.00131154 -0.03995156 -0.0243982 0.001138865 -0.04373979 -0.0429514 -5.68705e-4 -0.0460065 -0.02146559 5.80571e-4 -0.03930032 -0.03010851 0.001118838 -0.04436957 -0.0434122 -0.001035571 -0.04706722 -0.02177274 1.38679e-4 -0.04119402 -0.04549658 -0.001813113 -0.0382862 -0.06597059 -8.94434e-4 -0.03802031 -0.06114399 -0.001437842 -0.04105687 -0.04472315 -0.001929223 -0.04371058 -0.04666352 4.98801e-5 -0.04280287 -0.06799513 7.88594e-4 -0.04160517 -0.06821441 6.35759e-4 -0.04299706 -0.04679846 -4.80802e-4 -0.04431945 -0.04624134 5.04594e-4 -0.0441932 -0.06724768 6.94454e-4 -0.04472219 -0.04560256 8.11758e-4 -0.04589551 -0.06512993 6.41829e-4 -0.03999429 -0.06810909 1.28149e-4 -0.04226326 -0.04662424 -0.001019954 -0.04489439 -0.04484313 9.21166e-4 -0.04649227 -0.05941432 6.18956e-4 -0.04165679 -0.04616987 -0.001474499 -0.03894889 -0.06780731 -3.05808e-4 -0.04289638 -0.04476487 -5e-4 -0.04459875 -0.04403316 -0.001813113 -0.04750657 -0.02355915 -8.94434e-4 -0.04777246 -0.02838575 -0.001437842 -0.0447359 -0.04480659 -0.001929223 -0.04208219 -0.04286623 4.98801e-5 -0.04298996 -0.02153462 7.88594e-4 -0.0441876 -0.02131533 6.35759e-4 -0.04279577 -0.04273128 -4.80802e-4 -0.04147338 -0.0432884 5.04594e-4 -0.04159963 -0.02228212 6.94454e-4 -0.04107064 -0.04392719 8.11758e-4 -0.03989726 -0.02439987 6.41829e-4 -0.04579848 -0.02142065 1.28149e-4 -0.04352951 -0.04290556 -0.001019954 -0.04089838 -0.04468661 9.21166e-4 -0.0393005 -0.03011542 6.18956e-4 -0.04413598 -0.04335993 -0.001474499 -0.04684388 -0.02172249 -3.05808e-4 -0.04459875 -0.04403316 -0.001813113 -0.0447359 -0.04480659 -0.001929223 -0.04684388 -0.02172249 -3.05808e-4 0.04276669 -0.04298162 -0.001999974 0.04276669 -0.04298162 0.001421093 0.0429514 -0.04373979 0.00131154 0.0429514 -0.04373979 -0.001999974 0.0434122 -0.04436957 9.99604e-4 0.0434122 -0.04436957 -0.001999974 0.04407894 -0.04477506 5.32729e-4 0.04407894 -0.04477506 -0.001999974 0.04485011 -0.04489457 -1.79885e-5 0.04485011 -0.04489457 -0.001999974 0.04560828 -0.04470986 -5.68705e-4 0.04560828 -0.04470986 -0.001999974 0.04623806 -0.04424905 -0.001035571 0.04623806 -0.04424905 -0.001999974 0.04664355 -0.04358232 -0.001347482 0.04664355 -0.04358232 -0.001999974 0.04676306 -0.04281115 -0.001457035 0.04676306 -0.04281115 -0.001999974 0.04657834 -0.04205298 -0.001999974 0.04676306 -0.04281115 0.001999974 0.04657834 -0.04205298 0.001999974 0.04611754 -0.0414232 0.001999974 0.04611754 -0.0414232 -0.001999974 0.0454508 -0.04101771 0.001999974 0.0454508 -0.04101771 -0.001999974 0.04467964 -0.0408982 0.001999974 0.04467964 -0.0408982 -0.001999974 0.04392147 -0.04108291 0.001999974 0.04392147 -0.04108291 -0.001999974 0.04329168 -0.04154372 0.001999974 0.04329168 -0.04154372 -0.001999974 0.0434122 -0.04436957 0.001999974 0.0429514 -0.04373979 0.001999974 0.04276669 -0.04298162 0.001999974 0.04288619 -0.04221045 0.001999974 0.04664355 -0.04358232 0.001999974 0.04623806 -0.04424905 0.001999974 0.04560828 -0.04470986 0.001999974 0.04485011 -0.04489457 0.001999974 0.04407894 -0.04477506 0.001999974 0.04288619 -0.04221045 -0.001999974 0.04288619 -0.04221045 -0.001347482 0.04276669 -0.04298162 -0.001457035 0.03973013 -0.02656078 -9.65724e-4 0.03991949 -0.02174371 -4.56432e-4 0.0454508 -0.04101771 5.32729e-4 0.04467964 -0.0408982 -1.79885e-5 0.04328697 -0.01948261 0.001098155 0.04452681 -0.01968967 0.001266658 0.04611754 -0.0414232 9.99604e-4 0.04597449 -0.02042317 0.001186668 0.04657834 -0.04205298 0.00131154 0.04770976 -0.02252972 0.001138865 0.04392147 -0.04108291 -5.68705e-4 0.04165476 -0.01959711 5.80571e-4 0.04676306 -0.04281115 0.001421093 0.04836094 -0.02824002 0.001118838 0.04329168 -0.04154372 -0.001035571 0.04059404 -0.01990425 1.38679e-4 0.04476487 -0.04289638 0 0.04664355 -0.04358232 -0.001347482 0.04676306 -0.04281115 -0.001457035 0.04979962 -0.05923199 -9.65724e-4 0.04961031 -0.06404906 -4.56432e-4 0.04407894 -0.04477506 5.32729e-4 0.04485011 -0.04489457 -1.79885e-5 0.04624283 -0.06631016 0.001098155 0.04500299 -0.06610316 0.001266658 0.0434122 -0.04436957 9.99604e-4 0.04355525 -0.06536966 0.001186668 0.0429514 -0.04373979 0.00131154 0.04182004 -0.06326305 0.001138865 0.04560828 -0.04470986 -5.68705e-4 0.04787498 -0.06619572 5.80571e-4 0.0411688 -0.05755281 0.001118838 0.04623806 -0.04424905 -0.001035571 0.04893571 -0.06588858 1.38679e-4 0.0430625 -0.04216468 -0.001813113 0.04015469 -0.02169066 -8.94434e-4 0.03988879 -0.02651727 -0.001437842 0.04292535 -0.04293811 -0.001929223 0.04557907 -0.04099774 4.98801e-5 0.04467135 -0.01966613 7.88594e-4 0.04347366 -0.01944684 6.35759e-4 0.04486554 -0.04086279 -4.80802e-4 0.04618793 -0.04141992 5.04594e-4 0.04606169 -0.02041363 6.94454e-4 0.04659068 -0.0420587 8.11758e-4 0.047764 -0.02253139 6.41829e-4 0.04186278 -0.01955217 1.28149e-4 0.04413175 -0.04103708 -0.001019954 0.04676288 -0.04281812 9.21166e-4 0.04836076 -0.02824693 6.18956e-4 0.04352527 -0.04149144 -0.001474499 0.04081737 -0.019854 -3.05808e-4 0.04476487 -0.04289638 -5e-4 0.04646724 -0.04362809 -0.001813113 0.04937505 -0.06410211 -8.94434e-4 0.04964095 -0.0592755 -0.001437842 0.04660439 -0.04285466 -0.001929223 0.04395067 -0.04479503 4.98801e-5 0.04485845 -0.06612664 7.88594e-4 0.04605609 -0.06634593 6.35759e-4 0.04466426 -0.04492998 -4.80802e-4 0.04334187 -0.04437285 5.04594e-4 0.04346811 -0.0653792 6.94454e-4 0.04293912 -0.04373407 8.11758e-4 0.04176574 -0.06326144 6.41829e-4 0.04766696 -0.0662406 1.28149e-4 0.04539799 -0.04475575 -0.001019954 0.04276686 -0.04297465 9.21166e-4 0.04116898 -0.05754584 6.18956e-4 0.04600447 -0.04430139 -0.001474499 0.04871237 -0.06593883 -3.05808e-4 0.04646724 -0.04362809 -0.001813113 0.04660439 -0.04285466 -0.001929223 0.04871237 -0.06593883 -3.05808e-4 0.001868486 -0.08566129 -0.001999974 0.001868486 -0.08566129 0.001421093 0.00263381 -0.08581358 0.00131154 0.00263381 -0.08581358 -0.001999974 0.003282666 -0.08624708 9.99604e-4 0.003282666 -0.08624708 -0.001999974 0.00371623 -0.08689594 5.32729e-4 0.00371623 -0.08689594 -0.001999974 0.00386846 -0.08766132 -1.79885e-5 0.00386846 -0.08766132 -0.001999974 0.00371623 -0.0884267 -5.68705e-4 0.00371623 -0.0884267 -0.001999974 0.003282666 -0.0890755 -0.001035571 0.003282666 -0.0890755 -0.001999974 0.00263381 -0.08950906 -0.001347482 0.00263381 -0.08950906 -0.001999974 0.001868486 -0.0896613 -0.001457035 0.001868486 -0.0896613 -0.001999974 0.001103103 -0.08950906 -0.001999974 0.001868486 -0.0896613 0.001999974 0.001103103 -0.08950906 0.001999974 4.54273e-4 -0.0890755 0.001999974 4.54273e-4 -0.0890755 -0.001999974 2.07275e-5 -0.0884267 0.001999974 2.07275e-5 -0.0884267 -0.001999974 -1.31514e-4 -0.08766132 0.001999974 -1.31514e-4 -0.08766132 -0.001999974 2.07275e-5 -0.08689594 0.001999974 2.07275e-5 -0.08689594 -0.001999974 4.54273e-4 -0.08624708 0.001999974 4.54273e-4 -0.08624708 -0.001999974 0.003282666 -0.08624708 0.001999974 0.00263381 -0.08581358 0.001999974 0.001868486 -0.08566129 0.001999974 0.001103103 -0.08581358 0.001999974 0.00263381 -0.08950906 0.001999974 0.003282666 -0.0890755 0.001999974 0.00371623 -0.0884267 0.001999974 0.00386846 -0.08766132 0.001999974 0.00371623 -0.08689594 0.001999974 0.001103103 -0.08581358 -0.001999974 0.001103103 -0.08581358 -0.001347482 0.001868486 -0.08566129 -0.001457035 -0.01466679 -0.08332723 -9.65724e-4 -0.0194714 -0.08372163 -4.56432e-4 2.07275e-5 -0.0884267 5.32729e-4 -1.31514e-4 -0.08766132 -1.79885e-5 -0.02158695 -0.0871824 0.001098155 -0.02132731 -0.08841228 0.001266658 4.54273e-4 -0.0890755 9.99604e-4 -0.02053278 -0.08982741 0.001186668 0.001103103 -0.08950906 0.00131154 -0.01835417 -0.09147131 0.001138865 2.07275e-5 -0.08689594 -5.68705e-4 -0.02154213 -0.08554679 5.80571e-4 0.001868486 -0.0896613 0.001421093 -0.01262134 -0.09187865 0.001118838 4.54273e-4 -0.08624708 -0.001035571 -0.02128046 -0.08447396 1.38679e-4 0.001868486 -0.08766132 0 0.00263381 -0.08950906 -0.001347482 0.001868486 -0.0896613 -0.001457035 0.01840376 -0.09199541 -9.65724e-4 0.02320837 -0.09160101 -4.56432e-4 0.00371623 -0.08689594 5.32729e-4 0.00386846 -0.08766132 -1.79885e-5 0.02532392 -0.08814024 0.001098155 0.02506428 -0.0869103 0.001266658 0.003282666 -0.08624708 9.99604e-4 0.02426975 -0.08549523 0.001186668 0.00263381 -0.08581358 0.00131154 0.02209115 -0.08385127 0.001138865 0.00371623 -0.0884267 -5.68705e-4 0.0252791 -0.0897758 5.80571e-4 0.01635831 -0.08344399 0.001118838 0.003282666 -0.0890755 -0.001035571 0.02501744 -0.09084868 1.38679e-4 0.001064896 -0.08599168 -0.001813113 -0.01951438 -0.08395886 -8.94434e-4 -0.01470351 -0.08348762 -0.001437842 0.001831769 -0.08582168 -0.001929223 6.26221e-6 -0.08855569 4.98801e-5 -0.02134466 -0.08855772 7.88594e-4 -0.02161473 -0.08737045 6.35759e-4 -1.58966e-4 -0.08784854 -4.80802e-4 4.54016e-4 -0.08914595 5.04594e-4 -0.02053856 -0.08991491 6.94454e-4 0.001109361 -0.08952111 8.11758e-4 -0.01835024 -0.09152549 6.41829e-4 -0.02157819 -0.08575659 1.28149e-4 -1.6138e-5 -0.08710801 -0.001019954 0.0018754 -0.08966082 9.21166e-4 -0.01261442 -0.09187811 6.18956e-4 4.11976e-4 -0.0864827 -0.001474499 -0.02132117 -0.08469927 -3.05808e-4 0.001868486 -0.08766132 -5e-4 0.002672016 -0.08933097 -0.001813113 0.02325135 -0.09136372 -8.94434e-4 0.01844048 -0.09183502 -0.001437842 0.001905143 -0.08950096 -0.001929223 0.003730654 -0.08676695 4.98801e-5 0.02508163 -0.08676493 7.88594e-4 0.0253517 -0.08795219 6.35759e-4 0.003895938 -0.0874741 -4.80802e-4 0.003282904 -0.08617669 5.04594e-4 0.02427554 -0.08540773 6.94454e-4 0.002627611 -0.08580148 8.11758e-4 0.02208721 -0.08379715 6.41829e-4 0.02531516 -0.08956605 1.28149e-4 0.003753066 -0.08821463 -0.001019954 0.001861512 -0.08566182 9.21166e-4 0.0163514 -0.08344447 6.18956e-4 0.003324985 -0.08883988 -0.001474499 0.02505815 -0.09062337 -3.05808e-4 0.002672016 -0.08933097 -0.001813113 0.001905143 -0.08950096 -0.001929223 0.02505815 -0.09062337 -3.05808e-4 + + + + + + + + + + 0 -0.7462026 -0.665719 0.08095937 -0.9950895 0.05694371 -0.3826833 -0.9238796 0 -0.2855594 -0.6894015 -0.6657189 -0.6894015 -0.2855596 -0.6657187 -1 -2.17625e-7 0 -0.7462024 -1.22696e-7 -0.6657192 -0.9238796 0.3826835 0 -0.6894016 0.2855592 -0.6657187 -0.2855595 0.6894013 -0.6657189 -0.3826836 0.9238795 0 0 1 0 0 0.7462027 -0.6657189 0 0.7462028 0.6657188 0.2855593 0.6894014 0.6657189 0.7462024 2.09306e-7 -0.6657193 0.7462027 0 0.6657188 0.6894013 -0.2855595 0.6657189 0 -0.7462027 0.6657189 0.2855592 -0.6894014 0.665719 0.5276449 -0.5276449 0.665719 0.689402 0.2855592 0.6657183 0.5276449 0.5276451 0.665719 -0.5276449 -0.5276451 0.665719 -0.5276449 0.5276448 0.6657191 -0.7462028 0 0.6657188 -0.5276454 -0.5276448 -0.6657187 0.2855593 0.6894015 -0.6657189 0.6894013 0.2855597 -0.6657189 0.6894015 -0.2855592 -0.6657189 0.2855596 -0.6894013 -0.6657189 -0.7071067 -0.707107 0 -0.2855594 -0.6894015 0.6657189 -0.707107 0.7071067 0 -0.6894018 0.2855592 0.6657186 -0.9238794 -0.3826838 0 -0.6894017 -0.2855594 0.6657186 -0.2855592 0.6894014 0.665719 -0.3748962 -0.7816502 0.4984736 0.6311947 0.1767534 0.7552164 0.5248991 0.4826806 0.7010709 -0.1582986 -0.7873222 0.5958736 0.2573913 0.6935871 0.67282 -0.7081931 -0.4253229 0.5635272 -0.7082605 -0.1986545 0.6774241 0.6699832 -0.3351253 0.6624301 -0.817855 0.0142318 0.5752485 -0.02832227 0.7650859 0.6433052 -0.5823978 0.01877319 0.8126872 -0.357304 0.2884959 0.8883153 0.1679158 -0.9497295 0.2642319 0.5648971 -0.7122579 0.4166294 0.41309 -0.5338768 0.7377888 0.9653253 0.1375148 0.2218936 0.07708626 0.9719986 0.2219831 -0.1679159 0.9497294 0.2642319 0.5878704 0.6405184 0.49411 0.7081931 0.4253231 0.5635272 -0.6717817 0.1170585 0.7314416 -0.6311947 -0.1767534 0.7552163 0.374896 0.7816503 0.4984737 0.7082605 0.1986545 0.6774241 -0.8025102 0.3241897 0.500878 0.1582985 0.7873218 0.5958741 -0.2573911 -0.6935855 0.6728217 0.5823978 -0.01877266 0.8126872 -0.7079404 0.6868429 0.1645214 -0.227101 0.8081443 -0.5434408 0.04681378 -0.4709634 -0.8809098 -0.7987827 0.1411343 -0.584831 -0.6431276 0.2793524 -0.7129861 0.7421983 0.3454436 -0.5742912 0.783652 0.2218073 -0.580251 -0.6109308 0.4729923 -0.6348559 -0.6039934 0.01654142 -0.7968177 0.5849545 0.5077975 -0.6324319 -0.384606 -0.37048 -0.845472 0.2669962 0.7314997 -0.6273924 0.772009 0.1294873 -0.6222823 -0.863177 0.02027082 -0.5044946 -0.03747242 0.6877762 -0.7249551 -0.4273026 0.7637783 -0.4837924 0.2818456 -0.3080278 -0.9086704 0.2271012 -0.8081442 -0.5434409 -0.2334834 0.02328401 -0.972082 -0.02981293 0.340254 -0.9398608 0.7987845 -0.1411336 -0.5848289 0.6431276 -0.2793523 -0.7129862 -0.7421985 -0.3454434 -0.5742911 -0.7836518 -0.2218074 -0.5802511 0.6039935 -0.0165416 -0.7968176 -0.5849545 -0.5077975 -0.6324318 0.2584314 -0.7192381 -0.6449108 -0.667337 0.2068901 -0.7154424 0.3683512 -0.6397519 -0.6745628 -0.7687523 -0.1133454 -0.6294226 -0.8743168 -0.2032756 0.4407372 0.6717818 -0.1170586 0.7314414 -0.05454945 -0.9115495 0.4075561 0.3846062 0.3704797 -0.845472 0.6109308 -0.472992 -0.6348561 -0.5248991 -0.482681 0.7010706 0.02832239 -0.7650857 0.6433054 -0.2669953 -0.7314993 -0.6273933 0.03747254 -0.6877762 -0.724955 -0.5276448 0.527645 -0.665719 0.5276448 0.5276451 -0.6657189 0.5276453 -0.5276447 -0.6657188 -0.5878705 -0.6405183 0.4941098 -0.5396548 0.6347205 -0.5530848 0.6673443 -0.2068942 -0.7154344 0.2271012 -0.8081443 -0.5434408 0.7987844 -0.1411337 -0.584829 0.863176 -0.02027118 -0.5044961 -0.6673444 0.206894 -0.7154344 0.7455248 0.03179866 -0.6657189 0.906734 0.4217031 0 0.9976353 -0.03848809 0.05694246 0.676608 0.3146756 -0.6657184 0.2559248 0.7009432 -0.6657185 -0.0317952 0.7455247 -0.6657192 -0.04261016 0.9990919 0 -0.3146753 0.6766077 -0.6657188 -0.4217045 0.9067333 0 -0.7009429 0.2559249 -0.6657187 -0.9990918 -0.04261201 0 -0.9393478 0.3429663 0 -0.745525 -0.03179585 -0.6657188 -0.6766076 -0.3146756 0.6657188 -0.7455248 -0.03179281 0.6657193 0.03179609 -0.7455247 -0.6657192 0.3146747 -0.676608 0.6657187 0.0317955 -0.7455248 0.6657191 0.745525 0.03179413 0.665719 0.5496467 -0.5046846 0.6657192 0.7009418 -0.2559272 0.665719 -0.5046818 -0.5496491 0.6657193 -0.2559243 -0.7009434 0.6657186 0.504682 0.5496488 0.6657193 -0.5496481 0.5046825 0.6657196 -0.03179591 0.7455247 0.6657192 0.5046839 0.549647 -0.6657195 -0.6766074 -0.3146761 -0.6657187 -0.2559258 -0.7009428 -0.6657187 0.314677 -0.6766068 -0.6657189 0.700944 -0.2559227 -0.6657186 0.6763354 0.7365938 0 0.6766076 0.3146761 0.6657186 -0.7365952 0.6763339 0 -0.314675 0.676608 0.6657186 0.3429685 0.9393469 0 0.2559235 0.7009438 0.6657184 -0.7009431 0.2559249 0.6657186 0.7649651 0.4078625 0.4984744 -0.459876 -0.5449901 0.7010705 -0.1496988 -0.6381551 0.7552141 0.7798629 0.1917027 0.5958725 -0.681987 -0.2867105 0.6728231 0.3947595 0.7256764 0.5635235 0.3633663 -0.6550991 0.6624275 0.1682943 0.716083 0.6774232 -0.04906916 0.8165074 0.5752459 -0.765596 -0.004304528 0.6433073 -0.04357326 0.5810694 0.8126868 0.9560213 -0.1272945 0.2642339 -0.3034556 0.344686 0.8883165 0.7356837 -0.5340338 0.4166263 0.5509896 -0.3899658 0.7377922 -0.9678309 -0.1184346 0.2219837 -0.09625303 -0.9703084 0.2218946 -0.9560213 0.1273009 0.2642307 -0.6148878 -0.6146292 0.4941093 -0.1455783 0.6661823 0.7314425 -0.3947584 -0.725676 0.5635249 0.1496996 0.6381526 0.7552161 -0.7649654 -0.407863 0.4984735 -0.3580898 0.7879662 0.5008803 -0.1682934 -0.7160825 0.6774241 0.6819889 0.2867107 0.6728211 -0.7798627 -0.1917032 0.5958728 -0.716387 0.678029 0.1645187 0.0435726 -0.5810685 0.8126874 -0.8170879 0.1924597 -0.5434396 -0.175049 0.792034 -0.5848421 0.4725317 -0.02670288 -0.8809091 -0.3065029 0.630638 -0.712988 -0.1882129 -0.7923859 -0.5802591 -0.3135039 -0.7562432 -0.5742923 -0.4985941 0.5902202 -0.6348577 -0.04226207 0.602741 -0.796817 -0.482411 -0.60606 -0.6324326 0.3537545 0.4000416 -0.8454729 -0.7194592 -0.2979241 -0.6273913 -0.09648007 -0.7768225 -0.6222849 -0.05703401 0.8615258 -0.5045002 -0.6887509 0.008130908 -0.7249525 -0.7812932 0.39437 -0.4837904 0.3197576 -0.2684645 -0.9086704 0.8170879 -0.1924601 -0.5434395 -0.3412169 0.01528608 -0.9398603 -0.03320986 0.2322808 -0.9720817 0.1750516 -0.7920293 -0.5848476 0.3065037 -0.6306387 -0.712987 0.1882125 0.7923927 -0.58025 0.3135063 0.7562432 -0.5742909 0.04226112 -0.6027407 -0.7968172 0.4824105 0.6060616 -0.6324313 0.7295984 -0.22755 -0.6449087 -0.235139 0.657912 -0.715445 0.6548674 -0.3407562 -0.6745621 0.08048552 0.7728857 -0.6294202 0.1658352 0.8821812 0.4407438 0.1455777 -0.6661909 0.7314348 0.9083966 0.09334158 0.4075574 -0.3537541 -0.4000416 -0.8454732 0.4985966 -0.5902203 -0.6348556 0.4598743 0.5449897 0.701072 0.7655984 0.004303276 0.6433045 0.6887478 -0.008132696 -0.7249554 0.7194588 0.2979215 -0.6273929 -0.5496482 0.5046826 -0.6657195 -0.504683 -0.5496483 -0.6657191 0.5496493 -0.5046815 -0.6657193 0.6148877 0.6146301 0.4941083 -0.6571398 0.512119 -0.5530837 0.2351419 -0.657922 -0.7154348 0.05703675 -0.8615267 -0.5044986 -0.2351435 0.657919 -0.715437 -0.7455248 -0.03179848 -0.6657189 -0.906734 -0.4217032 0 -0.9976354 0.03848469 0.05694341 -0.6766065 -0.3146781 -0.6657187 -0.2559248 -0.7009432 -0.6657185 0.03179579 -0.7455246 -0.6657192 0.04261058 -0.9990918 0 0.3146759 -0.6766076 -0.6657187 0.4217039 -0.9067336 0 0.7009436 -0.255924 -0.6657184 0.9990918 0.04261124 0 0.9393488 -0.3429638 0 0.7455245 0.03179579 -0.6657194 0.6766064 0.3146775 0.6657192 0.7455248 0.03179281 0.6657193 -0.03179615 0.7455246 -0.6657192 -0.3146754 0.6766078 0.6657186 -0.03179633 0.7455247 0.6657192 -0.7455248 -0.03179454 0.665719 -0.5496484 0.5046824 0.6657195 -0.7009429 0.2559248 0.6657188 0.5046803 0.5496507 0.6657191 0.2559241 0.7009434 0.6657186 -0.5046829 -0.5496482 0.6657192 0.5496463 -0.5046849 0.6657193 0.03179556 -0.7455247 0.6657191 -0.5046815 -0.5496497 -0.6657191 0.6766088 0.3146734 -0.6657186 0.2559241 0.7009435 -0.6657185 -0.3146755 0.6766077 -0.6657187 -0.700944 0.2559227 -0.6657186 -0.6763349 -0.7365944 0 -0.6766079 -0.3146745 0.6657189 0.7365942 -0.676335 0 0.3146744 -0.6766083 0.6657186 -0.3429695 -0.9393466 0 -0.2559258 -0.7009428 0.6657187 0.7009417 -0.2559276 0.665719 -0.764965 -0.4078633 0.4984737 0.4598755 0.5449894 0.7010715 0.1496992 0.6381525 0.7552164 -0.7798621 -0.1917039 0.5958732 0.681988 0.2867115 0.6728216 -0.3947595 -0.7256749 0.5635256 -0.3633685 0.6550941 0.6624312 -0.1682949 -0.7160849 0.677421 0.04906517 -0.8165042 0.5752508 0.765596 0.00430423 0.6433073 0.04357218 -0.5810691 0.812687 -0.9560216 0.127295 0.2642325 0.3034564 -0.3446887 0.8883152 -0.7356817 0.5340346 0.4166288 -0.5509892 0.3899695 0.7377905 0.9678309 0.1184343 0.2219837 0.0962544 0.9703086 0.2218928 0.9560208 -0.1272993 0.2642333 0.6148896 0.6146296 0.4941064 0.1455783 -0.6661955 0.7314305 0.3947587 0.7256748 0.563526 -0.1496989 -0.6381545 0.7552147 0.7649644 0.4078623 0.4984756 0.3580877 -0.7879719 0.5008729 0.1682946 0.7160839 0.6774223 -0.6819881 -0.2867103 0.6728221 0.7798626 0.191703 0.5958727 0.7163875 -0.6780288 0.1645177 -0.04357349 0.5810688 0.8126873 0.8170869 -0.1924606 -0.543441 0.1750447 -0.7920413 -0.5848334 -0.472532 0.02670228 -0.8809089 0.3065026 -0.6306371 -0.7129888 0.1882129 0.7923938 -0.5802484 0.3135059 0.7562437 -0.5742905 0.4985944 -0.5902203 -0.6348572 0.04226189 -0.6027392 -0.7968183 0.4824109 0.6060609 -0.6324318 -0.3537521 -0.4000453 -0.8454722 0.7194578 0.2979224 -0.6273937 0.09647488 0.7768262 -0.6222811 0.05703181 -0.8615217 -0.5045075 0.6887508 -0.008131206 -0.7249526 0.7812935 -0.3943697 -0.4837903 -0.3197572 0.2684646 -0.9086706 -0.8170876 0.1924616 -0.5434395 0.3412169 -0.01528638 -0.9398604 0.03321045 -0.2322807 -0.9720817 -0.1750495 0.792033 -0.5848432 -0.3065018 0.6306356 -0.7129905 -0.1882119 -0.7923818 -0.5802651 -0.313505 -0.7562438 -0.574291 -0.04226082 0.6027417 -0.7968164 -0.4824106 -0.6060609 -0.632432 -0.7295985 0.22755 -0.6449086 0.2351387 -0.6579131 -0.7154441 -0.6548658 0.3407555 -0.674564 -0.08048909 -0.7728805 -0.6294261 -0.1658367 -0.8821825 0.4407408 -0.145578 0.6661812 0.7314436 -0.9083964 -0.09334224 0.4075578 0.3537537 0.4000431 -0.8454726 -0.4985963 0.5902209 -0.6348551 -0.4598749 -0.5449903 0.7010712 -0.7655987 -0.004303872 0.6433042 -0.688747 0.008132338 -0.7249562 -0.7194598 -0.2979237 -0.6273908 0.5496483 -0.5046825 -0.6657195 0.5046837 0.5496472 -0.6657195 -0.549648 0.5046826 -0.6657196 -0.6148885 -0.6146296 0.4941079 0.657138 -0.5121173 -0.5530872 -0.2351421 0.657922 -0.7154347 -0.05703562 0.8615291 -0.5044946 0.2351422 -0.6579188 -0.7154377 -3.10351e-7 0.7462036 -0.6657178 -0.08096092 0.9950889 0.05695182 0.3826845 0.9238792 0 0.2855598 0.6894004 -0.6657196 0.6894008 0.2855597 -0.6657193 1 1.54151e-6 0 0.7462028 1.52108e-6 -0.6657188 0.923879 -0.3826848 0 0.6894016 -0.2855603 -0.6657183 0.28556 -0.6894021 -0.6657179 0.3826839 -0.9238794 0 0 -1 0 0 -0.7462019 -0.6657198 0 -0.7462019 0.6657198 -0.2855598 -0.6894021 0.665718 -0.7462027 0 -0.6657189 -0.7462028 0 0.6657187 -0.6894011 0.2855591 0.6657193 -3.60873e-7 0.7462036 0.665718 -0.2855589 0.6894004 0.6657202 -0.5276443 0.5276465 0.6657183 -0.689401 -0.285561 0.6657186 -0.5276447 -0.527644 0.6657199 0.5276448 0.5276455 0.6657186 0.5276448 -0.5276439 0.6657199 0.7462028 1.56618e-6 0.6657188 0.5276442 0.5276459 -0.6657187 -0.2855599 -0.6894021 -0.665718 -0.6894011 -0.285561 -0.6657185 -0.6894015 0.285559 -0.665719 -0.2855592 0.6894005 -0.6657199 0.7071064 0.7071072 0 0.2855596 0.6894004 0.6657198 0.7071072 -0.7071065 0 0.6894012 -0.2855603 0.6657187 0.9238795 0.3826836 0 0.689401 0.2855598 0.6657192 0.2855601 -0.689402 0.665718 0.3748966 0.781649 0.498475 -0.6311954 -0.1767513 0.7552161 -0.5248981 -0.4826796 0.7010725 0.1582983 0.7873291 0.5958645 -0.2573927 -0.6935856 0.672821 0.7081932 0.4253179 0.5635309 0.7082578 0.1986523 0.6774277 -0.6699869 0.3351221 0.662428 0.8179191 -0.01422673 0.5751573 0.0283221 -0.7650799 0.6433123 0.582392 -0.01877611 0.8126913 0.3573055 -0.288505 0.8883117 -0.167915 0.9497284 0.2642359 -0.5648927 0.7122582 0.4166351 -0.4130837 0.5338729 0.7377951 -0.9653531 -0.1374804 0.2217944 -0.07708686 -0.9719977 0.2219867 0.167918 -0.9497307 0.2642259 -0.5878692 -0.6405211 0.4941079 -0.7081959 -0.4253249 0.5635223 0.6717795 -0.1170623 0.7314429 0.6311936 0.1767559 0.7552165 -0.3748962 -0.7816454 0.498481 -0.7082607 -0.1986582 0.6774228 0.8025099 -0.3241881 0.5008794 -0.1583018 -0.7873246 0.5958697 0.2573919 0.6935891 0.6728177 -0.5823986 0.01877582 0.8126866 0.7079401 -0.6868436 0.1645199 0.2270929 -0.8081509 -0.5434345 -0.04681378 0.4709674 -0.8809076 0.7987381 -0.1411775 -0.5848817 0.6431273 -0.2793527 -0.7129862 -0.742201 -0.3454418 -0.5742889 -0.7836484 -0.2218055 -0.5802565 0.6109306 -0.4729927 -0.6348558 0.6039939 -0.01653212 -0.7968176 -0.5849552 -0.5077995 -0.6324295 0.3846091 0.3704743 -0.8454731 -0.2669942 -0.7315006 -0.6273923 -0.7720052 -0.1294935 -0.6222857 0.8631245 -0.02027738 -0.5045839 0.03747326 -0.6877831 -0.7249485 0.4273028 -0.7637795 -0.4837906 -0.2818462 0.308034 -0.9086682 -0.2271057 0.8081416 -0.543443 0.2334829 -0.02328026 -0.9720821 0.02981233 -0.340258 -0.9398595 -0.7987309 0.1411525 -0.5848974 -0.6431262 0.2793472 -0.7129895 0.7421988 0.3454467 -0.5742887 0.7836537 0.2218036 -0.5802502 -0.6039999 0.01653999 -0.7968128 0.5849588 0.5078008 -0.6324253 -0.2584329 0.7192396 -0.6449084 0.667337 -0.2068899 -0.7154424 -0.3683511 0.6397474 -0.6745671 0.7687532 0.1133442 -0.6294216 0.8743509 0.2032626 0.4406754 -0.6717849 0.1170606 0.7314382 0.05455005 0.9115486 0.4075579 -0.3845989 -0.3704783 -0.8454759 -0.6109272 0.4729974 -0.6348554 0.5248938 0.4826764 0.7010778 -0.02832227 0.7650817 0.6433103 0.2669939 0.7314968 -0.6273969 -0.03747266 0.6877813 -0.7249501 0.5276443 -0.5276443 -0.6657201 -0.5276443 -0.5276442 -0.6657201 -0.5276439 0.5276466 -0.6657185 0.5878688 0.64052 0.4941098 0.5396559 -0.6347213 -0.5530827 -0.6673502 0.2068974 -0.715428 -0.8631843 0.02027374 -0.5044817 0.667343 -0.206893 -0.715436 + + + + + + + + + + + + + + +

0 0 1 1 2 2 0 0 2 2 3 3 7 4 8 5 9 6 9 6 10 7 11 8 15 9 14 10 16 11 15 9 16 11 17 12 16 11 19 13 20 14 26 15 25 16 27 17 33 18 34 19 29 20 29 20 27 17 25 16 25 16 23 21 21 22 21 22 20 14 19 13 31 23 33 18 29 20 21 22 19 13 36 24 36 24 38 25 31 23 21 22 36 24 31 23 34 19 1 1 0 0 3 3 5 26 7 4 15 9 17 12 18 27 24 28 26 15 28 29 40 30 3 3 7 4 15 9 18 27 24 28 4 31 2 2 32 32 12 33 10 7 37 34 12 33 37 34 36 24 6 35 4 31 31 23 6 35 31 23 39 36 8 5 39 36 38 25 2 2 1 1 33 18 2 2 33 18 32 32 16 11 14 10 35 37 10 7 8 5 38 25 49 38 48 39 50 40 51 41 49 38 50 40 51 41 50 40 52 42 46 43 53 44 54 45 55 46 52 42 56 47 57 48 41 49 44 50 57 48 44 50 58 51 53 44 57 48 58 51 53 44 58 51 54 45 60 52 61 53 62 54 60 52 62 54 63 55 64 56 65 57 66 58 64 56 66 58 67 59 68 60 64 56 67 59 65 57 72 61 73 62 1 1 70 63 71 64 72 61 75 65 76 66 77 67 79 68 80 69 81 70 82 71 83 72 81 70 83 72 84 73 85 74 86 75 82 71 85 74 82 71 81 70 87 76 88 77 86 75 84 73 83 72 89 78 91 79 92 80 88 77 93 81 78 82 77 67 96 83 97 84 98 85 96 83 98 85 99 86 100 87 101 88 102 89 104 90 105 91 101 88 104 90 101 88 100 87 112 92 113 93 97 84 112 92 97 84 96 83 109 94 108 95 113 93 109 94 113 93 112 92 41 49 93 81 77 67 51 41 55 46 91 79 51 41 91 79 87 76 42 96 77 67 80 69 53 44 46 43 84 73 52 42 50 40 86 75 52 42 86 75 88 77 50 40 48 39 82 71 50 40 82 71 86 75 48 39 47 97 83 72 44 50 43 98 79 68 47 97 54 45 89 78 47 97 89 78 83 72 43 98 42 96 80 69 55 46 92 80 91 79 68 60 70 63 106 99 64 56 68 60 104 90 60 52 112 92 96 83 65 57 100 87 103 100 61 53 60 52 96 83 61 53 96 83 99 86 72 61 65 57 103 100 72 61 103 100 109 94 73 62 76 66 113 93 73 62 113 93 108 95 69 101 67 59 101 88 76 66 97 84 113 93 74 102 107 103 111 104 63 55 62 54 98 85 66 58 108 95 102 89 62 54 61 53 99 86 62 54 99 86 98 85 3 3 2 2 4 31 3 3 4 31 5 26 5 26 4 31 6 35 5 26 6 35 7 4 7 4 6 35 8 5 9 6 8 5 10 7 11 8 10 7 12 33 11 8 12 33 13 105 13 105 12 33 14 10 13 105 14 10 15 9 18 27 17 12 16 11 16 11 20 14 18 27 18 27 20 14 21 22 18 27 21 22 22 106 22 106 21 22 23 21 22 106 23 21 24 28 24 28 23 21 25 16 24 28 25 16 26 15 26 15 27 17 28 29 28 29 27 17 29 20 28 29 29 20 30 107 31 23 32 32 33 18 19 13 35 37 36 24 36 24 37 34 38 25 38 25 39 36 31 23 29 20 25 16 21 22 31 23 29 20 21 22 30 107 29 20 34 19 30 107 34 19 40 30 0 0 40 30 34 19 34 19 33 18 1 1 40 30 0 0 3 3 7 4 9 6 11 8 11 8 13 105 15 9 18 27 22 106 24 28 28 29 30 107 40 30 7 4 11 8 15 9 24 28 28 29 40 30 40 30 7 4 15 9 15 9 24 28 40 30 4 31 32 32 31 23 14 10 12 33 36 24 14 10 36 24 35 37 8 5 6 35 39 36 16 11 35 37 19 13 10 7 38 25 37 34 41 49 42 96 43 98 41 49 43 98 44 50 45 108 46 43 47 97 45 108 47 97 48 39 49 38 45 108 48 39 46 43 54 45 47 97 55 46 51 41 52 42 77 67 78 82 79 68 87 76 86 75 85 74 84 73 89 78 90 109 91 79 88 77 87 76 93 81 94 110 78 82 90 109 89 78 94 110 90 109 94 110 93 81 49 38 51 41 87 76 49 38 87 76 85 74 57 48 53 44 90 109 57 48 90 109 93 81 45 108 49 38 85 74 45 108 85 74 81 70 41 49 57 48 93 81 46 43 45 108 81 70 46 43 81 70 84 73 42 96 41 49 77 67 53 44 84 73 90 109 54 45 58 51 94 110 54 45 94 110 89 78 58 51 44 50 78 82 58 51 78 82 94 110 48 39 83 72 82 71 56 47 52 42 88 77 56 47 88 77 92 80 44 50 79 68 78 82 43 98 80 69 79 68 55 46 56 47 92 80 68 60 67 59 69 101 70 63 68 60 69 101 70 63 69 101 71 64 65 57 73 62 66 58 1 1 71 64 74 102 75 65 60 52 63 55 75 65 63 55 76 66 72 61 76 66 73 62 114 111 97 84 98 85 114 111 98 85 115 112 100 87 102 89 103 100 106 99 107 103 105 91 106 99 105 91 104 90 103 100 102 89 108 95 103 100 108 95 109 94 110 113 111 104 107 103 110 113 107 103 106 99 112 92 116 114 97 84 112 92 97 84 114 111 109 94 108 95 116 114 109 94 116 114 112 92 68 60 106 99 104 90 75 65 72 61 109 94 75 65 109 94 112 92 64 56 104 90 100 87 60 52 75 65 112 92 60 52 112 92 114 111 65 57 64 56 100 87 70 63 1 1 110 113 70 63 110 113 106 99 61 53 60 52 114 111 61 53 114 111 115 112 71 64 69 101 105 91 71 64 105 91 107 103 73 62 76 66 116 114 73 62 116 114 108 95 69 101 101 88 105 91 76 66 63 55 97 84 76 66 97 84 116 114 67 59 66 58 102 89 67 59 102 89 101 88 74 102 71 64 107 103 63 55 98 85 97 84 66 58 73 62 108 95 62 54 61 53 115 112 62 54 115 112 98 85 1 1 74 102 111 104 1 1 111 104 110 113 117 115 119 116 118 117 117 115 120 118 119 116 124 119 126 120 125 121 126 120 128 122 127 123 132 124 133 125 131 126 132 124 134 127 133 125 133 125 137 128 136 129 143 130 144 131 142 132 150 133 146 134 151 135 146 134 142 132 144 131 142 132 138 136 140 137 138 136 136 129 137 128 148 138 146 134 150 133 138 136 153 139 136 129 153 139 148 138 155 140 138 136 148 138 153 139 151 135 117 115 118 117 120 118 124 119 122 141 132 124 135 142 134 127 141 143 145 144 143 130 157 145 124 119 120 118 132 124 141 143 135 142 121 146 149 147 119 116 129 148 154 149 127 123 129 148 153 139 154 149 123 150 148 138 121 146 123 150 156 151 148 138 125 121 155 140 156 151 119 116 150 133 118 117 119 116 149 147 150 133 133 125 152 152 131 126 127 123 155 140 125 121 166 153 167 154 165 155 168 156 167 154 166 153 168 156 169 157 167 154 163 158 171 159 170 160 172 161 173 162 169 157 174 163 161 164 158 165 174 163 175 166 161 164 170 160 175 166 174 163 170 160 171 159 175 166 177 167 179 168 178 169 177 167 180 170 179 168 181 171 183 172 182 173 181 171 184 174 183 172 185 175 184 174 181 171 182 173 190 176 189 177 118 117 188 178 187 179 189 177 193 180 192 181 194 182 197 183 196 184 198 185 200 186 199 187 198 185 201 188 200 186 202 189 199 187 203 190 202 189 198 185 199 187 204 191 203 190 205 192 201 188 206 193 200 186 208 194 205 192 209 195 210 196 194 182 195 197 213 198 215 199 214 200 213 198 216 201 215 199 217 202 219 203 218 204 221 205 218 204 222 206 221 205 217 202 218 204 229 207 214 200 230 208 229 207 213 198 214 200 226 209 230 208 225 210 226 209 229 207 230 208 158 165 194 182 210 196 168 156 208 194 172 161 168 156 204 191 208 194 159 211 197 183 194 182 170 160 201 188 163 158 169 157 203 190 167 154 169 157 205 192 203 190 167 154 199 187 165 155 167 154 203 190 199 187 165 155 200 186 164 212 161 164 196 184 160 213 164 212 206 193 171 159 164 212 200 186 206 193 160 213 197 183 159 211 172 161 208 194 209 195 185 175 223 214 187 179 181 171 221 205 185 175 177 167 213 198 229 207 182 173 220 215 217 202 178 169 213 198 177 167 178 169 216 201 213 198 189 177 220 215 182 173 189 177 226 209 220 215 190 176 230 208 193 180 190 176 225 210 230 208 186 216 218 204 184 174 193 180 230 208 214 200 191 217 228 218 224 219 180 170 215 199 179 168 183 172 219 203 225 210 179 168 216 201 178 169 179 168 215 199 216 201 120 118 121 146 119 116 120 118 122 141 121 146 122 141 123 150 121 146 122 141 124 119 123 150 124 119 125 121 123 150 126 120 127 123 125 121 128 122 129 148 127 123 128 122 130 220 129 148 130 220 131 126 129 148 130 220 132 124 131 126 135 142 133 125 134 127 133 125 135 142 137 128 135 142 138 136 137 128 135 142 139 221 138 136 139 221 140 137 138 136 139 221 141 143 140 137 141 143 142 132 140 137 141 143 143 130 142 132 143 130 145 144 144 131 145 144 146 134 144 131 145 144 147 222 146 134 148 138 150 133 149 147 136 129 153 139 152 152 153 139 155 140 154 149 155 140 148 138 156 151 146 134 138 136 142 132 148 138 138 136 146 134 147 222 151 135 146 134 147 222 157 145 151 135 117 115 151 135 157 145 151 135 118 117 150 133 157 145 120 118 117 115 124 119 128 122 126 120 128 122 132 124 130 220 135 142 141 143 139 221 145 144 157 145 147 222 124 119 132 124 128 122 141 143 157 145 145 144 157 145 132 124 124 119 132 124 157 145 141 143 121 146 148 138 149 147 131 126 153 139 129 148 131 126 152 152 153 139 125 121 156 151 123 150 133 125 136 129 152 152 127 123 154 149 155 140 158 165 160 213 159 211 158 165 161 164 160 213 162 223 164 212 163 158 162 223 165 155 164 212 166 153 165 155 162 223 163 158 164 212 171 159 172 161 169 157 168 156 194 182 196 184 195 197 204 191 202 189 203 190 201 188 207 224 206 193 208 194 204 191 205 192 210 196 195 197 211 225 207 224 211 225 206 193 207 224 210 196 211 225 166 153 204 191 168 156 166 153 202 189 204 191 174 163 207 224 170 160 174 163 210 196 207 224 162 223 202 189 166 153 162 223 198 185 202 189 158 165 210 196 174 163 163 158 198 185 162 223 163 158 201 188 198 185 159 211 194 182 158 165 170 160 207 224 201 188 171 159 211 225 175 166 171 159 206 193 211 225 175 166 195 197 161 164 175 166 211 225 195 197 165 155 199 187 200 186 173 162 205 192 169 157 173 162 209 195 205 192 161 164 195 197 196 184 160 213 196 184 197 183 172 161 209 195 173 162 185 175 186 216 184 174 187 179 186 216 185 175 187 179 188 178 186 216 182 173 183 172 190 176 118 117 191 217 188 178 192 181 180 170 177 167 192 181 193 180 180 170 189 177 190 176 193 180 231 198 215 199 214 200 231 198 232 201 215 199 217 202 220 215 219 203 223 214 222 206 224 219 223 214 221 205 222 206 220 215 225 210 219 203 220 215 226 209 225 210 227 226 224 219 228 218 227 226 223 214 224 219 229 207 214 200 233 227 229 207 231 198 214 200 226 209 233 227 225 210 226 209 229 207 233 227 185 175 221 205 223 214 192 181 226 209 189 177 192 181 229 207 226 209 181 171 217 202 221 205 177 167 229 207 192 181 177 167 231 198 229 207 182 173 217 202 181 171 187 179 227 226 118 117 187 179 223 214 227 226 178 169 231 198 177 167 178 169 232 201 231 198 188 178 222 206 186 216 188 178 224 219 222 206 190 176 233 227 193 180 190 176 225 210 233 227 186 216 222 206 218 204 193 180 214 200 180 170 193 180 233 227 214 200 184 174 219 203 183 172 184 174 218 204 219 203 191 217 224 219 188 178 180 170 214 200 215 199 183 172 225 210 190 176 179 168 232 201 178 169 179 168 215 199 232 201 118 117 228 218 191 217 118 117 227 226 228 218 234 228 236 229 235 230 234 228 237 231 236 229 241 232 243 233 242 234 243 233 245 235 244 236 249 237 250 238 248 239 249 237 251 240 250 238 250 238 254 241 253 242 260 243 261 244 259 245 267 246 263 247 268 248 263 247 259 245 261 244 259 245 255 249 257 250 255 249 253 242 254 241 265 251 263 247 267 246 255 249 270 252 253 242 270 252 265 251 272 253 255 249 265 251 270 252 268 248 234 228 235 230 237 231 241 232 239 254 249 237 252 255 251 240 258 256 262 257 260 243 274 258 241 232 237 231 249 237 258 256 252 255 238 259 266 260 236 229 246 261 271 262 244 236 246 261 270 252 271 262 240 263 265 251 238 259 240 263 273 264 265 251 242 234 272 253 273 264 236 229 267 246 235 230 236 229 266 260 267 246 250 238 269 265 248 239 244 236 272 253 242 234 283 266 284 267 282 268 285 269 284 267 283 266 285 269 286 270 284 267 280 271 288 272 287 273 289 274 290 275 286 270 291 276 278 277 275 278 291 276 292 279 278 277 287 273 292 279 291 276 287 273 288 272 292 279 294 280 296 281 295 282 294 280 297 283 296 281 298 284 300 285 299 286 298 284 301 287 300 285 302 288 301 287 298 284 299 286 307 289 306 290 235 230 305 291 304 292 306 290 310 293 309 294 311 295 314 296 313 297 315 298 317 299 316 300 315 298 318 301 317 299 319 302 316 300 320 303 319 302 315 298 316 300 321 304 320 303 322 305 318 301 323 306 317 299 325 307 322 305 326 308 327 309 311 295 312 310 330 311 332 312 331 313 330 311 333 314 332 312 334 315 336 316 335 317 338 318 335 317 339 319 338 318 334 315 335 317 346 320 331 313 347 321 346 320 330 311 331 313 343 322 347 321 342 323 343 322 346 320 347 321 275 278 311 295 327 309 285 269 325 307 289 274 285 269 321 304 325 307 276 324 314 296 311 295 287 273 318 301 280 271 286 270 320 303 284 267 286 270 322 305 320 303 284 267 316 300 282 268 284 267 320 303 316 300 282 268 317 299 281 325 278 277 313 297 277 326 281 325 323 306 288 272 281 325 317 299 323 306 277 326 314 296 276 324 289 274 325 307 326 308 302 288 340 327 304 292 298 284 338 318 302 288 294 280 330 311 346 320 299 286 337 328 334 315 295 282 330 311 294 280 295 282 333 314 330 311 306 290 337 328 299 286 306 290 343 322 337 328 307 289 347 321 310 293 307 289 342 323 347 321 303 329 335 317 301 287 310 293 347 321 331 313 308 330 345 331 341 332 297 283 332 312 296 281 300 285 336 316 342 323 296 281 333 314 295 282 296 281 332 312 333 314 237 231 238 259 236 229 237 231 239 254 238 259 239 254 240 263 238 259 239 254 241 232 240 263 241 232 242 234 240 263 243 233 244 236 242 234 245 235 246 261 244 236 245 235 247 333 246 261 247 333 248 239 246 261 247 333 249 237 248 239 252 255 250 238 251 240 250 238 252 255 254 241 252 255 255 249 254 241 252 255 256 334 255 249 256 334 257 250 255 249 256 334 258 256 257 250 258 256 259 245 257 250 258 256 260 243 259 245 260 243 262 257 261 244 262 257 263 247 261 244 262 257 264 335 263 247 265 251 267 246 266 260 253 242 270 252 269 265 270 252 272 253 271 262 272 253 265 251 273 264 263 247 255 249 259 245 265 251 255 249 263 247 264 335 268 248 263 247 264 335 274 258 268 248 234 228 268 248 274 258 268 248 235 230 267 246 274 258 237 231 234 228 241 232 245 235 243 233 245 235 249 237 247 333 252 255 258 256 256 334 262 257 274 258 264 335 241 232 249 237 245 235 258 256 274 258 262 257 274 258 249 237 241 232 249 237 274 258 258 256 238 259 265 251 266 260 248 239 270 252 246 261 248 239 269 265 270 252 242 234 273 264 240 263 250 238 253 242 269 265 244 236 271 262 272 253 275 278 277 326 276 324 275 278 278 277 277 326 279 336 281 325 280 271 279 336 282 268 281 325 283 266 282 268 279 336 280 271 281 325 288 272 289 274 286 270 285 269 311 295 313 297 312 310 321 304 319 302 320 303 318 301 324 337 323 306 325 307 321 304 322 305 327 309 312 310 328 338 324 337 328 338 323 306 324 337 327 309 328 338 283 266 321 304 285 269 283 266 319 302 321 304 291 276 324 337 287 273 291 276 327 309 324 337 279 336 319 302 283 266 279 336 315 298 319 302 275 278 327 309 291 276 280 271 315 298 279 336 280 271 318 301 315 298 276 324 311 295 275 278 287 273 324 337 318 301 288 272 328 338 292 279 288 272 323 306 328 338 292 279 312 310 278 277 292 279 328 338 312 310 282 268 316 300 317 299 290 275 322 305 286 270 290 275 326 308 322 305 278 277 312 310 313 297 277 326 313 297 314 296 289 274 326 308 290 275 302 288 303 329 301 287 304 292 303 329 302 288 304 292 305 291 303 329 299 286 300 285 307 289 235 230 308 330 305 291 309 294 297 283 294 280 309 294 310 293 297 283 306 290 307 289 310 293 348 311 332 312 331 313 348 311 349 314 332 312 334 315 337 328 336 316 340 327 339 319 341 332 340 327 338 318 339 319 337 328 342 323 336 316 337 328 343 322 342 323 344 339 341 332 345 331 344 339 340 327 341 332 346 320 331 313 350 340 346 320 348 311 331 313 343 322 350 340 342 323 343 322 346 320 350 340 302 288 338 318 340 327 309 294 343 322 306 290 309 294 346 320 343 322 298 284 334 315 338 318 294 280 346 320 309 294 294 280 348 311 346 320 299 286 334 315 298 284 304 292 344 339 235 230 304 292 340 327 344 339 295 282 348 311 294 280 295 282 349 314 348 311 305 291 339 319 303 329 305 291 341 332 339 319 307 289 350 340 310 293 307 289 342 323 350 340 303 329 339 319 335 317 310 293 331 313 297 283 310 293 350 340 331 313 301 287 336 316 300 285 301 287 335 317 336 316 308 330 341 332 305 291 297 283 331 313 332 312 300 285 342 323 307 289 296 281 349 314 295 282 296 281 332 312 349 314 235 230 345 331 308 330 235 230 344 339 345 331 351 341 352 342 353 343 351 341 353 343 354 344 358 345 359 346 360 347 360 347 361 348 362 349 366 350 365 351 367 352 366 350 367 352 368 353 367 352 370 354 371 355 377 356 376 357 378 358 384 359 385 360 380 361 380 361 378 358 376 357 376 357 374 362 372 363 372 363 371 355 370 354 382 364 384 359 380 361 372 363 370 354 387 365 387 365 389 366 382 364 372 363 387 365 382 364 385 360 352 342 351 341 354 344 356 367 358 345 366 350 368 353 369 368 375 369 377 356 379 370 391 371 354 344 358 345 366 350 369 368 375 369 355 372 353 343 383 373 363 374 361 348 388 375 363 374 388 375 387 365 357 376 355 372 382 364 357 376 382 364 390 377 359 346 390 377 389 366 353 343 352 342 384 359 353 343 384 359 383 373 367 352 365 351 386 378 361 348 359 346 389 366 400 379 399 380 401 381 402 382 400 379 401 381 402 382 401 381 403 383 397 384 404 385 405 386 406 387 403 383 407 388 408 389 392 390 395 391 408 389 395 391 409 392 404 385 408 389 409 392 404 385 409 392 405 386 411 393 412 394 413 395 411 393 413 395 414 396 415 397 416 398 417 399 415 397 417 399 418 400 419 401 415 397 418 400 416 398 423 402 424 403 352 342 421 404 422 405 423 402 426 406 427 407 428 408 430 409 431 410 432 411 433 412 434 413 432 411 434 413 435 414 436 415 437 416 433 412 436 415 433 412 432 411 438 417 439 418 437 416 435 414 434 413 440 419 442 420 443 421 439 418 444 422 429 423 428 408 447 424 448 425 449 426 447 424 449 426 450 427 451 428 452 429 453 430 455 431 456 432 452 429 455 431 452 429 451 428 463 433 464 434 448 425 463 433 448 425 447 424 460 435 459 436 464 434 460 435 464 434 463 433 392 390 444 422 428 408 402 382 406 387 442 420 402 382 442 420 438 417 393 437 428 408 431 410 404 385 397 384 435 414 403 383 401 381 437 416 403 383 437 416 439 418 401 381 399 380 433 412 401 381 433 412 437 416 399 380 398 438 434 413 395 391 394 439 430 409 398 438 405 386 440 419 398 438 440 419 434 413 394 439 393 437 431 410 406 387 443 421 442 420 419 401 421 404 457 440 415 397 419 401 455 431 411 393 463 433 447 424 416 398 451 428 454 441 412 394 411 393 447 424 412 394 447 424 450 427 423 402 416 398 454 441 423 402 454 441 460 435 424 403 427 407 464 434 424 403 464 434 459 436 420 442 418 400 452 429 427 407 448 425 464 434 425 443 458 444 462 445 414 396 413 395 449 426 417 399 459 436 453 430 413 395 412 394 450 427 413 395 450 427 449 426 354 344 353 343 355 372 354 344 355 372 356 367 356 367 355 372 357 376 356 367 357 376 358 345 358 345 357 376 359 346 360 347 359 346 361 348 362 349 361 348 363 374 362 349 363 374 364 446 364 446 363 374 365 351 364 446 365 351 366 350 369 368 368 353 367 352 367 352 371 355 369 368 369 368 371 355 372 363 369 368 372 363 373 447 373 447 372 363 374 362 373 447 374 362 375 369 375 369 374 362 376 357 375 369 376 357 377 356 377 356 378 358 379 370 379 370 378 358 380 361 379 370 380 361 381 448 382 364 383 373 384 359 370 354 386 378 387 365 387 365 388 375 389 366 389 366 390 377 382 364 380 361 376 357 372 363 382 364 380 361 372 363 381 448 380 361 385 360 381 448 385 360 391 371 351 341 391 371 385 360 385 360 384 359 352 342 391 371 351 341 354 344 358 345 360 347 362 349 362 349 364 446 366 350 369 368 373 447 375 369 379 370 381 448 391 371 358 345 362 349 366 350 375 369 379 370 391 371 391 371 358 345 366 350 366 350 375 369 391 371 355 372 383 373 382 364 365 351 363 374 387 365 365 351 387 365 386 378 359 346 357 376 390 377 367 352 386 378 370 354 361 348 389 366 388 375 392 390 393 437 394 439 392 390 394 439 395 391 396 449 397 384 398 438 396 449 398 438 399 380 400 379 396 449 399 380 397 384 405 386 398 438 406 387 402 382 403 383 428 408 429 423 430 409 438 417 437 416 436 415 435 414 440 419 441 450 442 420 439 418 438 417 444 422 445 451 429 423 441 450 440 419 445 451 441 450 445 451 444 422 400 379 402 382 438 417 400 379 438 417 436 415 408 389 404 385 441 450 408 389 441 450 444 422 396 449 400 379 436 415 396 449 436 415 432 411 392 390 408 389 444 422 397 384 396 449 432 411 397 384 432 411 435 414 393 437 392 390 428 408 404 385 435 414 441 450 405 386 409 392 445 451 405 386 445 451 440 419 409 392 395 391 429 423 409 392 429 423 445 451 399 380 434 413 433 412 407 388 403 383 439 418 407 388 439 418 443 421 395 391 430 409 429 423 394 439 431 410 430 409 406 387 407 388 443 421 419 401 418 400 420 442 421 404 419 401 420 442 421 404 420 442 422 405 416 398 424 403 417 399 352 342 422 405 425 443 426 406 411 393 414 396 426 406 414 396 427 407 423 402 427 407 424 403 465 424 448 425 449 426 465 424 449 426 466 427 451 428 453 430 454 441 457 440 458 444 456 432 457 440 456 432 455 431 454 441 453 430 459 436 454 441 459 436 460 435 461 452 462 445 458 444 461 452 458 444 457 440 463 433 467 453 448 425 463 433 448 425 465 424 460 435 459 436 467 453 460 435 467 453 463 433 419 401 457 440 455 431 426 406 423 402 460 435 426 406 460 435 463 433 415 397 455 431 451 428 411 393 426 406 463 433 411 393 463 433 465 424 416 398 415 397 451 428 421 404 352 342 461 452 421 404 461 452 457 440 412 394 411 393 465 424 412 394 465 424 466 427 422 405 420 442 456 432 422 405 456 432 458 444 424 403 427 407 467 453 424 403 467 453 459 436 420 442 452 429 456 432 427 407 414 396 448 425 427 407 448 425 467 453 418 400 417 399 453 430 418 400 453 430 452 429 425 443 422 405 458 444 414 396 449 426 448 425 417 399 424 403 459 436 413 395 412 394 466 427 413 395 466 427 449 426 352 342 425 443 462 445 352 342 462 445 461 452

+
+
+
+
+ + + + 1 0 0 0 0 1 0 0 0 0 1 0.025 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0.011 0 0 1 0.014 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1.229657 0.02 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0.015 0 0 0 1 + + + + + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + 0.705359 0 0 0.031 0 0.705359 0 0.031 0 0 0.705359 0.014 0 0 0 1 + + + + + + + + + + + + 0.7071068 0.7071068 0 0.031 -0.7071068 0.7071068 0 0.031 0 0 1 0.014 0 0 0 1 + + + + + + + + + + 0.6918778 0.7220147 0 0.031 -0.7220147 0.6918778 0 0.031 0 0 1 0.022 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/crazyflie/urdf/crazyflie_description.urdf b/crazyflie/urdf/crazyflie_description.urdf new file mode 100644 index 000000000..88a68e5c0 --- /dev/null +++ b/crazyflie/urdf/crazyflie_description.urdf @@ -0,0 +1,11 @@ + + + + + + + + + + + \ No newline at end of file diff --git a/crazyflie_sim/crazyflie_sim/crazyflie_server.py b/crazyflie_sim/crazyflie_sim/crazyflie_server.py index 0d05fede7..13bf4ae2e 100755 --- a/crazyflie_sim/crazyflie_sim/crazyflie_server.py +++ b/crazyflie_sim/crazyflie_sim/crazyflie_server.py @@ -16,6 +16,7 @@ import rclpy from rclpy.node import Node import rowan +from std_msgs.msg import String from std_srvs.srv import Empty @@ -100,6 +101,17 @@ def __init__(self): self._start_trajectory_callback) for name, _ in self.cfs.items(): + pub = self.create_publisher( + String, + name + '/robot_description', + rclpy.qos.QoSProfile( + depth=1, + durability=rclpy.qos.QoSDurabilityPolicy.TRANSIENT_LOCAL)) + + msg = String() + msg.data = self._ros_parameters['robot_description'].replace('$NAME', name) + pub.publish(msg) + self.create_service( Empty, name + '/emergency',