diff --git a/dxl_armed_turtlebot/README.md b/dxl_armed_turtlebot/README.md new file mode 100644 index 00000000..9ab25561 --- /dev/null +++ b/dxl_armed_turtlebot/README.md @@ -0,0 +1,88 @@ +## Smaples in Gazebo + +まずは、下記のコマンドを実行し、gazeboシステム及び仮想ロボットを立ち上げます +``` +$ roslaunch dxl_armed_turtlebot dxl_armed_turtlebot_gazebo.launch +``` + +その場合、以下のような画面になりと思います。 + +![gazebo_turtlebot](images/gazebo_turtlebot2.png) + +#### 注意: +gazeboのgui (右図) を立ち上げると、PCの処理負荷が一気に上がるので、通常は`gui:=false`というオプションをつけて、rvizのみ表示させることを推奨します。 +その場合、コマンドは以下のようになります。 + +``` +$ roslaunch dxl_armed_turtlebot dxl_armed_turtlebot_gazebo.launch gui:=false +``` + +### 1. Grasping test in gazebo via roseus + +以下のコマンドを実行し、roseusから目の前にある物体を掴んでみましょう。 + +``` +$ roscd dxl_armed_turtlebot/euslisp +$ roseus gazebo-grasp-test.l +``` + +このサンプルでは、eusのロボットモデルである`*ri*`を駆使して、台車移動、アーム操作、グリッパー操作という基本動作を実行しています。 +成功すると以下のようになります(gazebo guiの表示画面)。 + +![gazebo_turtlebot_grasp](images/gazebo_turtlebot_grasp.png) + +### 2. Object recognition and approaching via roseus +前の例では、物体認識を行っておりません。物体認識を踏まえた自律動作は以下のように実行します。 + +1. 物体認識を実行する. これは演習で習ったもので、詳細は演習資料を参考してください。 + ``` + $ roslaunch dxl_armed_turtlebot hsi_color_filter.launch DEFAULT_NAMESPACE:=/camera/depth INPUT:=points h_min:=-120 h_max:=-20 s_min:=120 + ``` +2. 認識結果を元に、自律行動を実行する + ``` + $ roscd dxl_armed_turtlebot/euslisp + $ roseus gazebo-grasp-with-recognition.l + ``` + +### 3. SLAM in Gazebo +gazebo内でも地図作成は、実機と同様、下記のコマンドを実行するだけ: +``` +$ rosrun slam_karto slam_karto +``` + +rviz上で、2D地図ができていることが確認できるでしょう。 +ロボットの移動はroseusからでもできるが、ここでは、下記のコマンドを紹介します: +``` +$ roslaunch turtlebot_teleop keyboard_teleop.launch +``` +機体を一周旋回させると、以下のようになります。 + +![gazebo_turtlebot_slam](images/gazebo_turtlebot_slam.png) + +### 4. Detect Checkerboard in Gazebo +gazebo内でも実機と同様にcheckerboardを検出することができる + +まず、checkerboader_detectorを起動しましょう: +``` +$ roslaunch roseus_tutorials checkerboard-detector.launch rect0_size_x:=0.02 rect0_size_y:=0.02 grid0_size_x:=7 grid0_size_y:=4 translation0:="0 0 0" image:=image_raw group:=/camera/rgb frame_id:=camera_rgb_frame +``` + + +次に、上記と同じコマンドを使って、ロボットを旋回させましょう: +``` +$ roslaunch turtlebot_teleop keyboard_teleop.launch +``` + +最後に、rviz上でchecker_boardが見つかれば、下記のコマンドでroseus上でcheckerboardを表示しましょう: + +``` +$ roscd dxl_armed_turtlebot/euslisp +$ roseus display-checkerboard.l +``` + +最終てきには、以下のようになります。 + +![gazebo_checkerboard](images/gazebo_checkerboard.png) + + + diff --git a/dxl_armed_turtlebot/config/dxl_armed_turtlebot_controllers.yaml b/dxl_armed_turtlebot/config/dxl_armed_turtlebot_controllers.yaml index 15847539..70310151 100644 --- a/dxl_armed_turtlebot/config/dxl_armed_turtlebot_controllers.yaml +++ b/dxl_armed_turtlebot/config/dxl_armed_turtlebot_controllers.yaml @@ -3,50 +3,63 @@ joint_state_controller: type: joint_state_controller/JointStateController publish_rate: 50 # Trajectory Controllers --------------------------------------- -trajectory_controller: +fullbody_controller: #type: effort_controllers/JointTrajectoryController type: velocity_controllers/JointTrajectoryController joints: - - arm_link1_joint - - arm_link2_joint - - arm_link3_joint - - arm_link4_joint - - arm_link5_joint - - arm_link6_joint - - arm_link7_joint + - arm_joint1 + - arm_joint2 + - arm_joint3 + - arm_joint4 + - arm_joint5 + - arm_joint6 constraints: goal_time: 0.5 # Override default stopped_velocity_tolerance: 0.02 # Override default - arm_link1_joint: - trajectory: 0.05 # Not enforced if unspecified + arm_joint1: + #trajectory: 0.1 # Not enforced if unspecified goal: 0.02 # Not enforced if unspecified - arm_link2_joint: - trajectory: 0.05 # Not enforced if unspecified + arm_joint2: + #trajectory: 0.1 # Not enforced if unspecified goal: 0.02 # Not enforced if unspecified - arm_link3_joint: - trajectory: 0.05 # Not enforced if unspecified + arm_joint3: + #trajectory: 0.1 # Not enforced if unspecified goal: 0.02 # Not enforced if unspecified - arm_link4_joint: - trajectory: 0.05 # Not enforced if unspecified + arm_joint4: + #trajectory: 0.1 # Not enforced if unspecified goal: 0.02 # Not enforced if unspecified - arm_link5_joint: - trajectory: 0.05 # Not enforced if unspecified + arm_joint5: + #trajectory: 0.1 # Not enforced if unspecified goal: 0.02 # Not enforced if unspecified - arm_link6_joint: - trajectory: 0.05 # Not enforced if unspecified + arm_joint6: + #trajectory: 0.1 # Not enforced if unspecified goal: 0.02 # Not enforced if unspecified - arm_link7_joint: - trajectory: 0.05 # Not enforced if unspecified + + gains: # Required because we're controlling an effort interface + arm_joint1: {p: 25.0, i: 0.0, d: 0.0} + arm_joint2: {p: 25.0, i: 0.0, d: 0.0} + arm_joint3: {p: 25.0, i: 0.0, d: 0.0} + arm_joint4: {p: 25.0, i: 0.0, d: 0.0} + arm_joint5: {p: 25.0, i: 0.0, d: 0.0} + arm_joint6: {p: 25.0, i: 0.0, d: 0.0} + state_publish_rate: 100 # Override default + action_monitor_rate: 100 # Override default + stop_trajectory_duration: 0 # Override default + +gripper_controller: + #type: effort_controllers/JointTrajectoryController + type: velocity_controllers/JointTrajectoryController + joints: + - gripper_joint + constraints: + goal_time: 0.5 # Override default + stopped_velocity_tolerance: 0.02 # Override default + gripper_joint: + #trajectory: 0.05 # Not enforced if unspecified goal: 0.02 # Not enforced if unspecified gains: # Required because we're controlling an effort interface - arm_link1_joint: {p: 25.0, i: 0.0, d: 0.0} - arm_link2_joint: {p: 25.0, i: 0.0, d: 0.0} - arm_link3_joint: {p: 25.0, i: 0.0, d: 0.0} - arm_link4_joint: {p: 25.0, i: 0.0, d: 0.0} - arm_link5_joint: {p: 25.0, i: 0.0, d: 0.0} - arm_link6_joint: {p: 25.0, i: 0.0, d: 0.0} - arm_link7_joint: {p: 5.0, i: 0.0, d: 0.0} + gripper_joint: {p: 10.0, i: 0.0, d: 0.0} state_publish_rate: 100 # Override default action_monitor_rate: 100 # Override default stop_trajectory_duration: 0 # Override default diff --git a/dxl_armed_turtlebot/euslisp/dxl-armed-turtlebot-interface.l b/dxl_armed_turtlebot/euslisp/dxl-armed-turtlebot-interface.l index 15bc6a0a..0ad5575e 100644 --- a/dxl_armed_turtlebot/euslisp/dxl-armed-turtlebot-interface.l +++ b/dxl_armed_turtlebot/euslisp/dxl-armed-turtlebot-interface.l @@ -14,7 +14,7 @@ ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; (defclass dxl-armed-turtlebot-interface :super robot-interface - :slots ()) + :slots (gripper-action)) (eval `(defmethod dxl-armed-turtlebot-interface ;; dxl-7dof-arm-interface, turtlebot-interfaceのメソッドをそれぞれdefmethodする @@ -48,4 +48,4 @@ (send *irtviewer* :change-background #f(0.9 0.9 0.9)) (send *irtviewer* :draw-objects) ) -(warn ";; (dxl-armed-turtlebot-init) ;; for initialize ~%") \ No newline at end of file +(warn ";; (dxl-armed-turtlebot-init) ;; for initialize ~%") diff --git a/dxl_armed_turtlebot/euslisp/dxl-armed-turtlebot.l b/dxl_armed_turtlebot/euslisp/dxl-armed-turtlebot.l index 45cb4e12..1d57d934 100644 --- a/dxl_armed_turtlebot/euslisp/dxl-armed-turtlebot.l +++ b/dxl_armed_turtlebot/euslisp/dxl-armed-turtlebot.l @@ -63,6 +63,8 @@ (send self :method-copying "-pose") (send self :method-copying "_joint") (send self :method-copying "inverse-kinematics" t) + (send self :method-copying "gripper" t) + (send self :method-copying "arm" t) t)) (:method-copying (substr &optional (use-args nil)) @@ -79,10 +81,12 @@ ,(if use-args `(send* arm-robot ,me args) `(send arm-robot ,me)) ) )) - ))) + ) + methods)) + ;; limbs - (:arm (&rest args) - (unless args (setq args (list nil))) (send* self :limb :rarm args)) + ;;(:arm (&rest args) + ;;(unless args (setq args (list nil))) (send* self :limb :rarm args)) ) ;; アーム台車モデル生成関数 diff --git a/dxl_armed_turtlebot/euslisp/gazebo-grasp-test.l b/dxl_armed_turtlebot/euslisp/gazebo-grasp-test.l new file mode 100644 index 00000000..9ec29ef9 --- /dev/null +++ b/dxl_armed_turtlebot/euslisp/gazebo-grasp-test.l @@ -0,0 +1,19 @@ +;; robotの初期化 +(load "package://dxl_armed_turtlebot/euslisp/dxl-armed-turtlebot-interface.l") +(dxl-armed-turtlebot-init) + +;; arm approach pose +(send *ri* :angle-vector #f(0 0 -90 0 90 0) 3000) +(send *ri* :wait-interpolation) + +;; open gripper +(send *ri* :stop-grasp) + +;; go-pos +(send *ri* :go-pos 0.56 0 1) + +;; grasp +;; still some bug in start-grasp, so we have to directly use :move-gripper +(send *ri* :move-gripper -30 :tm 1500 :wait t) +(send *ri* :wait-interpolation) +(send *ri* :angle-vector #f(90 0 45 0 45 45)) ;; arm tuck pose diff --git a/dxl_armed_turtlebot/euslisp/gazebo-grasp-with-recognition.l b/dxl_armed_turtlebot/euslisp/gazebo-grasp-with-recognition.l new file mode 100644 index 00000000..015cfd8d --- /dev/null +++ b/dxl_armed_turtlebot/euslisp/gazebo-grasp-with-recognition.l @@ -0,0 +1,91 @@ +;; robotの初期化 +(load "package://dxl_armed_turtlebot/euslisp/dxl-armed-turtlebot-interface.l") +(dxl-armed-turtlebot-init) + +(ros::load-ros-manifest "jsk_recognition_msgs") + +(defvar *topic-name* "/camera/depth/boxes") +(defvar *bounding-box-list* nil) + +(setq found-obj nil) +(setq obj-pos #f(0 0 0)) + +;; ros::initする +(ros::roseus "boundingboxarray_subscriber") + +;; コールバック関数 +(defun bounding-box-array-cb (msg) + (setq *bounding-box-list* (send msg :boxes)) ;; boxesは、BoundingBoxのArray(Euslispではlist) + (when *bounding-box-list* + (let* ((b (elt *bounding-box-list* 0)) + (cam->obj-coords (ros::tf-pose->coords (send b :pose))) + (cam-coords (send (send *dxl-armed-turtlebot* :camera_depth_optical_frame_lk) :copy-worldcoords))) + (setq obj-pos (scale 0.001 (send (send cam-coords :transform cam->obj-coords) :worldpos))) + (setq found-obj t) + obj-pos)) + ) + +(ros::subscribe *topic-name* jsk_recognition_msgs::BoundingBoxArray #'bounding-box-array-cb 1) + +(setq found-obj nil) +(until found-obj + (x::window-main-one) ;; IRT viewerの視点を変えられる。見にくければ変えよう + (ros::spin-once) + (ros::sleep) + ) + +(ros::ros-warn "found target ojbect ~A, appoaching" obj-pos) + +(setq 2d-pos (float-vector (elt obj-pos 0) (elt obj-pos 1))) + +(send *ri* :go-pos + (elt (scale (/ (- (norm 2d-pos) 0.6) (norm 2d-pos)) 2d-pos) 0) + (elt (scale (/ (- (norm 2d-pos) 0.6) (norm 2d-pos)) 2d-pos) 1) + (rad2deg (atan (elt obj-pos 1) (elt obj-pos 0)))) + +;; open gripper +(send *ri* :stop-grasp) + + +(setq found-obj nil) +(until found-obj + (x::window-main-one) ;; IRT viewerの視点を変えられる。見にくければ変えよう + (ros::spin-once) + (ros::sleep) + ) + +(ros::ros-warn "re-found target object ~A" obj-pos) +(setq target-cds (make-coords :pos (scale 1000 obj-pos))) +(send target-cds :translate #f(-200 0 50)) ;;z should be 0, but the link is not rigid in gazebo, so 100 is the height offset for end effector. +(objects (list *dxl-armed-turtlebot* target-cds)) + +(send *dxl-armed-turtlebot* :angle-vector #f(0 0 -90 0 90 0)) + +(send *dxl-armed-turtlebot* :arm :end-coords :translate #f(0 30 0)) ;; change the end-effector position + +(send *dxl-armed-turtlebot* :inverse-kinematics target-cds :rotation-axis :y) + +#| +(send *dxl-armed-turtlebot* :angle-vector (map float-vector #'(lambda(ang) + (cond + ((> ang 90) (- ang 180)) + ((< ang -90) (+ ang 180)) + (t ang) + )) + (send *dxl-armed-turtlebot* :angle-vector))) +|# + +(ros::ros-warn "the grap arm pose is ~A" (send *dxl-armed-turtlebot* :angle-vector)) + +(send *ri* :angle-vector (send *dxl-armed-turtlebot* :angle-vector) 3000) +(send *ri* :wait-interpolation) + +(send *ri* :go-pos 0.1 0 0) + +;; grasp +;; still some bug in start-grasp, so we have to directly use :move-gripper +(send *ri* :move-gripper -30 :tm 1500 :wait t) +(send *ri* :wait-interpolation) + +(send *ri* :angle-vector #f(80 0 45 0 45 45)) ;; arm tuck pose +(send *ri* :go-pos -0.6 0 0) ;; arm tuck pose diff --git a/dxl_armed_turtlebot/images/gazebo_checkerboard.png b/dxl_armed_turtlebot/images/gazebo_checkerboard.png new file mode 100644 index 00000000..33d2c68f Binary files /dev/null and b/dxl_armed_turtlebot/images/gazebo_checkerboard.png differ diff --git a/dxl_armed_turtlebot/images/gazebo_turtlebot2.png b/dxl_armed_turtlebot/images/gazebo_turtlebot2.png new file mode 100644 index 00000000..db82811f Binary files /dev/null and b/dxl_armed_turtlebot/images/gazebo_turtlebot2.png differ diff --git a/dxl_armed_turtlebot/images/gazebo_turtlebot_grasp.png b/dxl_armed_turtlebot/images/gazebo_turtlebot_grasp.png new file mode 100644 index 00000000..1d9ea0f8 Binary files /dev/null and b/dxl_armed_turtlebot/images/gazebo_turtlebot_grasp.png differ diff --git a/dxl_armed_turtlebot/images/gazebo_turtlebot_slam.png b/dxl_armed_turtlebot/images/gazebo_turtlebot_slam.png new file mode 100644 index 00000000..90e1df2b Binary files /dev/null and b/dxl_armed_turtlebot/images/gazebo_turtlebot_slam.png differ diff --git a/dxl_armed_turtlebot/launch/dxl_armed_turtlebot_gazebo.launch b/dxl_armed_turtlebot/launch/dxl_armed_turtlebot_gazebo.launch index 20f2ce97..84535446 100644 --- a/dxl_armed_turtlebot/launch/dxl_armed_turtlebot_gazebo.launch +++ b/dxl_armed_turtlebot/launch/dxl_armed_turtlebot_gazebo.launch @@ -53,6 +53,14 @@ + + + + + + + @@ -60,7 +68,8 @@ type="spawner" respawn="false" output="screen" args="joint_state_controller - trajectory_controller + fullbody_controller + gripper_controller "/> diff --git a/dxl_armed_turtlebot/package.xml b/dxl_armed_turtlebot/package.xml index fed07a48..3da174e8 100644 --- a/dxl_armed_turtlebot/package.xml +++ b/dxl_armed_turtlebot/package.xml @@ -53,4 +53,9 @@ teleop_twist_keyboard roseus_tutorials slam_karto + + + + + diff --git a/dxl_armed_turtlebot/scripts/tuck_arm.py b/dxl_armed_turtlebot/scripts/tuck_arm.py index e8b8a552..5c6efb99 100755 --- a/dxl_armed_turtlebot/scripts/tuck_arm.py +++ b/dxl_armed_turtlebot/scripts/tuck_arm.py @@ -14,12 +14,12 @@ def __init__(self, tuck_cmd): self._tuck_rate = rospy.Rate(5.0) # Hz self._tuck_threshold = 0.3 # radians self._joint_moves = { - 'tuck': [pi/2, 0, pi/4, 0, pi/2, pi/2, 0], - 'untuck': [0, 0, -pi/2, 0, pi/2, 0, 0], + 'tuck': [pi/2, 0, pi/4, 0, pi/2, pi/2], + 'untuck': [0, 0, -pi/2, 0, pi/2, 0], } self._arm_state = 'none' - self._pub = rospy.Publisher('/trajectory_controller/command', JointTrajectory, queue_size=1) - self._sub = rospy.Subscriber('/trajectory_controller/state', JointTrajectoryControllerState, self._check_arm_state) + self._pub = rospy.Publisher('/fullbody_controller/command', JointTrajectory, queue_size=1) + self._sub = rospy.Subscriber('/fullbody_controller/state', JointTrajectoryControllerState, self._check_arm_state) def _check_arm_state(self, msg): diff_check = lambda a, b: abs(a - b) <= self._tuck_threshold @@ -40,13 +40,12 @@ def _prepare_to_tuck(self): def _move_to(self, goal): traj = JointTrajectory() traj.joint_names = [ - 'arm_link1_joint', - 'arm_link2_joint', - 'arm_link3_joint', - 'arm_link4_joint', - 'arm_link5_joint', - 'arm_link6_joint', - 'arm_link7_joint' + 'arm_joint1', + 'arm_joint2', + 'arm_joint3', + 'arm_joint4', + 'arm_joint5', + 'arm_joint6', ] traj.points.append(JointTrajectoryPoint()) traj.points[0].positions = self._joint_moves[goal] diff --git a/dxl_armed_turtlebot/worlds/empty.world b/dxl_armed_turtlebot/worlds/empty.world index 083a66c8..dadc7224 100644 --- a/dxl_armed_turtlebot/worlds/empty.world +++ b/dxl_armed_turtlebot/worlds/empty.world @@ -306,5 +306,107 @@ -4 0 0 0 0 1.57102 + + + + 1 + 1.0 0.0 0.06 0 0 0 + + + 10 + + 0.1 + 0.0 + 0.0 + 0.015 + 0.0 + 0.1 + + + + + + 0.2 0.4 0.12 + + + + + + 0.4 + 0.4 + + + + + + + + + 0.2 0.4 0.12 + + + + + + + + + + 1.0 0 0.18 0 0 0 + + + 0.01 + + 0.001 + 0.0 + 0.0 + 0.001 + 0.0 + 0.001 + + + + + + 0.025 + 0.12 + + + + + + 0.9 + 0.9 + + + + + + + + + 0.025 + 0.12 + + + + + + + + + + + + 0 1.3 0.3 0 1.5708 -1.5708 + + model://checkerboard + + + diff --git a/dxl_armed_turtlebot/worlds/model/checkerboard/checkerboard_20mm_7x4.dae b/dxl_armed_turtlebot/worlds/model/checkerboard/checkerboard_20mm_7x4.dae new file mode 100644 index 00000000..9feeb070 --- /dev/null +++ b/dxl_armed_turtlebot/worlds/model/checkerboard/checkerboard_20mm_7x4.dae @@ -0,0 +1,148 @@ + + + + + VCGLab + VCGLib | MeshLab + + Y_UP + 金 1月 27 07:50:44 2017 + 金 1月 27 07:50:44 2017 + + + + checkerboard_20mm_7x4_color.png + + + + + + + + + + + + + texture0 + A8R8G8B8 + + + + + texture0-surface + LINEAR + LINEAR + + + + + + 0.9 0.9 0.9 1 + + + 0 0 0 1 + + + + + + 0 0 0 1 + + + 0.3 + + + 0 0 0 1 + + + 0.5 + + + 0 0 0 1 + + + 0 + + + 0 + + + + + + + + + + + 0.0805 0.095 0.335 0.0758511 0.0918405 0.335 0.0755 0.09 0.335 0.0805 0.095 0.332 0.0755 0.09 0.332 0.0786595 0.0946489 0.332 0.0769645 0.0935355 0.332 0.0758511 0.0918405 0.332 0.0769645 0.0935355 0.335 0.0786595 0.0946489 0.335 0.2055 0.09 0.335 0.2005 0.095 0.335 0.2055 0.09 0.332 0.2005 0.095 0.332 0.205149 0.0918405 0.332 0.204036 0.0935355 0.332 0.20234 0.0946489 0.332 0.20234 0.0946489 0.335 0.204036 0.0935355 0.335 0.205149 0.0918405 0.335 0.0805 -0.095 0.332 0.0755 -0.09 0.332 0.0805 -0.095 0.335 0.0758511 -0.0918405 0.335 0.0755 -0.09 0.335 0.0758511 -0.0918405 0.332 0.0769645 -0.0935355 0.332 0.0786595 -0.0946489 0.332 0.0786595 -0.0946489 0.335 0.0769645 -0.0935355 0.335 0.2005 -0.095 0.335 0.20234 -0.0946489 0.335 0.2055 -0.09 0.335 0.2005 -0.095 0.332 0.2055 -0.09 0.332 0.20234 -0.0946489 0.332 0.204036 -0.0935355 0.332 0.205149 -0.0918405 0.332 0.205149 -0.0918405 0.335 0.204036 -0.0935355 0.335 0.2005 0.095 0.332 0.0805 0.095 0.335 0.0805 0.095 0.332 0.2005 0.095 0.335 0.189591 0.095 0.332 0.178682 0.095 0.332 0.167773 0.095 0.332 0.156864 0.095 0.332 0.145955 0.095 0.332 0.135045 0.095 0.332 0.124136 0.095 0.332 0.113227 0.095 0.332 0.102318 0.095 0.332 0.0914091 0.095 0.332 0.0914091 0.095 0.335 0.102318 0.095 0.335 0.113227 0.095 0.335 0.124136 0.095 0.335 0.135045 0.095 0.335 0.145955 0.095 0.335 0.156864 0.095 0.335 0.167773 0.095 0.335 0.178682 0.095 0.335 0.189591 0.095 0.335 0.2055 -0.09 0.332 0.2055 -0.09 0.335 0.2055 0.09 0.332 0.2055 0.09 0.335 0.2055 -0.07875 0.332 0.2055 -0.0675 0.332 0.2055 -0.05625 0.332 0.2055 -0.045 0.332 0.2055 -0.03375 0.332 0.2055 -0.0225 0.332 0.2055 -0.01125 0.332 0.2055 2.06057e-16 0.332 0.2055 0.01125 0.332 0.2055 0.0225 0.332 0.2055 0.03375 0.332 0.2055 0.045 0.332 0.2055 0.05625 0.332 0.2055 0.0675 0.332 0.2055 0.07875 0.332 0.2055 0.07875 0.335 0.2055 0.0675 0.335 0.2055 0.05625 0.335 0.2055 0.045 0.335 0.2055 0.03375 0.335 0.2055 0.0225 0.335 0.2055 0.01125 0.335 0.2055 1.98952e-16 0.335 0.2055 -0.01125 0.335 0.2055 -0.0225 0.335 0.2055 -0.03375 0.335 0.2055 -0.045 0.335 0.2055 -0.05625 0.335 0.2055 -0.0675 0.335 0.2055 -0.07875 0.335 0.0805 -0.095 0.332 0.2005 -0.095 0.335 0.0805 -0.095 0.335 0.2005 -0.095 0.332 0.0914091 -0.095 0.332 0.102318 -0.095 0.332 0.113227 -0.095 0.332 0.124136 -0.095 0.332 0.135045 -0.095 0.332 0.145955 -0.095 0.332 0.156864 -0.095 0.332 0.167773 -0.095 0.332 0.178682 -0.095 0.332 0.189591 -0.095 0.332 0.189591 -0.095 0.335 0.178682 -0.095 0.335 0.167773 -0.095 0.335 0.156864 -0.095 0.335 0.145955 -0.095 0.335 0.135045 -0.095 0.335 0.124136 -0.095 0.335 0.113227 -0.095 0.335 0.102318 -0.095 0.335 0.0914091 -0.095 0.335 0.0755 0.09 0.332 0.0755 0.09 0.335 0.0755 -0.09 0.332 0.0755 -0.09 0.335 0.0755 0.07875 0.332 0.0755 0.0675 0.332 0.0755 0.05625 0.332 0.0755 0.045 0.332 0.0755 0.03375 0.332 0.0755 0.0225 0.332 0.0755 0.01125 0.332 0.0755 -7.81597e-17 0.332 0.0755 -0.01125 0.332 0.0755 -0.0225 0.332 0.0755 -0.03375 0.332 0.0755 -0.045 0.332 0.0755 -0.05625 0.332 0.0755 -0.0675 0.332 0.0755 -0.07875 0.332 0.0755 -0.07875 0.335 0.0755 -0.0675 0.335 0.0755 -0.05625 0.335 0.0755 -0.045 0.335 0.0755 -0.03375 0.335 0.0755 -0.0225 0.335 0.0755 -0.01125 0.335 0.0755 -8.52651e-17 0.335 0.0755 0.01125 0.335 0.0755 0.0225 0.335 0.0755 0.03375 0.335 0.0755 0.045 0.335 0.0755 0.05625 0.335 0.0755 0.0675 0.335 0.0755 0.07875 0.335 0.191056 -0.0791667 0.332 0.176611 -0.0791667 0.332 0.162167 -0.0791667 0.332 0.147722 -0.0791667 0.332 0.133278 -0.0791667 0.332 0.118833 -0.0791667 0.332 0.104389 -0.0791667 0.332 0.0899444 -0.0791667 0.332 0.191056 -0.0633333 0.332 0.176611 -0.0633333 0.332 0.162167 -0.0633333 0.332 0.147722 -0.0633333 0.332 0.133278 -0.0633333 0.332 0.118833 -0.0633333 0.332 0.104389 -0.0633333 0.332 0.0899444 -0.0633333 0.332 0.191056 -0.0475 0.332 0.176611 -0.0475 0.332 0.162167 -0.0475 0.332 0.147722 -0.0475 0.332 0.133278 -0.0475 0.332 0.118833 -0.0475 0.332 0.104389 -0.0475 0.332 0.0899444 -0.0475 0.332 0.191056 -0.0316667 0.332 0.176611 -0.0316667 0.332 0.162167 -0.0316667 0.332 0.147722 -0.0316667 0.332 0.133278 -0.0316667 0.332 0.118833 -0.0316667 0.332 0.104389 -0.0316667 0.332 0.0899444 -0.0316667 0.332 0.191056 -0.0158333 0.332 0.176611 -0.0158333 0.332 0.162167 -0.0158333 0.332 0.147722 -0.0158333 0.332 0.133278 -0.0158333 0.332 0.118833 -0.0158333 0.332 0.104389 -0.0158333 0.332 0.0899444 -0.0158333 0.332 0.191056 8.79297e-17 0.332 0.176611 9.05942e-17 0.332 0.162167 8.52651e-17 0.332 0.147722 8.52651e-17 0.332 0.133278 8.52651e-17 0.332 0.118833 8.52651e-17 0.332 0.104389 9.23706e-17 0.332 0.0899444 8.52651e-17 0.332 0.191056 0.0158333 0.332 0.176611 0.0158333 0.332 0.162167 0.0158333 0.332 0.147722 0.0158333 0.332 0.133278 0.0158333 0.332 0.118833 0.0158333 0.332 0.104389 0.0158333 0.332 0.0899444 0.0158333 0.332 0.191056 0.0316667 0.332 0.176611 0.0316667 0.332 0.162167 0.0316667 0.332 0.147722 0.0316667 0.332 0.133278 0.0316667 0.332 0.118833 0.0316667 0.332 0.104389 0.0316667 0.332 0.0899444 0.0316667 0.332 0.191056 0.0475 0.332 0.176611 0.0475 0.332 0.162167 0.0475 0.332 0.147722 0.0475 0.332 0.133278 0.0475 0.332 0.118833 0.0475 0.332 0.104389 0.0475 0.332 0.0899444 0.0475 0.332 0.191056 0.0633333 0.332 0.176611 0.0633333 0.332 0.162167 0.0633333 0.332 0.147722 0.0633333 0.332 0.133278 0.0633333 0.332 0.118833 0.0633333 0.332 0.104389 0.0633333 0.332 0.0899444 0.0633333 0.332 0.191056 0.0791667 0.332 0.176611 0.0791667 0.332 0.162167 0.0791667 0.332 0.147722 0.0791667 0.332 0.133278 0.0791667 0.332 0.118833 0.0791667 0.332 0.104389 0.0791667 0.332 0.0899444 0.0791667 0.332 0.0805 0.095 0.332 0.0786595 0.0946489 0.332 0.0769645 0.0935355 0.332 0.0758511 0.0918405 0.332 0.0755 0.09 0.332 0.2055 0.09 0.332 0.205149 0.0918405 0.332 0.204036 0.0935355 0.332 0.20234 0.0946489 0.332 0.2005 0.095 0.332 0.0755 -0.09 0.332 0.0758511 -0.0918405 0.332 0.0769645 -0.0935355 0.332 0.0786595 -0.0946489 0.332 0.0805 -0.095 0.332 0.2005 -0.095 0.332 0.20234 -0.0946489 0.332 0.204036 -0.0935355 0.332 0.205149 -0.0918405 0.332 0.2055 -0.09 0.332 0.189591 0.095 0.332 0.178682 0.095 0.332 0.167773 0.095 0.332 0.156864 0.095 0.332 0.145955 0.095 0.332 0.135045 0.095 0.332 0.124136 0.095 0.332 0.113227 0.095 0.332 0.102318 0.095 0.332 0.0914091 0.095 0.332 0.2055 -0.07875 0.332 0.2055 -0.0675 0.332 0.2055 -0.05625 0.332 0.2055 -0.045 0.332 0.2055 -0.03375 0.332 0.2055 -0.0225 0.332 0.2055 -0.01125 0.332 0.2055 2.06057e-16 0.332 0.2055 0.01125 0.332 0.2055 0.0225 0.332 0.2055 0.03375 0.332 0.2055 0.045 0.332 0.2055 0.05625 0.332 0.2055 0.0675 0.332 0.2055 0.07875 0.332 0.0914091 -0.095 0.332 0.102318 -0.095 0.332 0.113227 -0.095 0.332 0.124136 -0.095 0.332 0.135045 -0.095 0.332 0.145955 -0.095 0.332 0.156864 -0.095 0.332 0.167773 -0.095 0.332 0.178682 -0.095 0.332 0.189591 -0.095 0.332 0.0755 0.07875 0.332 0.0755 0.0675 0.332 0.0755 0.05625 0.332 0.0755 0.045 0.332 0.0755 0.03375 0.332 0.0755 0.0225 0.332 0.0755 0.01125 0.332 0.0755 -7.81597e-17 0.332 0.0755 -0.01125 0.332 0.0755 -0.0225 0.332 0.0755 -0.03375 0.332 0.0755 -0.045 0.332 0.0755 -0.05625 0.332 0.0755 -0.0675 0.332 0.0755 -0.07875 0.332 0.2055 1.98952e-16 0.335 0.0805 0.095 0.335 0.0786595 0.0946489 0.335 0.0769645 0.0935355 0.335 0.0758511 0.0918405 0.335 0.0755 0.09 0.335 0.2055 0.09 0.335 0.205149 0.0918405 0.335 0.204036 0.0935355 0.335 0.20234 0.0946489 0.335 0.2005 0.095 0.335 0.0755 -0.09 0.335 0.0758511 -0.0918405 0.335 0.0769645 -0.0935355 0.335 0.0786595 -0.0946489 0.335 0.0805 -0.095 0.335 0.2005 -0.095 0.335 0.20234 -0.0946489 0.335 0.204036 -0.0935355 0.335 0.205149 -0.0918405 0.335 0.2055 -0.09 0.335 0.189591 0.095 0.335 0.178682 0.095 0.335 0.167773 0.095 0.335 0.156864 0.095 0.335 0.145955 0.095 0.335 0.135045 0.095 0.335 0.124136 0.095 0.335 0.113227 0.095 0.335 0.102318 0.095 0.335 0.0914091 0.095 0.335 0.2055 -0.07875 0.335 0.2055 -0.0675 0.335 0.2055 -0.05625 0.335 0.2055 -0.045 0.335 0.2055 -0.03375 0.335 0.2055 -0.0225 0.335 0.2055 -0.01125 0.335 0.2055 0.01125 0.335 0.2055 0.0225 0.335 0.2055 0.03375 0.335 0.2055 0.045 0.335 0.2055 0.05625 0.335 0.2055 0.0675 0.335 0.2055 0.07875 0.335 0.0914091 -0.095 0.335 0.102318 -0.095 0.335 0.113227 -0.095 0.335 0.124136 -0.095 0.335 0.135045 -0.095 0.335 0.145955 -0.095 0.335 0.156864 -0.095 0.335 0.167773 -0.095 0.335 0.178682 -0.095 0.335 0.189591 -0.095 0.335 0.0755 0.07875 0.335 0.0755 0.0675 0.335 0.0755 0.05625 0.335 0.0755 0.045 0.335 0.0755 0.03375 0.335 0.0755 0.0225 0.335 0.0755 0.01125 0.335 0.0755 -8.52651e-17 0.335 0.0755 -0.01125 0.335 0.0755 -0.0225 0.335 0.0755 -0.03375 0.335 0.0755 -0.045 0.335 0.0755 -0.05625 0.335 0.0755 -0.0675 0.335 0.0755 -0.07875 0.335 0.0905 -0.06 0.335 0.1005 -0.06 0.335 0.1105 -0.06 0.335 0.1105 -0.07 0.335 0.1105 -0.08 0.335 0.1005 -0.08 0.335 0.0905 -0.08 0.335 0.0905 -0.07 0.335 0.1705 -0.06 0.335 0.1805 -0.06 0.335 0.1905 -0.06 0.335 0.1905 -0.07 0.335 0.1905 -0.08 0.335 0.1805 -0.08 0.335 0.1705 -0.08 0.335 0.1705 -0.07 0.335 0.1505 -0.06 0.335 0.1505 -0.07 0.335 0.1505 -0.08 0.335 0.1405 -0.08 0.335 0.1305 -0.08 0.335 0.1305 -0.07 0.335 0.1305 -0.06 0.335 0.0905 -0.02 0.335 0.1005 -0.02 0.335 0.1105 -0.02 0.335 0.1105 -0.04 0.335 0.1005 -0.04 0.335 0.0905 -0.04 0.335 0.0905 -0.03 0.335 0.1705 -0.02 0.335 0.1805 -0.02 0.335 0.1905 -0.02 0.335 0.1905 -0.03 0.335 0.1905 -0.04 0.335 0.1805 -0.04 0.335 0.1705 -0.04 0.335 0.0905 0.02 0.335 0.1005 0.02 0.335 0.1105 0.02 0.335 0.1105 2.20268e-16 0.335 0.1005 1.36779e-16 0.335 0.0905 5.32907e-17 0.335 0.0905 0.01 0.335 0.1705 0.02 0.335 0.1805 0.02 0.335 0.1905 0.02 0.335 0.1905 0.01 0.335 0.1905 5.32907e-17 0.335 0.1805 5.15144e-17 0.335 0.1705 4.9738e-17 0.335 0.0905 0.06 0.335 0.1005 0.06 0.335 0.1105 0.06 0.335 0.1105 0.04 0.335 0.1005 0.04 0.335 0.0905 0.04 0.335 0.0905 0.05 0.335 0.1305 0.06 0.335 0.1405 0.06 0.335 0.1505 0.06 0.335 0.1705 0.06 0.335 0.1805 0.06 0.335 0.1905 0.06 0.335 0.1905 0.05 0.335 0.1905 0.04 0.335 0.1805 0.04 0.335 0.1705 0.04 0.335 0.1205 -0.06 0.335 0.1105 -0.05 0.335 0.1305 0.08 0.335 0.1305 0.07 0.335 0.1105 0.08 0.335 0.1205 0.08 0.335 0.1105 0.07 0.335 0.1105 -0.01 0.335 0.1105 0.03 0.335 0.1705 0.08 0.335 0.1705 0.07 0.335 0.1505 0.08 0.335 0.1605 0.08 0.335 0.1505 0.07 0.335 0.1705 -0.01 0.335 0.1605 -0.06 0.335 0.1705 -0.05 0.335 0.1705 0.03 0.335 0.191056 -0.0791667 0.335 0.191056 -0.0475 0.335 0.191056 -0.0316667 0.335 0.191056 -0.0158333 0.335 0.191056 8.88178e-17 0.335 0.0899444 -0.0791667 0.335 0.0899444 -0.0475 0.335 0.0899444 -0.0158333 0.335 0.0899444 -0.0316667 0.335 0.0899444 8.52651e-17 0.335 0.191056 0.0158333 0.335 0.191056 0.0316667 0.335 0.191056 0.0475 0.335 0.191056 0.0633333 0.335 0.191056 0.0791667 0.335 0.0899444 0.0316667 0.335 0.0899444 0.0158333 0.335 0.0899444 0.0475 0.335 0.0899444 0.0633333 0.335 0.0899444 0.0791667 0.335 0.1505 -0.04 0.335 0.1505 -0.06 0.335 0.1305 -0.04 0.335 0.1305 -0.06 0.335 0.1705 -0.02 0.335 0.1705 -0.04 0.335 0.1505 -0.02 0.335 0.1505 -0.04 0.335 0.1305 -0.02 0.335 0.1305 -0.04 0.335 0.1105 -0.02 0.335 0.1105 -0.04 0.335 0.1505 1.06581e-16 0.335 0.1505 -0.02 0.335 0.1305 7.81597e-17 0.335 0.1305 -0.02 0.335 0.1305 0.02 0.335 0.1305 5.68434e-17 0.335 0.1105 0.02 0.335 0.1105 2.84217e-17 0.335 0.1705 0.02 0.335 0.1705 4.9738e-17 0.335 0.1505 0.02 0.335 0.1505 2.13163e-17 0.335 0.1505 0.04 0.335 0.1505 0.02 0.335 0.1305 0.04 0.335 0.1305 0.02 0.335 0.1305 0.06 0.335 0.1305 0.04 0.335 0.1105 0.06 0.335 0.1105 0.04 0.335 0.1705 0.06 0.335 0.1705 0.04 0.335 0.1505 0.06 0.335 0.1505 0.04 0.335 0.1505 0.02 0.335 0.1705 0.04 0.335 0.1505 0.04 0.335 0.1505 0.03 0.335 0.1605 0.02 0.335 0.1705 0.02 0.335 0.1705 0.03 0.335 0.1605 0.04 0.335 0.1505 -0.06 0.335 0.1705 -0.04 0.335 0.1505 -0.04 0.335 0.1505 -0.05 0.335 0.1605 -0.06 0.335 0.1705 -0.06 0.335 0.1705 -0.05 0.335 0.1605 -0.04 0.335 0.1505 -0.02 0.335 0.1705 4.9738e-17 0.335 0.1705 -0.02 0.335 0.1705 -0.01 0.335 0.1605 4.26326e-17 0.335 0.1505 3.55271e-17 0.335 0.1505 -0.01 0.335 0.1605 -0.02 0.335 0.1505 0.06 0.335 0.1505 0.08 0.335 0.1505 0.07 0.335 0.1605 0.06 0.335 0.1705 0.06 0.335 0.1705 0.07 0.335 0.1705 0.08 0.335 0.1605 0.08 0.335 0.1305 0.02 0.335 0.1105 0.02 0.335 0.1105 0.04 0.335 0.1105 0.03 0.335 0.1205 0.02 0.335 0.1305 0.03 0.335 0.1305 0.04 0.335 0.1205 0.04 0.335 0.1305 -0.02 0.335 0.1105 2.20268e-16 0.335 0.1305 -0.01 0.335 0.1305 7.81597e-17 0.335 0.1205 1.49214e-16 0.335 0.1105 -0.01 0.335 0.1105 -0.02 0.335 0.1205 -0.02 0.335 0.1305 0.06 0.335 0.1105 0.06 0.335 0.1305 0.08 0.335 0.1105 0.08 0.335 0.1105 0.07 0.335 0.1205 0.06 0.335 0.1305 0.07 0.335 0.1205 0.08 0.335 0.1305 -0.06 0.335 0.1105 -0.06 0.335 0.1105 -0.04 0.335 0.1105 -0.05 0.335 0.1205 -0.06 0.335 0.1305 -0.05 0.335 0.1305 -0.04 0.335 0.1205 -0.04 0.335 0.1905 0.06 0.335 0.1705 0.04 0.335 0.1805 0.04 0.335 0.1905 0.04 0.335 0.1905 0.05 0.335 0.1805 0.06 0.335 0.1705 0.06 0.335 0.1705 0.05 0.335 0.1505 0.04 0.335 0.1305 0.06 0.335 0.1305 0.04 0.335 0.1405 0.04 0.335 0.1505 0.05 0.335 0.1505 0.06 0.335 0.1405 0.06 0.335 0.1305 0.05 0.335 0.0905 0.04 0.335 0.1105 0.06 0.335 0.0905 0.06 0.335 0.1005 0.04 0.335 0.1105 0.04 0.335 0.1105 0.05 0.335 0.1005 0.06 0.335 0.0905 0.05 0.335 0.1905 5.32907e-17 0.335 0.1705 4.9738e-17 0.335 0.1905 0.02 0.335 0.1805 5.15144e-17 0.335 0.1905 0.01 0.335 0.1805 0.02 0.335 0.1705 0.02 0.335 0.1705 0.01 0.335 0.1505 3.55271e-17 0.335 0.1305 0.02 0.335 0.1305 7.81597e-17 0.335 0.1405 5.68434e-17 0.335 0.1505 0.01 0.335 0.1505 0.02 0.335 0.1405 0.02 0.335 0.1305 0.01 0.335 0.0905 5.32907e-17 0.335 0.1105 0.02 0.335 0.0905 0.02 0.335 0.1005 1.36779e-16 0.335 0.1105 2.20268e-16 0.335 0.1105 0.01 0.335 0.1005 0.02 0.335 0.0905 0.01 0.335 0.1905 -0.04 0.335 0.1705 -0.04 0.335 0.1905 -0.02 0.335 0.1805 -0.04 0.335 0.1905 -0.03 0.335 0.1805 -0.02 0.335 0.1705 -0.02 0.335 0.1705 -0.03 0.335 0.1505 -0.04 0.335 0.1505 -0.02 0.335 0.1305 -0.04 0.335 0.1405 -0.04 0.335 0.1505 -0.03 0.335 0.1405 -0.02 0.335 0.1305 -0.02 0.335 0.1305 -0.03 0.335 0.0905 -0.04 0.335 0.1105 -0.02 0.335 0.0905 -0.02 0.335 0.1005 -0.04 0.335 0.1105 -0.04 0.335 0.1105 -0.03 0.335 0.1005 -0.02 0.335 0.0905 -0.03 0.335 0.1505 -0.08 0.335 0.1305 -0.08 0.335 0.1505 -0.06 0.335 0.1305 -0.06 0.335 0.1405 -0.08 0.335 0.1505 -0.07 0.335 0.1405 -0.06 0.335 0.1305 -0.07 0.335 0.1905 -0.08 0.335 0.1705 -0.08 0.335 0.1905 -0.06 0.335 0.1705 -0.06 0.335 0.1705 -0.07 0.335 0.1805 -0.08 0.335 0.1905 -0.07 0.335 0.1805 -0.06 0.335 0.1105 -0.08 0.335 0.0905 -0.08 0.335 0.0905 -0.06 0.335 0.1005 -0.08 0.335 0.1105 -0.07 0.335 0.1105 -0.06 0.335 0.1005 -0.06 0.335 0.0905 -0.07 0.335 + + + + + + + + + + -0.187385 0.982287 0 -0.187385 0.982287 0 -0.835809 0.549021 0 -0.835809 0.549021 0 -0.982286 0.187385 0 -0.982286 0.187385 0 -0.549021 0.835809 0 -0.549021 0.835809 0 0.982295 0.187339 0 0.982295 0.187339 0 0.548796 0.835956 0 0.548796 0.835956 0 0.187433 0.982277 0 0.187433 0.982277 0 0.8359 0.548882 0 0.8359 0.548882 0 -0.187385 -0.982287 0 -0.187385 -0.982287 0 -0.835809 -0.549021 0 -0.835809 -0.549021 0 -0.982286 -0.187385 0 -0.982286 -0.187385 0 -0.549021 -0.835809 0 -0.549021 -0.835809 0 0.187433 -0.982277 0 0.187433 -0.982277 0 0.8359 -0.548882 0 0.8359 -0.548882 0 0.982295 -0.187339 0 0.982295 -0.187339 0 0.548796 -0.835956 0 0.548796 -0.835956 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 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 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 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 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 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 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 1 0.635294 1 1 + + + + + + + + + + 0.883639 0.136973 0.883639 0.143254 0.877358 0.143254 0.883639 0.151489 0.877358 0.145207 0.883639 0.145207 0.867742 0.135592 0.874023 0.135592 0.874023 0.141873 0.882258 0.135592 0.875977 0.141873 0.875977 0.135592 0.904823 0.113027 0.904823 0.106746 0.911104 0.106746 0.904823 0.0985115 0.911104 0.104793 0.904823 0.104793 0.920719 0.114408 0.914438 0.114408 0.914438 0.108127 0.906204 0.114408 0.912485 0.108127 0.912485 0.114408 0.901489 0.114408 0.895207 0.114408 0.895207 0.108127 0.886973 0.114408 0.893254 0.108127 0.893254 0.114408 0.90287 0.0985115 0.90287 0.104793 0.896588 0.104793 0.90287 0.113027 0.896588 0.106746 0.90287 0.106746 0.920719 0.0951773 0.914438 0.0951773 0.914438 0.0888961 0.906204 0.0951773 0.912485 0.0888961 0.912485 0.0951773 0.9221 0.0792807 0.9221 0.0855619 0.915819 0.0855619 0.9221 0.0937963 0.915819 0.0875151 0.9221 0.087515 0.9221 0.0985115 0.9221 0.104793 0.915819 0.104793 0.9221 0.113027 0.915819 0.106746 0.9221 0.106746 0.906204 0.0971304 0.912485 0.0971304 0.912485 0.103412 0.920719 0.0971304 0.914438 0.103412 0.914438 0.0971304 0.920719 0.133639 0.914438 0.133639 0.914438 0.127358 0.906204 0.133639 0.912485 0.127358 0.912485 0.133639 0.9221 0.117742 0.9221 0.124023 0.915819 0.124023 0.9221 0.132258 0.915819 0.125977 0.9221 0.125977 0.9221 0.136973 0.9221 0.143254 0.915819 0.143254 0.9221 0.151489 0.915819 0.145207 0.9221 0.145207 0.906204 0.135592 0.912485 0.135592 0.912485 0.141873 0.920719 0.135592 0.914438 0.141873 0.914438 0.135592 0.90287 0.117742 0.90287 0.124023 0.896588 0.124023 0.90287 0.132258 0.896588 0.125977 0.90287 0.125977 0.886973 0.116361 0.893254 0.116361 0.893254 0.122642 0.901489 0.116361 0.895207 0.122642 0.895207 0.116361 0.343796 0.116361 0.326923 0.133234 0.31005 0.116361 0.308669 0.151489 0.308669 0.117742 0.325542 0.134615 0.308669 0.0792807 0.325542 0.0961539 0.308669 0.113027 0.343796 0.114408 0.31005 0.114408 0.326923 0.0975349 0.34713 0.117742 0.364004 0.134615 0.34713 0.151489 0.382258 0.15287 0.348511 0.15287 0.365385 0.135996 0.31005 0.15287 0.326923 0.135996 0.343796 0.15287 0.345177 0.117742 0.345177 0.151489 0.328304 0.134615 0.348511 0.114408 0.365385 0.0975349 0.382258 0.114408 0.383639 0.0792807 0.383639 0.113027 0.366766 0.0961539 0.383639 0.151489 0.366766 0.134615 0.383639 0.117742 0.348511 0.116361 0.382258 0.116361 0.365385 0.133234 0.345177 0.113027 0.328304 0.0961539 0.345177 0.0792807 0.31005 0.0778996 0.343796 0.0778996 0.326923 0.0947728 0.382258 0.0778996 0.365385 0.0947728 0.348511 0.0778996 0.34713 0.113027 0.34713 0.0792807 0.364004 0.0961539 0.420719 0.116361 0.403846 0.133234 0.386973 0.116361 0.385592 0.151489 0.385592 0.117742 0.402465 0.134615 0.385592 0.0792807 0.402465 0.0961539 0.385592 0.113027 0.420719 0.114408 0.386973 0.114408 0.403846 0.0975349 0.424053 0.117742 0.440927 0.134615 0.424053 0.151489 0.459181 0.15287 0.425435 0.15287 0.442308 0.135996 0.386973 0.15287 0.403846 0.135996 0.420719 0.15287 0.4221 0.117742 0.4221 0.151489 0.405227 0.134615 0.425435 0.114408 0.442308 0.0975349 0.459181 0.114408 0.460562 0.0792807 0.460562 0.113027 0.443689 0.0961539 0.460562 0.151489 0.443689 0.134615 0.460562 0.117742 0.425435 0.116361 0.459181 0.116361 0.442308 0.133234 0.4221 0.113027 0.405227 0.0961539 0.4221 0.0792807 0.386973 0.0778996 0.420719 0.0778996 0.403846 0.0947728 0.459181 0.0778996 0.442308 0.0947728 0.425435 0.0778996 0.424053 0.113027 0.424053 0.0792807 0.440927 0.0961539 0.497642 0.116361 0.480769 0.133234 0.463896 0.116361 0.462515 0.151489 0.462515 0.117742 0.479388 0.134615 0.462515 0.0792807 0.479388 0.0961539 0.462515 0.113027 0.497642 0.114408 0.463896 0.114408 0.480769 0.0975349 0.500977 0.117742 0.51785 0.134615 0.500977 0.151489 0.536104 0.15287 0.502358 0.15287 0.519231 0.135996 0.463896 0.15287 0.480769 0.135996 0.497642 0.15287 0.499023 0.117742 0.499023 0.151489 0.48215 0.134615 0.502358 0.114408 0.519231 0.0975349 0.536104 0.114408 0.537485 0.0792807 0.537485 0.113027 0.520612 0.0961539 0.537485 0.151489 0.520612 0.134615 0.537485 0.117742 0.502358 0.116361 0.536104 0.116361 0.519231 0.133234 0.499023 0.113027 0.48215 0.0961539 0.499023 0.0792807 0.463896 0.0778996 0.497642 0.0778996 0.480769 0.0947728 0.536104 0.0778996 0.519231 0.0947728 0.502358 0.0778996 0.500977 0.113027 0.500977 0.0792807 0.51785 0.0961539 0.574565 0.116361 0.557692 0.133234 0.540819 0.116361 0.539438 0.151489 0.539438 0.117742 0.556311 0.134615 0.539438 0.0792807 0.556311 0.0961539 0.539438 0.113027 0.574565 0.114408 0.540819 0.114408 0.557692 0.0975349 0.5779 0.117742 0.594773 0.134615 0.5779 0.151489 0.613027 0.15287 0.579281 0.15287 0.596154 0.135996 0.540819 0.15287 0.557692 0.135996 0.574565 0.15287 0.575947 0.117742 0.575947 0.151489 0.559073 0.134615 0.579281 0.114408 0.596154 0.0975349 0.613027 0.114408 0.614408 0.0792807 0.614408 0.113027 0.597535 0.0961539 0.614408 0.151489 0.597535 0.134615 0.614408 0.117742 0.579281 0.116361 0.613027 0.116361 0.596154 0.133234 0.575947 0.113027 0.559073 0.0961539 0.575947 0.0792807 0.540819 0.0778996 0.574565 0.0778996 0.557692 0.0947728 0.613027 0.0778996 0.596154 0.0947728 0.579281 0.0778996 0.5779 0.113027 0.5779 0.0792807 0.594773 0.0961539 0.651489 0.116361 0.634615 0.133234 0.617742 0.116361 0.616361 0.151489 0.616361 0.117742 0.633234 0.134615 0.616361 0.0792807 0.633234 0.0961539 0.616361 0.113027 0.651489 0.114408 0.617742 0.114408 0.634615 0.0975349 0.654823 0.117742 0.671696 0.134615 0.654823 0.151489 0.68995 0.15287 0.656204 0.15287 0.673077 0.135996 0.617742 0.15287 0.634615 0.135996 0.651489 0.15287 0.65287 0.117742 0.65287 0.151489 0.635996 0.134615 0.656204 0.114408 0.673077 0.0975349 0.68995 0.114408 0.691331 0.0792807 0.691331 0.113027 0.674458 0.0961539 0.691331 0.151489 0.674458 0.134615 0.691331 0.117742 0.656204 0.116361 0.68995 0.116361 0.673077 0.133234 0.65287 0.113027 0.635996 0.0961539 0.65287 0.0792807 0.617742 0.0778996 0.651489 0.0778996 0.634615 0.0947728 0.68995 0.0778996 0.673077 0.0947728 0.656204 0.0778996 0.654823 0.113027 0.654823 0.0792807 0.671696 0.0961539 0.728412 0.116361 0.711538 0.133234 0.694665 0.116361 0.693284 0.151489 0.693284 0.117742 0.710157 0.134615 0.693284 0.0792807 0.710157 0.0961539 0.693284 0.113027 0.728412 0.114408 0.694665 0.114408 0.711538 0.0975349 0.731746 0.117742 0.748619 0.134615 0.731746 0.151489 0.766873 0.15287 0.733127 0.15287 0.75 0.135996 0.694665 0.15287 0.711538 0.135996 0.728412 0.15287 0.729793 0.117742 0.729793 0.151489 0.71292 0.134615 0.733127 0.114408 0.75 0.0975349 0.766873 0.114408 0.768254 0.0792807 0.768254 0.113027 0.751381 0.0961539 0.768254 0.151489 0.751381 0.134615 0.768254 0.117742 0.733127 0.116361 0.766873 0.116361 0.75 0.133234 0.729793 0.113027 0.71292 0.0961539 0.729793 0.0792807 0.694665 0.0778996 0.728412 0.0778996 0.711538 0.0947728 0.766873 0.0778996 0.75 0.0947728 0.733127 0.0778996 0.731746 0.113027 0.731746 0.0792807 0.748619 0.0961539 0.805335 0.116361 0.788462 0.133234 0.771588 0.116361 0.770207 0.151489 0.770207 0.117742 0.78708 0.134615 0.770207 0.0792807 0.78708 0.0961539 0.770207 0.113027 0.805335 0.114408 0.771588 0.114408 0.788462 0.0975349 0.808669 0.117742 0.825542 0.134615 0.808669 0.151489 0.843796 0.15287 0.81005 0.15287 0.826923 0.135996 0.771588 0.15287 0.788462 0.135996 0.805335 0.15287 0.806716 0.117742 0.806716 0.151489 0.789843 0.134615 0.81005 0.114408 0.826923 0.0975349 0.843796 0.114408 0.845177 0.0792807 0.845177 0.113027 0.828304 0.0961539 0.845177 0.151489 0.828304 0.134615 0.845177 0.117742 0.81005 0.116361 0.843796 0.116361 0.826923 0.133234 0.0745654 0.999023 0.000976562 0.999023 0.000976562 0.925435 0.0759465 0.997642 0.00235763 0.924053 0.0759465 0.924053 0.693284 0.617742 0.729388 0.653846 0.693284 0.68995 0.766873 0.691331 0.694665 0.691331 0.730769 0.655227 0.151489 0.999023 0.0778996 0.999023 0.0778996 0.925435 0.15287 0.997642 0.0792807 0.924053 0.15287 0.924053 0.768254 0.68995 0.73215 0.653846 0.768254 0.617742 0.694665 0.616361 0.766873 0.616361 0.730769 0.652465 0.228412 0.999023 0.154823 0.999023 0.154823 0.925435 0.229793 0.997642 0.156204 0.924053 0.229793 0.924053 0.770207 0.617742 0.806311 0.653846 0.770207 0.68995 0.843796 0.691331 0.771588 0.691331 0.807692 0.655227 0.305335 0.999023 0.231746 0.999023 0.231746 0.925435 0.306716 0.997642 0.233127 0.924053 0.306716 0.924053 0.382258 0.999023 0.308669 0.999023 0.308669 0.925435 0.383639 0.997642 0.31005 0.924053 0.383639 0.924053 0.845177 0.68995 0.809073 0.653846 0.845177 0.617742 0.771588 0.616361 0.843796 0.616361 0.807692 0.652465 0.459181 0.999023 0.385592 0.999023 0.385592 0.925435 0.460562 0.997642 0.386973 0.924053 0.460562 0.924053 0.84713 0.617742 0.883234 0.653846 0.84713 0.68995 0.920719 0.691331 0.848511 0.691331 0.884615 0.655227 0.536104 0.999023 0.462515 0.999023 0.462515 0.925435 0.537485 0.997642 0.463896 0.924053 0.537485 0.924053 0.9221 0.68995 0.885996 0.653846 0.9221 0.617742 0.848511 0.616361 0.920719 0.616361 0.884615 0.652465 0.613027 0.999023 0.539438 0.999023 0.539438 0.925435 0.614408 0.997642 0.540819 0.924053 0.614408 0.924053 0.68995 0.999023 0.616361 0.999023 0.616361 0.925435 0.691331 0.997642 0.617742 0.924053 0.691331 0.924053 0.924053 0.617742 0.960157 0.653846 0.924053 0.68995 0.997642 0.691331 0.925435 0.691331 0.961538 0.655227 0.766873 0.999023 0.693284 0.999023 0.693284 0.925435 0.768254 0.997642 0.694665 0.924053 0.768254 0.924053 0.999023 0.68995 0.96292 0.653846 0.999023 0.617742 0.925435 0.616361 0.997642 0.616361 0.961538 0.652465 0.843796 0.999023 0.770207 0.999023 0.770207 0.925435 0.845177 0.997642 0.771588 0.924053 0.845177 0.924053 0.000976562 0.540819 0.0370805 0.576923 0.000976562 0.613027 0.0745654 0.614408 0.00235763 0.614408 0.0384615 0.578304 0.920719 0.999023 0.84713 0.999023 0.84713 0.925435 0.9221 0.997642 0.848511 0.924053 0.9221 0.924053 0.997642 0.999023 0.924053 0.999023 0.924053 0.925435 0.999023 0.997642 0.925435 0.924053 0.999023 0.924053 0.0759465 0.613027 0.0398426 0.576923 0.0759465 0.540819 0.00235763 0.539438 0.0745654 0.539438 0.0384615 0.575542 0.0745654 0.9221 0.000976562 0.9221 0.000976562 0.848511 0.0759465 0.920719 0.00235763 0.84713 0.0759465 0.84713 0.0778996 0.540819 0.114004 0.576923 0.0778996 0.613027 0.151489 0.614408 0.0792807 0.614408 0.115385 0.578304 0.151489 0.9221 0.0778996 0.9221 0.0778996 0.848511 0.15287 0.920719 0.0792807 0.84713 0.15287 0.84713 0.15287 0.613027 0.116766 0.576923 0.15287 0.540819 0.0792807 0.539438 0.151489 0.539438 0.115385 0.575542 0.228412 0.9221 0.154823 0.9221 0.154823 0.848511 0.229793 0.920719 0.156204 0.84713 0.229793 0.84713 0.305335 0.9221 0.231746 0.9221 0.231746 0.848511 0.306716 0.920719 0.233127 0.84713 0.306716 0.84713 0.154823 0.540819 0.190927 0.576923 0.154823 0.613027 0.228412 0.614408 0.156204 0.614408 0.192308 0.578304 0.382258 0.9221 0.308669 0.9221 0.308669 0.848511 0.383639 0.920719 0.31005 0.84713 0.383639 0.84713 0.229793 0.613027 0.193689 0.576923 0.229793 0.540819 0.156204 0.539438 0.228412 0.539438 0.192308 0.575542 0.459181 0.9221 0.385592 0.9221 0.385592 0.848511 0.460562 0.920719 0.386973 0.84713 0.460562 0.84713 0.231746 0.540819 0.26785 0.576923 0.231746 0.613027 0.305335 0.614408 0.233127 0.614408 0.269231 0.578304 0.536104 0.9221 0.462515 0.9221 0.462515 0.848511 0.537485 0.920719 0.463896 0.84713 0.537485 0.84713 0.613027 0.9221 0.539438 0.9221 0.539438 0.848511 0.614408 0.920719 0.540819 0.84713 0.614408 0.84713 0.306716 0.613027 0.270612 0.576923 0.306716 0.540819 0.233127 0.539438 0.305335 0.539438 0.269231 0.575542 0.68995 0.9221 0.616361 0.9221 0.616361 0.848511 0.691331 0.920719 0.617742 0.84713 0.691331 0.84713 0.308669 0.540819 0.344773 0.576923 0.308669 0.613027 0.382258 0.614408 0.31005 0.614408 0.346154 0.578304 0.766873 0.9221 0.693284 0.9221 0.693284 0.848511 0.768254 0.920719 0.694665 0.84713 0.768254 0.84713 0.383639 0.613027 0.347535 0.576923 0.383639 0.540819 0.31005 0.539438 0.382258 0.539438 0.346154 0.575542 0.843796 0.9221 0.770207 0.9221 0.770207 0.848511 0.845177 0.920719 0.771588 0.84713 0.845177 0.84713 0.920719 0.9221 0.84713 0.9221 0.84713 0.848511 0.9221 0.920719 0.848511 0.84713 0.9221 0.84713 0.385592 0.540819 0.421696 0.576923 0.385592 0.613027 0.459181 0.614408 0.386973 0.614408 0.423077 0.578304 0.997642 0.9221 0.924053 0.9221 0.924053 0.848511 0.999023 0.920719 0.925435 0.84713 0.999023 0.84713 0.460562 0.613027 0.424458 0.576923 0.460562 0.540819 0.386973 0.539438 0.459181 0.539438 0.423077 0.575542 0.0745654 0.845177 0.000976562 0.845177 0.000976562 0.771588 0.0759465 0.843796 0.00235763 0.770207 0.0759465 0.770207 0.462515 0.540819 0.498619 0.576923 0.462515 0.613027 0.536104 0.614408 0.463896 0.614408 0.5 0.578304 0.151489 0.845177 0.0778996 0.845177 0.0778996 0.771588 0.15287 0.843796 0.0792807 0.770207 0.15287 0.770207 0.228412 0.845177 0.154823 0.845177 0.154823 0.771588 0.229793 0.843796 0.156204 0.770207 0.229793 0.770207 0.537485 0.613027 0.501381 0.576923 0.537485 0.540819 0.463896 0.539438 0.536104 0.539438 0.5 0.575542 0.305335 0.845177 0.231746 0.845177 0.231746 0.771588 0.306716 0.843796 0.233127 0.770207 0.306716 0.770207 0.539438 0.540819 0.575542 0.576923 0.539438 0.613027 0.613027 0.614408 0.540819 0.614408 0.576923 0.578304 0.382258 0.845177 0.308669 0.845177 0.308669 0.771588 0.383639 0.843796 0.31005 0.770207 0.383639 0.770207 0.614408 0.613027 0.578304 0.576923 0.614408 0.540819 0.540819 0.539438 0.613027 0.539438 0.576923 0.575542 0.459181 0.845177 0.385592 0.845177 0.385592 0.771588 0.460562 0.843796 0.386973 0.770207 0.460562 0.770207 0.536104 0.845177 0.462515 0.845177 0.462515 0.771588 0.537485 0.843796 0.463896 0.770207 0.537485 0.770207 0.616361 0.540819 0.652465 0.576923 0.616361 0.613027 0.68995 0.614408 0.617742 0.614408 0.653846 0.578304 0.613027 0.845177 0.539438 0.845177 0.539438 0.771588 0.614408 0.843796 0.540819 0.770207 0.614408 0.770207 0.691331 0.613027 0.655227 0.576923 0.691331 0.540819 0.617742 0.539438 0.68995 0.539438 0.653846 0.575542 0.68995 0.845177 0.616361 0.845177 0.616361 0.771588 0.691331 0.843796 0.617742 0.770207 0.691331 0.770207 0.693284 0.540819 0.729388 0.576923 0.693284 0.613027 0.766873 0.614408 0.694665 0.614408 0.730769 0.578304 0.766873 0.845177 0.693284 0.845177 0.693284 0.771588 0.768254 0.843796 0.694665 0.770207 0.768254 0.770207 0.843796 0.845177 0.770207 0.845177 0.770207 0.771588 0.845177 0.843796 0.771588 0.770207 0.845177 0.770207 0.768254 0.613027 0.73215 0.576923 0.768254 0.540819 0.694665 0.539438 0.766873 0.539438 0.730769 0.575542 0.920719 0.845177 0.84713 0.845177 0.84713 0.771588 0.9221 0.843796 0.848511 0.770207 0.9221 0.770207 0.770207 0.540819 0.806311 0.576923 0.770207 0.613027 0.843796 0.614408 0.771588 0.614408 0.807692 0.578304 0.997642 0.845177 0.924053 0.845177 0.924053 0.771588 0.999023 0.843796 0.925435 0.770207 0.999023 0.770207 0.845177 0.613027 0.809073 0.576923 0.845177 0.540819 0.771588 0.539438 0.843796 0.539438 0.807692 0.575542 0.0745654 0.768254 0.000976562 0.768254 0.000976562 0.694665 0.0759465 0.766873 0.00235763 0.693284 0.0759465 0.693284 0.855769 0.104388 0.848511 0.0971304 0.863027 0.0971304 0.912485 0.116361 0.912485 0.122642 0.906204 0.116361 0.84713 0.613027 0.84713 0.540819 0.883234 0.576923 0.884615 0.578304 0.920719 0.614408 0.848511 0.614408 0.910035 0.0817308 0.912485 0.0792807 0.912485 0.0841809 0.885996 0.576923 0.9221 0.540819 0.9221 0.613027 0.151489 0.768254 0.0778996 0.768254 0.0778996 0.694665 0.848511 0.539438 0.920719 0.539438 0.884615 0.575542 0.924053 0.540819 0.960157 0.576923 0.924053 0.613027 0.925435 0.614408 0.961538 0.578304 0.997642 0.614408 0.0792807 0.693284 0.15287 0.693284 0.15287 0.766873 0.999023 0.540819 0.999023 0.613027 0.96292 0.576923 0.925435 0.539438 0.997642 0.539438 0.961538 0.575542 0.000976562 0.463896 0.0370805 0.5 0.000976562 0.536104 0.0745654 0.537485 0.00235763 0.537485 0.0384615 0.501381 0.0759465 0.463896 0.0759465 0.536104 0.0398426 0.5 0.0745654 0.462515 0.0384615 0.498619 0.00235763 0.462515 0.0778996 0.536104 0.0778996 0.463896 0.114004 0.5 0.151489 0.537485 0.0792807 0.537485 0.115385 0.501381 0.15287 0.536104 0.116766 0.5 0.15287 0.463896 0.0792807 0.462515 0.151489 0.462515 0.115385 0.498619 0.154823 0.463896 0.190927 0.5 0.154823 0.536104 0.156204 0.537485 0.192308 0.501381 0.228412 0.537485 0.229793 0.463896 0.229793 0.536104 0.193689 0.5 0.192308 0.498619 0.156204 0.462515 0.228412 0.462515 0.231746 0.463896 0.26785 0.5 0.231746 0.536104 0.305335 0.537485 0.233127 0.537485 0.269231 0.501381 0.228412 0.768254 0.154823 0.768254 0.154823 0.694665 0.306716 0.463896 0.306716 0.536104 0.270612 0.5 0.305335 0.462515 0.269231 0.498619 0.233127 0.462515 0.308669 0.463896 0.344773 0.5 0.308669 0.536104 0.382258 0.537485 0.31005 0.537485 0.346154 0.501381 0.156204 0.693284 0.229793 0.693284 0.229793 0.766873 0.383639 0.463896 0.383639 0.536104 0.347535 0.5 0.31005 0.462515 0.382258 0.462515 0.346154 0.498619 0.920719 0.116361 0.914438 0.122642 0.914438 0.116361 0.911104 0.0778996 0.908654 0.0803497 0.906204 0.0778996 0.84713 0.113027 0.84713 0.0985115 0.854388 0.105769 0.385592 0.463896 0.421696 0.5 0.385592 0.536104 0.305335 0.768254 0.231746 0.768254 0.231746 0.694665 0.459181 0.537485 0.386973 0.537485 0.423077 0.501381 0.460562 0.536104 0.424458 0.5 0.460562 0.463896 0.459181 0.462515 0.423077 0.498619 0.386973 0.462515 0.462515 0.536104 0.462515 0.463896 0.498619 0.5 0.463896 0.537485 0.5 0.501381 0.536104 0.537485 0.537485 0.463896 0.537485 0.536104 0.501381 0.5 0.536104 0.462515 0.5 0.498619 0.463896 0.462515 0.306716 0.766873 0.233127 0.693284 0.306716 0.693284 0.539438 0.463896 0.575542 0.5 0.539438 0.536104 0.540819 0.537485 0.576923 0.501381 0.613027 0.537485 0.614408 0.463896 0.614408 0.536104 0.578304 0.5 0.576923 0.498619 0.540819 0.462515 0.613027 0.462515 0.616361 0.463896 0.652465 0.5 0.616361 0.536104 0.68995 0.537485 0.617742 0.537485 0.653846 0.501381 0.691331 0.463896 0.691331 0.536104 0.655227 0.5 0.68995 0.462515 0.653846 0.498619 0.617742 0.462515 0.693284 0.536104 0.693284 0.463896 0.729388 0.5 0.766873 0.537485 0.694665 0.537485 0.730769 0.501381 0.768254 0.536104 0.73215 0.5 0.768254 0.463896 0.694665 0.462515 0.766873 0.462515 0.730769 0.498619 0.770207 0.463896 0.806311 0.5 0.770207 0.536104 0.843796 0.537485 0.771588 0.537485 0.807692 0.501381 0.845177 0.463896 0.845177 0.536104 0.809073 0.5 0.771588 0.462515 0.843796 0.462515 0.807692 0.498619 0.883234 0.5 0.84713 0.536104 0.84713 0.463896 0.920719 0.0778996 0.918269 0.0803497 0.915819 0.0778996 0.904823 0.132258 0.904823 0.125977 0.911104 0.125977 0.920719 0.537485 0.848511 0.537485 0.884615 0.501381 0.854388 0.0865385 0.84713 0.0937963 0.84713 0.0792807 0.382258 0.768254 0.308669 0.768254 0.308669 0.694665 0.9221 0.463896 0.9221 0.536104 0.885996 0.5 0.920719 0.462515 0.884615 0.498619 0.848511 0.462515 0.924053 0.536104 0.924053 0.463896 0.960157 0.5 0.925435 0.537485 0.961538 0.501381 0.997642 0.537485 0.383639 0.766873 0.31005 0.693284 0.383639 0.693284 0.999023 0.536104 0.96292 0.5 0.999023 0.463896 0.997642 0.462515 0.961538 0.498619 0.925435 0.462515 0.000976562 0.459181 0.000976562 0.386973 0.0370805 0.423077 0.00235763 0.460562 0.0384615 0.424458 0.0745654 0.460562 0.0759465 0.459181 0.0398426 0.423077 0.0759465 0.386973 0.00235763 0.385592 0.0745654 0.385592 0.0384615 0.421696 0.0778996 0.386973 0.114004 0.423077 0.0778996 0.459181 0.385592 0.694665 0.459181 0.768254 0.385592 0.768254 0.0792807 0.460562 0.115385 0.424458 0.151489 0.460562 0.460562 0.766873 0.386973 0.693284 0.460562 0.693284 0.15287 0.459181 0.116766 0.423077 0.15287 0.386973 0.0792807 0.385592 0.151489 0.385592 0.115385 0.421696 0.154823 0.386973 0.190927 0.423077 0.154823 0.459181 0.228412 0.460562 0.156204 0.460562 0.192308 0.424458 0.229793 0.459181 0.193689 0.423077 0.229793 0.386973 0.192308 0.421696 0.156204 0.385592 0.228412 0.385592 0.231746 0.386973 0.26785 0.423077 0.231746 0.459181 0.305335 0.460562 0.233127 0.460562 0.269231 0.424458 0.536104 0.768254 0.462515 0.768254 0.462515 0.694665 0.306716 0.386973 0.306716 0.459181 0.270612 0.423077 0.233127 0.385592 0.305335 0.385592 0.269231 0.421696 0.308669 0.386973 0.344773 0.423077 0.308669 0.459181 0.537485 0.766873 0.463896 0.693284 0.537485 0.693284 0.916888 0.0817308 0.914438 0.0841809 0.914438 0.0792807 0.31005 0.460562 0.346154 0.424458 0.382258 0.460562 0.347535 0.423077 0.383639 0.386973 0.383639 0.459181 0.863027 0.0951773 0.848511 0.0951773 0.855769 0.0879195 0.904823 0.117742 0.911104 0.124023 0.904823 0.124023 0.346154 0.421696 0.31005 0.385592 0.382258 0.385592 0.911104 0.0875151 0.908654 0.0899652 0.906204 0.087515 0.875977 0.0888961 0.882258 0.0951773 0.875977 0.0951773 0.866361 0.0985115 0.873619 0.105769 0.866361 0.113027 0.421696 0.423077 0.385592 0.459181 0.385592 0.386973 0.459181 0.460562 0.386973 0.460562 0.423077 0.424458 0.864408 0.132258 0.848511 0.116361 0.864408 0.116361 0.424458 0.423077 0.460562 0.386973 0.460562 0.459181 0.874023 0.0951773 0.867742 0.0951773 0.874023 0.0888961 0.883639 0.0792807 0.883639 0.0855619 0.877358 0.0855619 0.539438 0.694665 0.613027 0.768254 0.539438 0.768254 0.423077 0.421696 0.386973 0.385592 0.459181 0.385592 0.498619 0.423077 0.462515 0.459181 0.462515 0.386973 0.463896 0.460562 0.5 0.424458 0.536104 0.460562 0.537485 0.386973 0.537485 0.459181 0.501381 0.423077 0.463896 0.385592 0.536104 0.385592 0.5 0.421696 0.539438 0.386973 0.575542 0.423077 0.539438 0.459181 0.540819 0.460562 0.576923 0.424458 0.613027 0.460562 0.614408 0.386973 0.614408 0.459181 0.578304 0.423077 0.540819 0.385592 0.613027 0.385592 0.576923 0.421696 0.343796 0.193284 0.308669 0.228412 0.308669 0.193284 0.616361 0.386973 0.652465 0.423077 0.616361 0.459181 0.68995 0.460562 0.617742 0.460562 0.653846 0.424458 0.691331 0.386973 0.691331 0.459181 0.655227 0.423077 0.614408 0.766873 0.540819 0.693284 0.614408 0.693284 0.68995 0.385592 0.653846 0.421696 0.617742 0.385592 0.693284 0.459181 0.693284 0.386973 0.729388 0.423077 0.694665 0.460562 0.730769 0.424458 0.766873 0.460562 0.768254 0.386973 0.768254 0.459181 0.73215 0.423077 0.867742 0.114408 0.875 0.10715 0.882258 0.114408 0.883639 0.0937963 0.877358 0.0875151 0.883639 0.087515 0.308669 0.156204 0.343796 0.191331 0.308669 0.191331 0.694665 0.385592 0.766873 0.385592 0.730769 0.421696 0.770207 0.386973 0.806311 0.423077 0.770207 0.459181 0.843796 0.460562 0.771588 0.460562 0.807692 0.424458 0.809073 0.423077 0.845177 0.386973 0.845177 0.459181 0.883639 0.0985115 0.883639 0.104793 0.877358 0.104793 0.855769 0.10715 0.863027 0.114408 0.848511 0.114408 0.806716 0.113027 0.789843 0.0961539 0.806716 0.0792807 0.864408 0.0985115 0.864408 0.113027 0.85715 0.105769 0.382258 0.229793 0.34713 0.229793 0.34713 0.194665 0.345177 0.194665 0.345177 0.229793 0.31005 0.229793 0.383639 0.191331 0.348511 0.191331 0.383639 0.156204 0.807692 0.421696 0.771588 0.385592 0.843796 0.385592 0.84713 0.386973 0.883234 0.423077 0.84713 0.459181 0.884615 0.424458 0.920719 0.460562 0.848511 0.460562 0.383639 0.228412 0.348511 0.193284 0.383639 0.193284 0.9221 0.459181 0.885996 0.423077 0.9221 0.386973 0.920719 0.385592 0.884615 0.421696 0.848511 0.385592 0.924053 0.459181 0.924053 0.386973 0.960157 0.423077 0.866361 0.132258 0.866361 0.116361 0.882258 0.116361 0.997642 0.460562 0.925435 0.460562 0.961538 0.424458 0.999023 0.386973 0.999023 0.459181 0.96292 0.423077 0.925435 0.385592 0.997642 0.385592 0.961538 0.421696 0.000976562 0.31005 0.0370805 0.346154 0.000976562 0.382258 0.0745654 0.383639 0.00235763 0.383639 0.0384615 0.347535 0.0759465 0.31005 0.0759465 0.382258 0.0398426 0.346154 0.0745654 0.308669 0.0384615 0.344773 0.00235763 0.308669 0.0778996 0.382258 0.0778996 0.31005 0.114004 0.346154 0.0792807 0.383639 0.115385 0.347535 0.151489 0.383639 0.345177 0.18995 0.31005 0.154823 0.345177 0.154823 0.68995 0.768254 0.616361 0.768254 0.616361 0.694665 0.15287 0.382258 0.116766 0.346154 0.15287 0.31005 0.0792807 0.308669 0.151489 0.308669 0.115385 0.344773 0.886973 0.135592 0.901489 0.135592 0.894231 0.14285 0.907273 0.0913462 0.904823 0.0937963 0.904823 0.088896 0.883639 0.106746 0.883639 0.113027 0.877358 0.106746 0.154823 0.382258 0.154823 0.31005 0.190927 0.346154 0.874023 0.0971304 0.874023 0.103412 0.867742 0.0971304 0.84713 0.151489 0.84713 0.135592 0.863027 0.135592 0.156204 0.383639 0.192308 0.347535 0.228412 0.383639 0.229793 0.382258 0.193689 0.346154 0.229793 0.31005 0.84713 0.133639 0.84713 0.117742 0.863027 0.133639 0.192308 0.344773 0.156204 0.308669 0.228412 0.308669 0.875977 0.103412 0.875977 0.0971304 0.882258 0.0971304 0.382258 0.154823 0.34713 0.18995 0.34713 0.154823 0.231746 0.382258 0.231746 0.31005 0.26785 0.346154 0.385592 0.193284 0.420719 0.193284 0.385592 0.228412 0.305335 0.383639 0.233127 0.383639 0.269231 0.347535 0.385592 0.156204 0.420719 0.191331 0.385592 0.191331 0.459181 0.229793 0.424053 0.229793 0.424053 0.194665 0.306716 0.31005 0.306716 0.382258 0.270612 0.346154 0.269231 0.344773 0.233127 0.308669 0.305335 0.308669 0.4221 0.194665 0.4221 0.229793 0.386973 0.229793 0.885592 0.151489 0.885592 0.136973 0.89285 0.144231 0.864408 0.0855619 0.858127 0.0855619 0.864408 0.0792807 0.308669 0.31005 0.344773 0.346154 0.308669 0.382258 0.382258 0.383639 0.31005 0.383639 0.346154 0.347535 0.383639 0.382258 0.347535 0.346154 0.383639 0.31005 0.346154 0.344773 0.31005 0.308669 0.382258 0.308669 0.421696 0.346154 0.385592 0.382258 0.385592 0.31005 0.885592 0.132258 0.885592 0.117742 0.89285 0.125 0.864408 0.0937963 0.858127 0.0875151 0.864408 0.087515 0.771588 0.0778996 0.805335 0.0778996 0.788462 0.0947728 0.691331 0.766873 0.617742 0.693284 0.691331 0.693284 0.386973 0.383639 0.423077 0.347535 0.459181 0.383639 0.460562 0.382258 0.424458 0.346154 0.460562 0.31005 0.386973 0.308669 0.459181 0.308669 0.423077 0.344773 0.462515 0.382258 0.462515 0.31005 0.498619 0.346154 0.425435 0.191331 0.460562 0.156204 0.460562 0.191331 0.766873 0.768254 0.693284 0.768254 0.693284 0.694665 0.425435 0.193284 0.460562 0.193284 0.460562 0.228412 0.463896 0.383639 0.5 0.347535 0.536104 0.383639 0.537485 0.31005 0.537485 0.382258 0.501381 0.346154 0.901489 0.133639 0.886973 0.133639 0.894231 0.126381 0.854793 0.0841809 0.848511 0.0778996 0.854793 0.0778996 0.863027 0.0778996 0.856746 0.0841809 0.856746 0.0778996 0.536104 0.308669 0.5 0.344773 0.463896 0.308669 0.539438 0.382258 0.539438 0.31005 0.575542 0.346154 0.540819 0.383639 0.576923 0.347535 0.613027 0.383639 0.614408 0.31005 0.614408 0.382258 0.578304 0.346154 0.540819 0.308669 0.613027 0.308669 0.576923 0.344773 0.616361 0.31005 0.652465 0.346154 0.616361 0.382258 0.904823 0.136973 0.91208 0.144231 0.904823 0.151489 0.653846 0.347535 0.68995 0.383639 0.617742 0.383639 0.906204 0.15287 0.913462 0.145612 0.920719 0.15287 0.691331 0.382258 0.655227 0.346154 0.691331 0.31005 0.386973 0.154823 0.4221 0.154823 0.4221 0.18995 0.68995 0.308669 0.653846 0.344773 0.617742 0.308669 0.874023 0.0778996 0.874023 0.0841809 0.867742 0.0778996 0.459181 0.154823 0.424053 0.18995 0.424053 0.154823 0.729388 0.346154 0.693284 0.382258 0.693284 0.31005 0.497642 0.193284 0.462515 0.228412 0.462515 0.193284 0.462515 0.156204 0.497642 0.191331 0.462515 0.191331 0.875977 0.0778996 0.882258 0.0778996 0.875977 0.0841809 0.694665 0.383639 0.730769 0.347535 0.766873 0.383639 0.768254 0.31005 0.768254 0.382258 0.73215 0.346154 0.81005 0.0778996 0.843796 0.0778996 0.826923 0.0947728 0.894231 0.145612 0.901489 0.15287 0.886973 0.15287 0.730769 0.344773 0.694665 0.308669 0.766873 0.308669 0.770207 0.31005 0.806311 0.346154 0.770207 0.382258 0.807692 0.347535 0.843796 0.383639 0.771588 0.383639 0.904823 0.0841808 0.904823 0.0792807 0.907273 0.0817308 0.872642 0.0875151 0.866361 0.0937963 0.866361 0.087515 0.845177 0.382258 0.809073 0.346154 0.845177 0.31005 0.895612 0.144231 0.90287 0.136973 0.90287 0.151489 0.807692 0.344773 0.771588 0.308669 0.843796 0.308669 0.883234 0.346154 0.84713 0.382258 0.84713 0.31005 0.768254 0.693284 0.768254 0.766873 0.694665 0.693284 0.920719 0.383639 0.848511 0.383639 0.884615 0.347535 0.500977 0.194665 0.536104 0.229793 0.500977 0.229793 0.9221 0.382258 0.885996 0.346154 0.9221 0.31005 0.920719 0.308669 0.884615 0.344773 0.848511 0.308669 0.960157 0.346154 0.924053 0.382258 0.924053 0.31005 0.961538 0.347535 0.997642 0.383639 0.925435 0.383639 0.96292 0.346154 0.999023 0.31005 0.999023 0.382258 0.997642 0.308669 0.961538 0.344773 0.925435 0.308669 0.000976562 0.305335 0.000976562 0.233127 0.0370805 0.269231 0.770207 0.694665 0.843796 0.768254 0.770207 0.768254 0.0384615 0.270612 0.0745654 0.306716 0.00235763 0.306716 0.845177 0.766873 0.771588 0.693284 0.845177 0.693284 0.0398426 0.269231 0.0759465 0.233127 0.0759465 0.305335 0.872642 0.0855619 0.866361 0.0855619 0.866361 0.0792807 0.463896 0.229793 0.499023 0.194665 0.499023 0.229793 0.0745654 0.231746 0.0384615 0.26785 0.00235763 0.231746 0.114004 0.269231 0.0778996 0.305335 0.0778996 0.233127 0.0792807 0.306716 0.115385 0.270612 0.151489 0.306716 0.537485 0.191331 0.502358 0.191331 0.537485 0.156204 0.90287 0.0855619 0.896588 0.0855619 0.90287 0.0792807 0.15287 0.305335 0.116766 0.269231 0.15287 0.233127 0.0792807 0.231746 0.151489 0.231746 0.115385 0.26785 0.190927 0.269231 0.154823 0.305335 0.154823 0.233127 0.866361 0.136973 0.873619 0.144231 0.866361 0.151489 0.192308 0.270612 0.228412 0.306716 0.156204 0.306716 0.84713 0.694665 0.920719 0.768254 0.84713 0.768254 0.882258 0.15287 0.867742 0.15287 0.875 0.145612 0.90287 0.087515 0.90287 0.0937963 0.896588 0.0875151 0.886973 0.0778996 0.893254 0.0778996 0.893254 0.0841809 0.855769 0.145612 0.863027 0.15287 0.848511 0.15287 0.229793 0.305335 0.193689 0.269231 0.229793 0.233127 0.156204 0.231746 0.228412 0.231746 0.192308 0.26785 0.231746 0.305335 0.231746 0.233127 0.26785 0.269231 0.864408 0.136973 0.864408 0.151489 0.85715 0.144231 0.502358 0.193284 0.537485 0.193284 0.537485 0.228412 0.882258 0.133639 0.867742 0.133639 0.875 0.126381 0.463896 0.154823 0.499023 0.154823 0.499023 0.18995 0.9221 0.766873 0.848511 0.693284 0.9221 0.693284 0.233127 0.306716 0.269231 0.270612 0.305335 0.306716 0.306716 0.233127 0.306716 0.305335 0.270612 0.269231 0.305335 0.231746 0.269231 0.26785 0.233127 0.231746 0.308669 0.305335 0.308669 0.233127 0.344773 0.269231 0.382258 0.306716 0.31005 0.306716 0.346154 0.270612 0.347535 0.269231 0.383639 0.233127 0.383639 0.305335 0.500977 0.18995 0.500977 0.154823 0.536104 0.154823 0.924053 0.768254 0.924053 0.694665 0.997642 0.768254 0.31005 0.231746 0.382258 0.231746 0.346154 0.26785 0.808669 0.0792807 0.825542 0.0961539 0.808669 0.113027 0.385592 0.233127 0.421696 0.269231 0.385592 0.305335 0.999023 0.766873 0.925435 0.693284 0.999023 0.693284 0.386973 0.306716 0.423077 0.270612 0.459181 0.306716 0.460562 0.233127 0.460562 0.305335 0.424458 0.269231 0.423077 0.26785 0.386973 0.231746 0.459181 0.231746 0.462515 0.233127 0.498619 0.269231 0.462515 0.305335 0.876381 0.125 0.883639 0.117742 0.883639 0.132258 0.908654 0.0831118 0.911104 0.0855619 0.906204 0.0855619 0.895207 0.0841809 0.895207 0.0778996 0.901489 0.0778996 0.5 0.270612 0.536104 0.306716 0.463896 0.306716 0.537485 0.233127 0.537485 0.305335 0.501381 0.269231 0.536104 0.231746 0.5 0.26785 0.463896 0.231746 0.0745654 0.691331 0.000976562 0.691331 0.000976562 0.617742 0.0759465 0.68995 0.00235763 0.616361 0.0759465 0.616361 0.151489 0.691331 0.0778996 0.691331 0.0778996 0.617742 0.15287 0.68995 0.0792807 0.616361 0.15287 0.616361 0.228412 0.691331 0.154823 0.691331 0.154823 0.617742 0.229793 0.68995 0.156204 0.616361 0.229793 0.616361 0.305335 0.691331 0.231746 0.691331 0.231746 0.617742 0.306716 0.68995 0.233127 0.616361 0.306716 0.616361 0.382258 0.691331 0.308669 0.691331 0.308669 0.617742 0.383639 0.68995 0.31005 0.616361 0.383639 0.616361 0.459181 0.691331 0.385592 0.691331 0.385592 0.617742 0.460562 0.68995 0.386973 0.616361 0.460562 0.616361 0.536104 0.691331 0.462515 0.691331 0.462515 0.617742 0.537485 0.68995 0.463896 0.616361 0.537485 0.616361 0.613027 0.691331 0.539438 0.691331 0.539438 0.617742 0.614408 0.68995 0.540819 0.616361 0.614408 0.616361 0.68995 0.691331 0.616361 0.691331 0.616361 0.617742 0.691331 0.68995 0.617742 0.616361 0.691331 0.616361 0.539438 0.233127 0.575542 0.269231 0.539438 0.305335 0.574565 0.193284 0.539438 0.228412 0.539438 0.193284 0.539438 0.156204 0.574565 0.191331 0.539438 0.191331 0.5779 0.194665 0.613027 0.229793 0.5779 0.229793 0.575947 0.194665 0.575947 0.229793 0.540819 0.229793 0.576923 0.270612 0.613027 0.306716 0.540819 0.306716 0.614408 0.305335 0.578304 0.269231 0.614408 0.233127 0.579281 0.191331 0.614408 0.156204 0.614408 0.191331 0.614408 0.228412 0.579281 0.193284 0.614408 0.193284 0.575947 0.18995 0.540819 0.154823 0.575947 0.154823 0.5779 0.18995 0.5779 0.154823 0.613027 0.154823 0.576923 0.26785 0.540819 0.231746 0.613027 0.231746 0.616361 0.233127 0.652465 0.269231 0.616361 0.305335 0.651489 0.193284 0.616361 0.228412 0.616361 0.193284 0.616361 0.156204 0.651489 0.191331 0.616361 0.191331 0.654823 0.194665 0.68995 0.229793 0.654823 0.229793 0.65287 0.194665 0.65287 0.229793 0.617742 0.229793 0.653846 0.270612 0.68995 0.306716 0.617742 0.306716 0.691331 0.156204 0.691331 0.191331 0.656204 0.191331 0.691331 0.228412 0.656204 0.193284 0.691331 0.193284 0.691331 0.233127 0.691331 0.305335 0.655227 0.269231 0.617742 0.231746 0.68995 0.231746 0.653846 0.26785 0.617742 0.154823 0.65287 0.154823 0.65287 0.18995 0.654823 0.154823 0.68995 0.154823 0.654823 0.18995 0.693284 0.305335 0.693284 0.233127 0.729388 0.269231 0.728412 0.193284 0.693284 0.228412 0.693284 0.193284 0.693284 0.156204 0.728412 0.191331 0.693284 0.191331 0.731746 0.194665 0.766873 0.229793 0.731746 0.229793 0.729793 0.194665 0.729793 0.229793 0.694665 0.229793 0.694665 0.306716 0.730769 0.270612 0.766873 0.306716 0.768254 0.156204 0.768254 0.191331 0.733127 0.191331 0.768254 0.228412 0.733127 0.193284 0.768254 0.193284 0.768254 0.305335 0.73215 0.269231 0.768254 0.233127 0.766873 0.231746 0.730769 0.26785 0.694665 0.231746 0.694665 0.154823 0.729793 0.154823 0.729793 0.18995 0.731746 0.154823 0.766873 0.154823 0.731746 0.18995 0.770207 0.228412 0.770207 0.193284 0.805335 0.193284 0.770207 0.156204 0.805335 0.191331 0.770207 0.191331 0.770207 0.305335 0.770207 0.233127 0.806311 0.269231 0.843796 0.306716 0.771588 0.306716 0.807692 0.270612 0.843796 0.229793 0.808669 0.229793 0.808669 0.194665 0.806716 0.229793 0.771588 0.229793 0.806716 0.194665 0.845177 0.233127 0.845177 0.305335 0.809073 0.269231 0.81005 0.191331 0.845177 0.156204 0.845177 0.191331 0.845177 0.228412 0.81005 0.193284 0.845177 0.193284 0.806716 0.18995 0.771588 0.154823 0.806716 0.154823 0.808669 0.18995 0.808669 0.154823 0.843796 0.154823 0.843796 0.231746 0.807692 0.26785 0.771588 0.231746 0.84713 0.305335 0.84713 0.233127 0.883234 0.269231 0.882258 0.193284 0.84713 0.228412 0.84713 0.193284 0.84713 0.156204 0.882258 0.191331 0.84713 0.191331 0.885592 0.194665 0.920719 0.229793 0.885592 0.229793 0.883639 0.194665 0.883639 0.229793 0.848511 0.229793 0.848511 0.306716 0.884615 0.270612 0.920719 0.306716 0.9221 0.156204 0.9221 0.191331 0.886973 0.191331 0.9221 0.228412 0.886973 0.193284 0.9221 0.193284 0.9221 0.305335 0.885996 0.269231 0.9221 0.233127 0.920719 0.231746 0.884615 0.26785 0.848511 0.231746 0.848511 0.154823 0.883639 0.154823 0.883639 0.18995 0.885592 0.154823 0.920719 0.154823 0.885592 0.18995 0.924053 0.233127 0.960157 0.269231 0.924053 0.305335 0.959181 0.193284 0.924053 0.228412 0.924053 0.193284 0.924053 0.156204 0.959181 0.191331 0.924053 0.191331 0.962515 0.194665 0.997642 0.229793 0.962515 0.229793 0.960562 0.194665 0.960562 0.229793 0.925435 0.229793 0.961538 0.270612 0.997642 0.306716 0.925435 0.306716 0.999023 0.156204 0.999023 0.191331 0.963896 0.191331 0.999023 0.228412 0.963896 0.193284 0.999023 0.193284 0.999023 0.305335 0.96292 0.269231 0.999023 0.233127 0.997642 0.231746 0.961538 0.26785 0.925435 0.231746 0.925435 0.154823 0.960562 0.154823 0.960562 0.18995 0.962515 0.154823 0.997642 0.154823 0.962515 0.18995 0.000976562 0.151489 0.000976562 0.116361 0.0361039 0.116361 0.000976562 0.0792807 0.0361039 0.114408 0.000976562 0.114408 0.000976562 0.156204 0.0370805 0.192308 0.000976562 0.228412 0.00235763 0.229793 0.0384615 0.193689 0.0745654 0.229793 0.0745654 0.15287 0.0394381 0.15287 0.0394381 0.117742 0.037485 0.15287 0.00235763 0.15287 0.037485 0.117742 0.0759465 0.0792807 0.0759465 0.114408 0.0408192 0.114408 0.0759465 0.151489 0.0408192 0.116361 0.0759465 0.116361 0.0759465 0.156204 0.0759465 0.228412 0.0398426 0.192308 0.037485 0.113027 0.00235763 0.0778996 0.037485 0.0778996 0.00235763 0.154823 0.0745654 0.154823 0.0384615 0.190927 0.0394381 0.113027 0.0394381 0.0778996 0.0745654 0.0778996 0.0778996 0.151489 0.0778996 0.116361 0.113027 0.116361 0.0778996 0.0792807 0.113027 0.114408 0.0778996 0.114408 0.0778996 0.156204 0.114004 0.192308 0.0778996 0.228412 0.0792807 0.229793 0.115385 0.193689 0.151489 0.229793 0.151489 0.15287 0.116361 0.15287 0.116361 0.117742 0.114408 0.15287 0.0792807 0.15287 0.114408 0.117742 0.15287 0.156204 0.15287 0.228412 0.116766 0.192308 0.117742 0.114408 0.15287 0.0792807 0.15287 0.114408 0.15287 0.151489 0.117742 0.116361 0.15287 0.116361 0.114408 0.113027 0.0792807 0.0778996 0.114408 0.0778996 0.116361 0.113027 0.116361 0.0778996 0.151489 0.0778996 0.151489 0.154823 0.115385 0.190927 0.0792807 0.154823 0.154823 0.228412 0.154823 0.156204 0.190927 0.192308 0.18995 0.116361 0.154823 0.151489 0.154823 0.116361 0.154823 0.0792807 0.18995 0.114408 0.154823 0.114408 0.193284 0.117742 0.228412 0.15287 0.193284 0.15287 0.191331 0.117742 0.191331 0.15287 0.156204 0.15287 0.156204 0.229793 0.192308 0.193689 0.228412 0.229793 0.229793 0.0792807 0.229793 0.114408 0.194665 0.114408 0.229793 0.151489 0.194665 0.116361 0.229793 0.116361 0.229793 0.156204 0.229793 0.228412 0.193689 0.192308 0.156204 0.154823 0.228412 0.154823 0.192308 0.190927 0.156204 0.0778996 0.191331 0.0778996 0.191331 0.113027 0.193284 0.0778996 0.228412 0.0778996 0.193284 0.113027 0.231746 0.151489 0.231746 0.116361 0.266873 0.116361 0.231746 0.0792807 0.266873 0.114408 0.231746 0.114408 0.231746 0.156204 0.26785 0.192308 0.231746 0.228412 0.305335 0.229793 0.233127 0.229793 0.269231 0.193689 0.270207 0.117742 0.305335 0.15287 0.270207 0.15287 0.268254 0.15287 0.233127 0.15287 0.268254 0.117742 0.306716 0.0792807 0.306716 0.114408 0.271588 0.114408 0.306716 0.151489 0.271588 0.116361 0.306716 0.116361 0.306716 0.156204 0.306716 0.228412 0.270612 0.192308 0.233127 0.154823 0.305335 0.154823 0.269231 0.190927 0.233127 0.0778996 0.268254 0.0778996 0.268254 0.113027 0.270207 0.0778996 0.305335 0.0778996 0.270207 0.113027 + + + + + + + + + + + + + + + +

9 9 0 0 0 0 0 1 3 3 0 2 9 9 1 3 3 3 1 4 5 5 1 5 1 1 2 6 8 8 2 7 6 6 2 8 1 1 3 9 6 6 3 10 7 7 3 11 2 2 4 12 1 1 4 13 7 7 4 14 2 2 5 15 7 7 5 16 4 4 5 17 8 8 6 18 9 9 6 19 5 5 6 20 8 8 7 21 5 5 7 22 6 6 7 23 19 19 8 24 10 10 8 25 12 12 8 26 19 19 9 27 12 12 9 28 14 14 9 29 17 17 10 30 18 18 10 31 15 15 10 32 17 17 11 33 15 15 11 34 16 16 11 35 11 11 12 36 17 17 12 37 16 16 12 38 11 11 13 39 16 16 13 40 13 13 13 41 18 18 14 42 19 19 14 43 14 14 14 44 18 18 15 45 14 14 15 46 15 15 15 47 27 27 16 48 20 20 16 49 22 22 16 50 27 27 17 51 22 22 17 52 28 28 17 53 25 25 18 54 26 26 18 55 29 29 18 56 25 25 19 57 29 29 19 58 23 23 19 59 21 21 20 60 25 25 20 61 23 23 20 62 21 21 21 63 23 23 21 64 24 24 21 65 26 26 22 66 27 27 22 67 28 28 22 68 26 26 23 69 28 28 23 70 29 29 23 71 31 31 24 72 30 30 24 73 33 33 24 74 31 31 25 75 33 33 25 76 35 35 25 77 38 38 26 78 39 39 26 79 36 36 26 80 38 38 27 81 36 36 27 82 37 37 27 83 32 32 28 84 38 38 28 85 37 37 28 86 32 32 29 87 37 37 29 88 34 34 29 89 39 39 30 90 31 31 30 91 35 35 30 92 39 39 31 93 35 35 31 94 36 36 31 95 40 40 32 96 44 44 32 97 63 63 32 98 40 40 33 99 63 63 33 100 43 43 33 101 44 44 34 102 45 45 34 103 62 62 34 104 44 44 35 105 62 62 35 106 63 63 35 107 46 46 36 108 47 47 36 109 60 60 36 110 46 46 37 111 60 60 37 112 61 61 37 113 48 48 38 114 59 59 38 115 60 60 38 116 48 48 39 117 60 60 39 118 47 47 39 119 45 45 40 120 46 46 40 121 61 61 40 122 45 45 41 123 61 61 41 124 62 62 41 125 48 48 42 126 49 49 42 127 58 58 42 128 48 48 43 129 58 58 43 130 59 59 43 131 49 49 44 132 50 50 44 133 57 57 44 134 49 49 45 135 57 57 45 136 58 58 45 137 50 50 46 138 51 51 46 139 56 56 46 140 50 50 47 141 56 56 47 142 57 57 47 143 52 52 48 144 53 53 48 145 54 54 48 146 52 52 49 147 54 54 49 148 55 55 49 149 42 42 50 150 41 41 50 151 54 54 50 152 42 42 51 153 54 54 51 154 53 53 51 155 51 51 52 156 52 52 52 157 55 55 52 158 51 51 53 159 55 55 53 160 56 56 53 161 64 64 54 162 68 68 54 163 97 97 54 164 64 64 55 165 97 97 55 166 65 65 55 167 69 69 56 168 70 70 56 169 95 95 56 170 69 69 57 171 95 95 57 172 96 96 57 173 68 68 58 174 69 69 58 175 96 96 58 176 68 68 59 177 96 96 59 178 97 97 59 179 72 72 60 180 93 93 60 181 94 94 60 182 72 72 61 183 94 94 61 184 71 71 61 185 73 73 62 186 74 74 62 187 91 91 62 188 73 73 63 189 91 91 63 190 92 92 63 191 72 72 64 192 73 73 64 193 92 92 64 194 72 72 65 195 92 92 65 196 93 93 65 197 70 70 66 198 71 71 66 199 94 94 66 200 70 70 67 201 94 94 67 202 95 95 67 203 90 90 68 204 91 91 68 205 74 74 68 206 90 90 69 207 74 74 69 208 75 75 69 209 75 75 70 210 76 76 70 211 89 89 70 212 75 75 71 213 89 89 71 214 90 90 71 215 77 77 72 216 78 78 72 217 87 87 72 218 77 77 73 219 87 87 73 220 88 88 73 221 76 76 74 222 77 77 74 223 88 88 74 224 76 76 75 225 88 88 75 226 89 89 75 227 79 79 76 228 80 80 76 229 85 85 76 230 79 79 77 231 85 85 77 232 86 86 77 233 81 81 78 234 82 82 78 235 83 83 78 236 81 81 79 237 83 83 79 238 84 84 79 239 80 80 80 240 81 81 80 241 84 84 80 242 80 80 81 243 84 84 81 244 85 85 81 245 78 78 82 246 79 79 82 247 86 86 82 248 78 78 83 249 86 86 83 250 87 87 83 251 67 67 84 252 83 83 84 253 82 82 84 254 67 67 85 255 82 82 85 256 66 66 85 257 98 98 86 258 102 102 86 259 121 121 86 260 98 98 87 261 121 121 87 262 100 100 87 263 102 102 88 264 103 103 88 265 120 120 88 266 102 102 89 267 120 120 89 268 121 121 89 269 104 104 90 270 105 105 90 271 118 118 90 272 104 104 91 273 118 118 91 274 119 119 91 275 105 105 92 276 106 106 92 277 117 117 92 278 105 105 93 279 117 117 93 280 118 118 93 281 103 103 94 282 104 104 94 283 119 119 94 284 103 103 95 285 119 119 95 286 120 120 95 287 106 106 96 288 107 107 96 289 116 116 96 290 106 106 97 291 116 116 97 292 117 117 97 293 107 107 98 294 108 108 98 295 115 115 98 296 107 107 99 297 115 115 99 298 116 116 99 299 108 108 100 300 109 109 100 301 114 114 100 302 108 108 101 303 114 114 101 304 115 115 101 305 110 110 102 306 111 111 102 307 112 112 102 308 110 110 103 309 112 112 103 310 113 113 103 311 111 111 104 312 101 101 104 313 99 99 104 314 111 111 105 315 99 99 105 316 112 112 105 317 109 109 106 318 110 110 106 319 113 113 106 320 109 109 107 321 113 113 107 322 114 114 107 323 122 122 108 324 126 126 108 325 155 155 108 326 122 122 109 327 155 155 109 328 123 123 109 329 128 128 110 330 153 153 110 331 154 154 110 332 128 128 111 333 154 154 111 334 127 127 111 335 126 126 112 336 127 127 112 337 154 154 112 338 126 126 113 339 154 154 113 340 155 155 113 341 129 129 114 342 130 130 114 343 151 151 114 344 129 129 115 345 151 151 115 346 152 152 115 347 131 131 116 348 132 132 116 349 149 149 116 350 131 131 117 351 149 149 117 352 150 150 117 353 130 130 118 354 131 131 118 355 150 150 118 356 130 130 119 357 150 150 119 358 151 151 119 359 129 129 120 360 152 152 120 361 153 153 120 362 129 129 121 363 153 153 121 364 128 128 121 365 148 148 122 366 149 149 122 367 132 132 122 368 148 148 123 369 132 132 123 370 133 133 123 371 134 134 124 372 135 135 124 373 146 146 124 374 134 134 125 375 146 146 125 376 147 147 125 377 136 136 126 378 137 137 126 379 144 144 126 380 136 136 127 381 144 144 127 382 145 145 127 383 135 135 128 384 136 136 128 385 145 145 128 386 135 135 129 387 145 145 129 388 146 146 129 389 138 138 130 390 139 139 130 391 142 142 130 392 138 138 131 393 142 142 131 394 143 143 131 395 124 124 132 396 125 125 132 397 141 141 132 398 124 124 133 399 141 141 133 400 140 140 133 401 140 140 134 402 141 141 134 403 142 142 134 404 140 140 135 405 142 142 135 406 139 139 135 407 137 137 136 408 138 138 136 409 143 143 136 410 137 137 137 411 143 143 137 412 144 144 137 413 147 147 138 414 148 148 138 415 133 133 138 416 147 147 139 417 133 133 139 418 134 134 139 419 165 165 140 420 164 164 140 421 156 156 140 422 165 165 141 423 156 156 141 424 157 157 141 425 166 166 142 426 165 165 142 427 157 157 142 428 166 166 143 429 157 157 143 430 158 158 143 431 167 167 144 432 166 166 144 433 158 158 144 434 167 167 145 435 158 158 145 436 159 159 145 437 168 168 146 438 167 167 146 439 159 159 146 440 168 168 147 441 159 159 147 442 160 160 147 443 169 169 148 444 168 168 148 445 160 160 148 446 169 169 149 447 160 160 149 448 161 161 149 449 170 170 150 450 169 169 150 451 161 161 150 452 170 170 151 453 161 161 151 454 162 162 151 455 171 171 152 456 170 170 152 457 162 162 152 458 171 171 153 459 162 162 153 460 163 163 153 461 173 173 154 462 172 172 154 463 164 164 154 464 173 173 155 465 164 164 155 466 165 165 155 467 174 174 156 468 173 173 156 469 165 165 156 470 174 174 157 471 165 165 157 472 166 166 157 473 175 175 158 474 174 174 158 475 166 166 158 476 175 175 159 477 166 166 159 478 167 167 159 479 176 176 160 480 175 175 160 481 167 167 160 482 176 176 161 483 167 167 161 484 168 168 161 485 177 177 162 486 176 176 162 487 168 168 162 488 177 177 163 489 168 168 163 490 169 169 163 491 178 178 164 492 177 177 164 493 169 169 164 494 178 178 165 495 169 169 165 496 170 170 165 497 179 179 166 498 178 178 166 499 170 170 166 500 179 179 167 501 170 170 167 502 171 171 167 503 181 181 168 504 180 180 168 505 172 172 168 506 181 181 169 507 172 172 169 508 173 173 169 509 182 182 170 510 181 181 170 511 173 173 170 512 182 182 171 513 173 173 171 514 174 174 171 515 183 183 172 516 182 182 172 517 174 174 172 518 183 183 173 519 174 174 173 520 175 175 173 521 184 184 174 522 183 183 174 523 175 175 174 524 184 184 175 525 175 175 175 526 176 176 175 527 185 185 176 528 184 184 176 529 176 176 176 530 185 185 177 531 176 176 177 532 177 177 177 533 186 186 178 534 185 185 178 535 177 177 178 536 186 186 179 537 177 177 179 538 178 178 179 539 187 187 180 540 186 186 180 541 178 178 180 542 187 187 181 543 178 178 181 544 179 179 181 545 189 189 182 546 188 188 182 547 180 180 182 548 189 189 183 549 180 180 183 550 181 181 183 551 190 190 184 552 189 189 184 553 181 181 184 554 190 190 185 555 181 181 185 556 182 182 185 557 191 191 186 558 190 190 186 559 182 182 186 560 191 191 187 561 182 182 187 562 183 183 187 563 192 192 188 564 191 191 188 565 183 183 188 566 192 192 189 567 183 183 189 568 184 184 189 569 193 193 190 570 192 192 190 571 184 184 190 572 193 193 191 573 184 184 191 574 185 185 191 575 194 194 192 576 193 193 192 577 185 185 192 578 194 194 193 579 185 185 193 580 186 186 193 581 195 195 194 582 194 194 194 583 186 186 194 584 195 195 195 585 186 186 195 586 187 187 195 587 197 197 196 588 196 196 196 589 188 188 196 590 197 197 197 591 188 188 197 592 189 189 197 593 198 198 198 594 197 197 198 595 189 189 198 596 198 198 199 597 189 189 199 598 190 190 199 599 199 199 200 600 198 198 200 601 190 190 200 602 199 199 201 603 190 190 201 604 191 191 201 605 200 200 202 606 199 199 202 607 191 191 202 608 200 200 203 609 191 191 203 610 192 192 203 611 201 201 204 612 200 200 204 613 192 192 204 614 201 201 205 615 192 192 205 616 193 193 205 617 202 202 206 618 201 201 206 619 193 193 206 620 202 202 207 621 193 193 207 622 194 194 207 623 203 203 208 624 202 202 208 625 194 194 208 626 203 203 209 627 194 194 209 628 195 195 209 629 205 205 210 630 204 204 210 631 196 196 210 632 205 205 211 633 196 196 211 634 197 197 211 635 206 206 212 636 205 205 212 637 197 197 212 638 206 206 213 639 197 197 213 640 198 198 213 641 207 207 214 642 206 206 214 643 198 198 214 644 207 207 215 645 198 198 215 646 199 199 215 647 208 208 216 648 207 207 216 649 199 199 216 650 208 208 217 651 199 199 217 652 200 200 217 653 209 209 218 654 208 208 218 655 200 200 218 656 209 209 219 657 200 200 219 658 201 201 219 659 210 210 220 660 209 209 220 661 201 201 220 662 210 210 221 663 201 201 221 664 202 202 221 665 211 211 222 666 210 210 222 667 202 202 222 668 211 211 223 669 202 202 223 670 203 203 223 671 213 213 224 672 212 212 224 673 204 204 224 674 213 213 225 675 204 204 225 676 205 205 225 677 214 214 226 678 213 213 226 679 205 205 226 680 214 214 227 681 205 205 227 682 206 206 227 683 215 215 228 684 214 214 228 685 206 206 228 686 215 215 229 687 206 206 229 688 207 207 229 689 216 216 230 690 215 215 230 691 207 207 230 692 216 216 231 693 207 207 231 694 208 208 231 695 217 217 232 696 216 216 232 697 208 208 232 698 217 217 233 699 208 208 233 700 209 209 233 701 218 218 234 702 217 217 234 703 209 209 234 704 218 218 235 705 209 209 235 706 210 210 235 707 219 219 236 708 218 218 236 709 210 210 236 710 219 219 237 711 210 210 237 712 211 211 237 713 221 221 238 714 220 220 238 715 212 212 238 716 221 221 239 717 212 212 239 718 213 213 239 719 222 222 240 720 221 221 240 721 213 213 240 722 222 222 241 723 213 213 241 724 214 214 241 725 223 223 242 726 222 222 242 727 214 214 242 728 223 223 243 729 214 214 243 730 215 215 243 731 224 224 244 732 223 223 244 733 215 215 244 734 224 224 245 735 215 215 245 736 216 216 245 737 225 225 246 738 224 224 246 739 216 216 246 740 225 225 247 741 216 216 247 742 217 217 247 743 226 226 248 744 225 225 248 745 217 217 248 746 226 226 249 747 217 217 249 748 218 218 249 749 227 227 250 750 226 226 250 751 218 218 250 752 227 227 251 753 218 218 251 754 219 219 251 755 229 229 252 756 228 228 252 757 220 220 252 758 229 229 253 759 220 220 253 760 221 221 253 761 230 230 254 762 229 229 254 763 221 221 254 764 230 230 255 765 221 221 255 766 222 222 255 767 231 231 256 768 230 230 256 769 222 222 256 770 231 231 257 771 222 222 257 772 223 223 257 773 232 232 258 774 231 231 258 775 223 223 258 776 232 232 259 777 223 223 259 778 224 224 259 779 233 233 260 780 232 232 260 781 224 224 260 782 233 233 261 783 224 224 261 784 225 225 261 785 234 234 262 786 233 233 262 787 225 225 262 788 234 234 263 789 225 225 263 790 226 226 263 791 235 235 264 792 234 234 264 793 226 226 264 794 235 235 265 795 226 226 265 796 227 227 265 797 237 237 266 798 236 236 266 799 228 228 266 800 237 237 267 801 228 228 267 802 229 229 267 803 238 238 268 804 237 237 268 805 229 229 268 806 238 238 269 807 229 229 269 808 230 230 269 809 239 239 270 810 238 238 270 811 230 230 270 812 239 239 271 813 230 230 271 814 231 231 271 815 240 240 272 816 239 239 272 817 231 231 272 818 240 240 273 819 231 231 273 820 232 232 273 821 241 241 274 822 240 240 274 823 232 232 274 824 241 241 275 825 232 232 275 826 233 233 275 827 242 242 276 828 241 241 276 829 233 233 276 830 242 242 277 831 233 233 277 832 234 234 277 833 243 243 278 834 242 242 278 835 234 234 278 836 243 243 279 837 234 234 279 838 235 235 279 839 260 260 280 840 259 259 280 841 263 263 280 842 261 261 281 843 260 260 281 844 263 263 281 845 259 259 282 846 156 156 282 847 263 263 282 848 274 274 283 849 263 263 283 850 156 156 283 851 262 262 284 852 261 261 284 853 263 263 284 854 298 298 285 855 156 156 285 856 259 259 285 857 297 297 286 858 157 157 286 859 156 156 286 860 297 297 287 861 156 156 287 862 298 298 287 863 157 157 288 864 297 297 288 865 296 296 288 866 296 296 289 867 295 295 289 868 158 158 289 869 294 294 290 870 159 159 290 871 158 158 290 872 294 294 291 873 158 158 291 874 295 295 291 875 157 157 292 876 296 296 292 877 158 158 292 878 164 164 293 879 275 275 293 880 274 274 293 881 164 164 294 882 274 274 294 883 156 156 294 884 164 164 295 885 276 276 295 886 275 275 295 887 277 277 296 888 172 172 296 889 180 180 296 890 277 277 297 891 180 180 297 892 278 278 297 893 180 180 298 894 279 279 298 895 278 278 298 896 172 172 299 897 277 277 299 898 276 276 299 899 172 172 300 900 276 276 300 901 164 164 300 902 180 180 301 903 188 188 301 904 279 279 301 905 196 196 302 906 281 281 302 907 280 280 302 908 196 196 303 909 280 280 303 910 188 188 303 911 280 280 304 912 279 279 304 913 188 188 304 914 293 293 305 915 160 160 305 916 159 159 305 917 293 293 306 918 159 159 306 919 294 294 306 920 292 292 307 921 161 161 307 922 160 160 307 923 292 292 308 924 160 160 308 925 293 293 308 926 161 161 309 927 292 292 309 928 291 291 309 929 161 161 310 930 291 291 310 931 290 290 310 932 161 161 311 933 290 290 311 934 162 162 311 935 289 289 312 936 163 163 312 937 162 162 312 938 289 289 313 939 162 162 313 940 290 290 313 941 163 163 314 942 258 258 314 943 254 254 314 944 254 254 315 945 257 257 315 946 256 256 315 947 256 256 316 948 255 255 316 949 254 254 316 950 254 254 317 951 258 258 317 952 257 257 317 953 163 163 318 954 289 289 318 955 258 258 318 956 312 312 319 957 171 171 319 958 163 163 319 959 312 312 320 960 163 163 320 961 313 313 320 962 254 254 321 963 313 313 321 964 163 163 321 965 171 171 322 966 311 311 322 967 310 310 322 968 171 171 323 969 310 310 323 970 179 179 323 971 179 179 324 972 310 310 324 973 309 309 324 974 179 179 325 975 309 309 325 976 187 187 325 977 187 187 326 978 309 309 326 979 308 308 326 980 187 187 327 981 308 308 327 982 195 195 327 983 171 171 328 984 312 312 328 985 311 311 328 986 306 306 329 987 203 203 329 988 195 195 329 989 306 306 330 990 195 195 330 991 307 307 330 992 307 307 331 993 195 195 331 994 308 308 331 995 204 204 332 996 282 282 332 997 281 281 332 998 204 204 333 999 281 281 333 1000 196 196 333 1001 204 204 334 1002 283 283 334 1003 282 282 334 1004 284 284 335 1005 212 212 335 1006 220 220 335 1007 284 284 336 1008 220 220 336 1009 285 285 336 1010 220 220 337 1011 286 286 337 1012 285 285 337 1013 212 212 338 1014 284 284 338 1015 283 283 338 1016 212 212 339 1017 283 283 339 1018 204 204 339 1019 287 287 340 1020 228 228 340 1021 236 236 340 1022 287 287 341 1023 236 236 341 1024 288 288 341 1025 236 236 342 1026 249 249 342 1027 288 288 342 1028 286 286 343 1029 220 220 343 1030 228 228 343 1031 287 287 344 1032 286 286 344 1033 228 228 344 1034 251 251 345 1035 250 250 345 1036 249 249 345 1037 252 252 346 1038 251 251 346 1039 249 249 346 1040 253 253 347 1041 236 236 347 1042 264 264 347 1043 252 252 348 1044 249 249 348 1045 253 253 348 1046 264 264 349 1047 236 236 349 1048 237 237 349 1049 264 264 350 1050 237 237 350 1051 265 265 350 1052 238 238 351 1053 266 266 351 1054 265 265 351 1055 238 238 352 1056 265 265 352 1057 237 237 352 1058 239 239 353 1059 268 268 353 1060 267 267 353 1061 239 239 354 1062 267 267 354 1063 238 238 354 1064 238 238 355 1065 267 267 355 1066 266 266 355 1067 240 240 356 1068 269 269 356 1069 268 268 356 1070 240 240 357 1071 268 268 357 1072 239 239 357 1073 253 253 358 1074 249 249 358 1075 236 236 358 1076 203 203 359 1077 306 306 359 1078 305 305 359 1079 203 203 360 1080 305 305 360 1081 211 211 360 1082 211 211 361 1083 304 304 361 1084 303 303 361 1085 211 211 362 1086 303 303 362 1087 219 219 362 1088 235 235 363 1089 300 300 363 1090 299 299 363 1091 235 235 364 1092 299 299 364 1093 243 243 364 1094 227 227 365 1095 302 302 365 1096 301 301 365 1097 227 227 366 1098 301 301 366 1099 235 235 366 1100 219 219 367 1101 303 303 367 1102 302 302 367 1103 219 219 368 1104 302 302 368 1105 227 227 368 1106 211 211 369 1107 305 305 369 1108 304 304 369 1109 300 300 370 1110 235 235 370 1111 301 301 370 1112 242 242 371 1113 272 272 371 1114 271 271 371 1115 242 242 372 1116 271 271 372 1117 241 241 372 1118 269 269 373 1119 240 240 373 1120 241 241 373 1121 269 269 374 1122 241 241 374 1123 270 270 374 1124 241 241 375 1125 271 271 375 1126 270 270 375 1127 243 243 376 1128 273 273 376 1129 272 272 376 1130 243 243 377 1131 272 272 377 1132 242 242 377 1133 247 247 378 1134 246 246 378 1135 248 248 378 1136 243 243 379 1137 248 248 379 1138 244 244 379 1139 299 299 380 1140 248 248 380 1141 243 243 380 1142 244 244 381 1143 248 248 381 1144 245 245 381 1145 245 245 382 1146 248 248 382 1147 246 246 382 1148 273 273 383 1149 243 243 383 1150 244 244 383 1151 332 332 384 1152 333 333 384 1153 334 334 384 1154 334 334 385 1155 331 331 385 1156 332 332 385 1157 330 330 386 1158 331 331 386 1159 334 334 386 1160 330 330 387 1161 334 334 387 1162 396 396 387 1163 346 346 388 1164 470 470 388 1165 345 345 388 1166 334 334 389 1167 470 470 389 1168 396 396 389 1169 347 347 390 1170 471 471 390 1171 346 346 390 1172 470 470 391 1173 395 395 391 1174 396 396 391 1175 394 394 392 1176 395 395 392 1177 470 470 392 1178 471 471 393 1179 470 470 393 1180 346 346 393 1181 345 345 394 1182 470 470 394 1183 334 334 394 1184 368 368 395 1185 330 330 395 1186 396 396 395 1187 367 367 396 1188 368 368 396 1189 396 396 396 1190 367 367 397 1191 396 396 397 1192 397 397 397 1193 398 398 398 1194 365 365 398 1195 366 366 398 1196 402 402 399 1197 364 364 399 1198 365 365 399 1199 366 366 400 1200 367 367 400 1201 397 397 400 1202 366 366 401 1203 397 397 401 1204 398 398 401 1205 401 401 402 1206 399 399 402 1207 467 467 402 1208 401 401 403 1209 467 467 403 1210 400 400 403 1211 402 402 404 1212 398 398 404 1213 399 399 404 1214 402 402 405 1215 399 399 405 1216 401 401 405 1217 403 403 406 1218 364 364 406 1219 402 402 406 1220 365 365 407 1221 398 398 407 1222 402 402 407 1223 393 393 408 1224 394 394 408 1225 471 471 408 1226 471 471 409 1227 347 347 409 1228 348 348 409 1229 348 348 410 1230 349 349 410 1231 472 472 410 1232 348 348 411 1233 472 472 411 1234 471 471 411 1235 471 471 412 1236 472 472 412 1237 417 417 412 1238 471 471 413 1239 417 417 413 1240 418 418 413 1241 419 419 414 1242 471 471 414 1243 418 418 414 1244 419 419 415 1245 393 393 415 1246 471 471 415 1247 473 473 416 1248 472 472 416 1249 349 349 416 1250 473 473 417 1251 349 349 417 1252 350 350 417 1253 351 351 418 1254 473 473 418 1255 350 350 418 1256 416 416 419 1257 417 417 419 1258 472 472 419 1259 416 416 420 1260 472 472 420 1261 473 473 420 1262 415 415 421 1263 416 416 421 1264 473 473 421 1265 432 432 422 1266 473 473 422 1267 474 474 422 1268 468 468 423 1269 392 392 423 1270 393 393 423 1271 399 399 424 1272 392 392 424 1273 467 467 424 1274 420 420 425 1275 468 468 425 1276 419 419 425 1277 468 468 426 1278 393 393 426 1279 419 419 426 1280 415 415 427 1281 473 473 427 1282 433 433 427 1283 466 466 428 1284 415 415 428 1285 433 433 428 1286 415 415 429 1287 466 466 429 1288 414 414 429 1289 473 473 430 1290 432 432 430 1291 433 433 430 1292 474 474 431 1293 473 473 431 1294 351 351 431 1295 474 474 432 1296 351 351 432 1297 314 314 432 1298 471 471 433 1299 394 394 433 1300 470 470 433 1301 404 404 434 1302 362 362 434 1303 363 363 434 1304 364 364 435 1305 403 403 435 1306 363 363 435 1307 362 362 436 1308 388 388 436 1309 361 361 436 1310 360 360 437 1311 361 361 437 1312 388 388 437 1313 360 360 438 1314 388 388 438 1315 389 389 438 1316 363 363 439 1317 403 403 439 1318 404 404 439 1319 388 388 440 1320 404 404 440 1321 405 405 440 1322 388 388 441 1323 405 405 441 1324 387 387 441 1325 387 387 442 1326 405 405 442 1327 406 406 442 1328 387 387 443 1329 406 406 443 1330 452 452 443 1331 362 362 444 1332 404 404 444 1333 388 388 444 1334 359 359 445 1335 360 360 445 1336 389 389 445 1337 359 359 446 1338 389 389 446 1339 390 390 446 1340 329 329 447 1341 325 325 447 1342 328 328 447 1343 326 326 448 1344 327 327 448 1345 325 325 448 1346 327 327 449 1347 328 328 449 1348 325 325 449 1349 390 390 450 1350 329 329 450 1351 359 359 450 1352 391 391 451 1353 384 384 451 1354 475 475 451 1355 325 325 452 1356 390 390 452 1357 475 475 452 1358 475 475 453 1359 383 383 453 1360 325 325 453 1361 382 382 454 1362 383 383 454 1363 475 475 454 1364 384 384 455 1365 476 476 455 1366 475 475 455 1367 329 329 456 1368 390 390 456 1369 325 325 456 1370 391 391 457 1371 475 475 457 1372 390 390 457 1373 387 387 458 1374 452 452 458 1375 386 386 458 1376 385 385 459 1377 476 476 459 1378 384 384 459 1379 386 386 460 1380 453 453 460 1381 385 385 460 1382 411 411 461 1383 385 385 461 1384 453 453 461 1385 411 411 462 1386 453 453 462 1387 410 410 462 1388 408 408 463 1389 409 409 463 1390 459 459 463 1391 385 385 464 1392 411 411 464 1393 476 476 464 1394 477 477 465 1395 408 408 465 1396 425 425 465 1397 411 411 466 1398 412 412 466 1399 476 476 466 1400 478 478 467 1401 476 476 467 1402 412 412 467 1403 478 478 468 1404 412 412 468 1405 413 413 468 1406 379 379 469 1407 380 380 469 1408 476 476 469 1409 379 379 470 1410 476 476 470 1411 478 478 470 1412 476 476 471 1413 380 380 471 1414 381 381 471 1415 379 379 472 1416 478 478 472 1417 378 378 472 1418 381 381 473 1419 382 382 473 1420 476 476 473 1421 477 477 474 1422 478 478 474 1423 413 413 474 1424 477 477 475 1425 413 413 475 1426 407 407 475 1427 408 408 476 1428 477 477 476 1429 407 407 476 1430 378 378 477 1431 478 478 477 1432 477 477 477 1433 477 477 478 1434 377 377 478 1435 378 378 478 1436 376 376 479 1437 377 377 479 1438 477 477 479 1439 376 376 480 1440 477 477 480 1441 479 479 480 1442 425 425 481 1443 408 408 481 1444 459 459 481 1445 425 425 482 1446 459 459 482 1447 424 424 482 1448 476 476 483 1449 382 382 483 1450 475 475 483 1451 433 433 484 1452 434 434 484 1453 466 466 484 1454 480 480 485 1455 474 474 485 1456 314 314 485 1457 480 480 486 1458 314 314 486 1459 352 352 486 1460 474 474 487 1461 480 480 487 1462 431 431 487 1463 474 474 488 1464 431 431 488 1465 432 432 488 1466 430 430 489 1467 431 431 489 1468 480 480 489 1469 480 480 490 1470 352 352 490 1471 353 353 490 1472 481 481 491 1473 353 353 491 1474 354 354 491 1475 354 354 492 1476 355 355 492 1477 482 482 492 1478 354 354 493 1479 482 482 493 1480 481 481 493 1481 356 356 494 1482 482 482 494 1483 355 355 494 1484 356 356 495 1485 483 483 495 1486 482 482 495 1487 481 481 496 1488 430 430 496 1489 480 480 496 1490 480 480 497 1491 353 353 497 1492 481 481 497 1493 482 482 498 1494 449 449 498 1495 481 481 498 1496 450 450 499 1497 469 469 499 1498 429 429 499 1499 469 469 500 1500 428 428 500 1501 429 429 500 1502 429 429 501 1503 430 430 501 1504 481 481 501 1505 482 482 502 1506 448 448 502 1507 449 449 502 1508 450 450 503 1509 481 481 503 1510 449 449 503 1511 481 481 504 1512 450 450 504 1513 429 429 504 1514 465 465 505 1515 443 443 505 1516 444 444 505 1517 469 469 506 1518 450 450 506 1519 451 451 506 1520 448 448 507 1521 482 482 507 1522 447 447 507 1523 357 357 508 1524 358 358 508 1525 484 484 508 1526 357 357 509 1527 484 484 509 1528 483 483 509 1529 483 483 510 1530 446 446 510 1531 447 447 510 1532 447 447 511 1533 482 482 511 1534 483 483 511 1535 483 483 512 1536 484 484 512 1537 446 446 512 1538 484 484 513 1539 358 358 513 1540 320 320 513 1541 357 357 514 1542 483 483 514 1543 356 356 514 1544 322 322 515 1545 320 320 515 1546 321 321 515 1547 323 323 516 1548 320 320 516 1549 322 322 516 1550 324 324 517 1551 335 335 517 1552 484 484 517 1553 323 323 518 1554 324 324 518 1555 320 320 518 1556 320 320 519 1557 324 324 519 1558 484 484 519 1559 335 335 520 1560 336 336 520 1561 484 484 520 1562 446 446 521 1563 484 484 521 1564 462 462 521 1565 462 462 522 1566 484 484 522 1567 461 461 522 1568 446 446 523 1569 462 462 523 1570 445 445 523 1571 464 464 524 1572 461 461 524 1573 337 337 524 1574 336 336 525 1575 337 337 525 1576 461 461 525 1577 338 338 526 1578 464 464 526 1579 337 337 526 1580 339 339 527 1581 463 463 527 1582 338 338 527 1583 464 464 528 1584 338 338 528 1585 463 463 528 1586 465 465 529 1587 463 463 529 1588 454 454 529 1589 465 465 530 1590 454 454 530 1591 455 455 530 1592 461 461 531 1593 484 484 531 1594 336 336 531 1595 443 443 532 1596 465 465 532 1597 455 455 532 1598 339 339 533 1599 454 454 533 1600 463 463 533 1601 426 426 534 1602 477 477 534 1603 425 425 534 1604 479 479 535 1605 426 426 535 1606 427 427 535 1607 439 439 536 1608 460 460 536 1609 438 438 536 1610 485 485 537 1611 421 421 537 1612 422 422 537 1613 460 460 538 1614 439 439 538 1615 422 422 538 1616 439 439 539 1617 485 485 539 1618 422 422 539 1619 423 423 540 1620 460 460 540 1621 422 422 540 1622 486 486 541 1623 427 427 541 1624 421 421 541 1625 375 375 542 1626 376 376 542 1627 479 479 542 1628 375 375 543 1629 479 479 543 1630 486 486 543 1631 375 375 544 1632 486 486 544 1633 374 374 544 1634 486 486 545 1635 421 421 545 1636 485 485 545 1637 373 373 546 1638 374 374 546 1639 485 485 546 1640 485 485 547 1641 374 374 547 1642 486 486 547 1643 486 486 548 1644 479 479 548 1645 427 427 548 1646 487 487 549 1647 440 440 549 1648 441 441 549 1649 441 441 550 1650 435 435 550 1651 488 488 550 1652 441 441 551 1653 488 488 551 1654 487 487 551 1655 485 485 552 1656 487 487 552 1657 372 372 552 1658 485 485 553 1659 372 372 553 1660 373 373 553 1661 487 487 554 1662 371 371 554 1663 372 372 554 1664 487 487 555 1665 485 485 555 1666 440 440 555 1667 439 439 556 1668 440 440 556 1669 485 485 556 1670 477 477 557 1671 426 426 557 1672 479 479 557 1673 436 436 558 1674 437 437 558 1675 458 458 558 1676 458 458 559 1677 489 489 559 1678 436 436 559 1679 457 457 560 1680 454 454 560 1681 340 340 560 1682 457 457 561 1683 340 340 561 1684 341 341 561 1685 341 341 562 1686 342 342 562 1687 456 456 562 1688 341 341 563 1689 456 456 563 1690 457 457 563 1691 343 343 564 1692 456 456 564 1693 342 342 564 1694 456 456 565 1695 489 489 565 1696 458 458 565 1697 455 455 566 1698 442 442 566 1699 443 443 566 1700 343 343 567 1701 489 489 567 1702 456 456 567 1703 371 371 568 1704 488 488 568 1705 370 370 568 1706 488 488 569 1707 435 435 569 1708 436 436 569 1709 369 369 570 1710 370 370 570 1711 488 488 570 1712 369 369 571 1713 488 488 571 1714 489 489 571 1715 319 319 572 1716 369 369 572 1717 489 489 572 1718 436 436 573 1719 489 489 573 1720 488 488 573 1721 488 488 574 1722 371 371 574 1723 487 487 574 1724 315 315 575 1725 319 319 575 1726 489 489 575 1727 316 316 576 1728 319 319 576 1729 315 315 576 1730 318 318 577 1731 319 319 577 1732 317 317 577 1733 316 316 578 1734 317 317 578 1735 319 319 578 1736 344 344 579 1737 315 315 579 1738 489 489 579 1739 489 489 580 1740 343 343 580 1741 344 344 580 1742 339 339 581 1743 340 340 581 1744 454 454 581 1745 493 493 582 1746 491 491 582 1747 490 490 582 1748 493 493 583 1749 490 490 583 1750 492 492 583 1751 497 497 584 1752 495 495 584 1753 494 494 584 1754 497 497 585 1755 494 494 585 1756 496 496 585 1757 501 501 586 1758 499 499 586 1759 498 498 586 1760 501 501 587 1761 498 498 587 1762 500 500 587 1763 505 505 588 1764 503 503 588 1765 502 502 588 1766 505 505 589 1767 502 502 589 1768 504 504 589 1769 509 509 590 1770 507 507 590 1771 506 506 590 1772 509 509 591 1773 506 506 591 1774 508 508 591 1775 513 513 592 1776 511 511 592 1777 510 510 592 1778 513 513 593 1779 510 510 593 1780 512 512 593 1781 517 517 594 1782 515 515 594 1783 514 514 594 1784 517 517 595 1785 514 514 595 1786 516 516 595 1787 521 521 596 1788 519 519 596 1789 518 518 596 1790 521 521 597 1791 518 518 597 1792 520 520 597 1793 525 525 598 1794 523 523 598 1795 522 522 598 1796 525 525 599 1797 522 522 599 1798 524 524 599 1799 533 533 600 1800 529 529 600 1801 530 530 600 1802 530 530 601 1803 529 529 601 1804 526 526 601 1805 532 532 602 1806 530 530 602 1807 531 531 602 1808 533 533 603 1809 532 532 603 1810 527 527 603 1811 533 533 604 1812 528 528 604 1813 529 529 604 1814 532 532 605 1815 533 533 605 1816 530 530 605 1817 541 541 606 1818 537 537 606 1819 538 538 606 1820 538 538 607 1821 537 537 607 1822 534 534 607 1823 540 540 608 1824 538 538 608 1825 539 539 608 1826 541 541 609 1827 540 540 609 1828 535 535 609 1829 541 541 610 1830 536 536 610 1831 537 537 610 1832 540 540 611 1833 541 541 611 1834 538 538 611 1835 546 546 612 1836 548 548 612 1837 549 549 612 1838 549 549 613 1839 548 548 613 1840 542 542 613 1841 545 545 614 1842 549 549 614 1843 544 544 614 1844 546 546 615 1845 545 545 615 1846 543 543 615 1847 546 546 616 1848 547 547 616 1849 548 548 616 1850 545 545 617 1851 546 546 617 1852 549 549 617 1853 553 553 618 1854 554 554 618 1855 555 555 618 1856 553 553 619 1857 552 552 619 1858 550 550 619 1859 557 557 620 1860 553 553 620 1861 555 555 620 1862 553 553 621 1863 557 557 621 1864 552 552 621 1865 557 557 622 1866 551 551 622 1867 552 552 622 1868 556 556 623 1869 557 557 623 1870 555 555 623 1871 563 563 624 1872 561 561 624 1873 562 562 624 1874 562 562 625 1875 561 561 625 1876 559 559 625 1877 563 563 626 1878 562 562 626 1879 558 558 626 1880 565 565 627 1881 563 563 627 1882 564 564 627 1883 565 565 628 1884 560 560 628 1885 561 561 628 1886 563 563 629 1887 565 565 629 1888 561 561 629 1889 573 573 630 1890 566 566 630 1891 568 568 630 1892 573 573 631 1893 571 571 631 1894 572 572 631 1895 571 571 632 1896 573 573 632 1897 568 568 632 1898 568 568 633 1899 570 570 633 1900 571 571 633 1901 570 570 634 1902 567 567 634 1903 571 571 634 1904 569 569 635 1905 570 570 635 1906 568 568 635 1907 579 579 636 1908 574 574 636 1909 580 580 636 1910 579 579 637 1911 578 578 637 1912 575 575 637 1913 581 581 638 1914 579 579 638 1915 580 580 638 1916 579 579 639 1917 581 581 639 1918 578 578 639 1919 581 581 640 1920 577 577 640 1921 578 578 640 1922 576 576 641 1923 581 581 641 1924 580 580 641 1925 587 587 642 1926 585 585 642 1927 586 586 642 1928 586 586 643 1929 585 585 643 1930 583 583 643 1931 587 587 644 1932 586 586 644 1933 582 582 644 1934 589 589 645 1935 587 587 645 1936 588 588 645 1937 589 589 646 1938 584 584 646 1939 585 585 646 1940 587 587 647 1941 589 589 647 1942 585 585 647 1943 594 594 648 1944 597 597 648 1945 592 592 648 1946 592 592 649 1947 597 597 649 1948 591 591 649 1949 594 594 650 1950 592 592 650 1951 593 593 650 1952 595 595 651 1953 594 594 651 1954 590 590 651 1955 595 595 652 1956 596 596 652 1957 597 597 652 1958 594 594 653 1959 595 595 653 1960 597 597 653 1961 601 601 654 1962 598 598 654 1963 602 602 654 1964 601 601 655 1965 605 605 655 1966 600 600 655 1967 605 605 656 1968 601 601 656 1969 602 602 656 1970 602 602 657 1971 604 604 657 1972 605 605 657 1973 604 604 658 1974 599 599 658 1975 605 605 658 1976 603 603 659 1977 604 604 659 1978 602 602 659 1979 612 612 660 1980 613 613 660 1981 609 609 660 1982 609 609 661 1983 613 613 661 1984 606 606 661 1985 611 611 662 1986 609 609 662 1987 610 610 662 1988 612 612 663 1989 611 611 663 1990 607 607 663 1991 612 612 664 1992 608 608 664 1993 613 613 664 1994 611 611 665 1995 612 612 665 1996 609 609 665 1997 617 617 666 1998 614 614 666 1999 618 618 666 2000 617 617 667 2001 621 621 667 2002 615 615 667 2003 621 621 668 2004 617 617 668 2005 618 618 668 2006 618 618 669 2007 619 619 669 2008 621 621 669 2009 619 619 670 2010 620 620 670 2011 621 621 670 2012 616 616 671 2013 619 619 671 2014 618 618 671 2015 625 625 672 2016 622 622 672 2017 626 626 672 2018 625 625 673 2019 629 629 673 2020 624 624 673 2021 629 629 674 2022 625 625 674 2023 626 626 674 2024 626 626 675 2025 628 628 675 2026 629 629 675 2027 628 628 676 2028 623 623 676 2029 629 629 676 2030 627 627 677 2031 628 628 677 2032 626 626 677 2033 633 633 678 2034 634 634 678 2035 635 635 678 2036 633 633 679 2037 637 637 679 2038 630 630 679 2039 636 636 680 2040 633 633 680 2041 635 635 680 2042 636 636 681 2043 635 635 681 2044 631 631 681 2045 633 633 682 2046 636 636 682 2047 637 637 682 2048 636 636 683 2049 632 632 683 2050 637 637 683 2051 641 641 684 2052 638 638 684 2053 642 642 684 2054 641 641 685 2055 645 645 685 2056 639 639 685 2057 645 645 686 2058 641 641 686 2059 642 642 686 2060 642 642 687 2061 643 643 687 2062 645 645 687 2063 643 643 688 2064 644 644 688 2065 645 645 688 2066 640 640 689 2067 643 643 689 2068 642 642 689 2069 650 650 690 2070 653 653 690 2071 649 649 690 2072 649 649 691 2073 653 653 691 2074 648 648 691 2075 650 650 692 2076 649 649 692 2077 646 646 692 2078 651 651 693 2079 650 650 693 2080 647 647 693 2081 651 651 694 2082 652 652 694 2083 653 653 694 2084 650 650 695 2085 651 651 695 2086 653 653 695 2087 659 659 696 2088 661 661 696 2089 657 657 696 2090 657 657 697 2091 661 661 697 2092 654 654 697 2093 659 659 698 2094 657 657 698 2095 658 658 698 2096 660 660 699 2097 659 659 699 2098 655 655 699 2099 660 660 700 2100 656 656 700 2101 661 661 700 2102 659 659 701 2103 660 660 701 2104 661 661 701 2105 666 666 702 2106 662 662 702 2107 667 667 702 2108 666 666 703 2109 669 669 703 2110 663 663 703 2111 668 668 704 2112 666 666 704 2113 667 667 704 2114 666 666 705 2115 668 668 705 2116 669 669 705 2117 668 668 706 2118 665 665 706 2119 669 669 706 2120 664 664 707 2121 668 668 707 2122 667 667 707 2123 675 675 708 2124 670 670 708 2125 676 676 708 2126 675 675 709 2127 674 674 709 2128 671 671 709 2129 674 674 710 2130 675 675 710 2131 676 676 710 2132 674 674 711 2133 676 676 711 2134 677 677 711 2135 674 674 712 2136 677 677 712 2137 673 673 712 2138 672 672 713 2139 677 677 713 2140 676 676 713 2141 681 681 714 2142 678 678 714 2143 682 682 714 2144 681 681 715 2145 685 685 715 2146 679 679 715 2147 684 684 716 2148 681 681 716 2149 682 682 716 2150 681 681 717 2151 684 684 717 2152 685 685 717 2153 684 684 718 2154 680 680 718 2155 685 685 718 2156 683 683 719 2157 684 684 719 2158 682 682 719 2159

+
+
+
+
+ + + + + + + + + + + + + + + + + + +
diff --git a/dxl_armed_turtlebot/worlds/model/checkerboard/checkerboard_20mm_7x4.urdf b/dxl_armed_turtlebot/worlds/model/checkerboard/checkerboard_20mm_7x4.urdf new file mode 100644 index 00000000..517ad828 --- /dev/null +++ b/dxl_armed_turtlebot/worlds/model/checkerboard/checkerboard_20mm_7x4.urdf @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/dxl_armed_turtlebot/worlds/model/checkerboard/checkerboard_20mm_7x4_color.png b/dxl_armed_turtlebot/worlds/model/checkerboard/checkerboard_20mm_7x4_color.png new file mode 100644 index 00000000..593595d8 Binary files /dev/null and b/dxl_armed_turtlebot/worlds/model/checkerboard/checkerboard_20mm_7x4_color.png differ diff --git a/dxl_armed_turtlebot/worlds/model/checkerboard/model.config b/dxl_armed_turtlebot/worlds/model/checkerboard/model.config new file mode 100644 index 00000000..577dc281 --- /dev/null +++ b/dxl_armed_turtlebot/worlds/model/checkerboard/model.config @@ -0,0 +1,11 @@ + + + checkerboard + 1.0 + model.sdf + + Moju Zhao + chou@jsk.imi.i.u-tokyo.ac.jp + + dxl_armed_turtlebot + diff --git a/dxl_armed_turtlebot/worlds/model/checkerboard/model.sdf b/dxl_armed_turtlebot/worlds/model/checkerboard/model.sdf new file mode 100644 index 00000000..9ce6a318 --- /dev/null +++ b/dxl_armed_turtlebot/worlds/model/checkerboard/model.sdf @@ -0,0 +1,68 @@ + + + + 1 + + 0 0 0 0 -0 0 + + + + model://checkerboard/checkerboard_20mm_7x4.dae + 1 1 1 + + + + + + 100 + 50 + + + + 0 + 1e+06 + + + 0 + 1 + + 0 + 0.2 + 1e+13 + 1 + 0.01 + 0 + + + 1 + -0.01 + 0 + 0.2 + 1e+13 + 1 + + + + 10 + 0 + + + 1 + 0 + + + model://checkerboard/checkerboard_20mm_7x4.dae + 1 1 1 + + + + + 0 + 0 + + 0 + 0 + 0 + + + diff --git a/dynamixel_7dof_arm/config/dynamixel_joint_controllers.yaml b/dynamixel_7dof_arm/config/dynamixel_joint_controllers.yaml index 001c945d..e5346cd1 100644 --- a/dynamixel_7dof_arm/config/dynamixel_joint_controllers.yaml +++ b/dynamixel_7dof_arm/config/dynamixel_joint_controllers.yaml @@ -76,12 +76,12 @@ arm_j6_controller: min: 0 max: 1023 -arm_j7_controller: +gripper_joint_controller: controller: package: dynamixel_controllers module: joint_position_controller type: JointPositionController - joint_name: arm_joint7 + joint_name: gripper_joint joint_speed: 2.0 motor: id: 7 diff --git a/dynamixel_7dof_arm/euslisp/dxl-7dof-arm-interface-common.l b/dynamixel_7dof_arm/euslisp/dxl-7dof-arm-interface-common.l index c19cd356..dc996a20 100644 --- a/dynamixel_7dof_arm/euslisp/dxl-7dof-arm-interface-common.l +++ b/dynamixel_7dof_arm/euslisp/dxl-7dof-arm-interface-common.l @@ -14,13 +14,24 @@ (:initialize-arm-robot-ros () ;; subscriber - (dotimes (i (length (send robot :angle-vector))) + + (dotimes (i (+ (length (send robot :angle-vector)) 1)) (ros::subscribe - (format nil "/arm_j~d_controller/state" (1+ i)) + (if (eq i 6) + (format nil "/gripper_joint_controller/state") + (format nil "/arm_j~d_controller/state" (1+ i))) dynamixel_msgs::JointState #'send self :dynamixel-motor-states-callback :groupname groupname)) - (unless (send self :simulation-modep) - ;; services + ;; for gazebo + (when (ros::get-param "use_sim_time" nil) + (ros::subscribe + (format nil "/joint_states") + sensor_msgs::JointState + #'send self :joint-states-callback :groupname groupname) + ) + + (unless (or (send self :simulation-modep) (ros::get-param "use_sim_time" nil)) + ;; services for arm joints (dotimes (i (length (send robot :angle-vector))) (ros::wait-for-service (format nil "/arm_j~d_controller/set_compliance_slope" (1+ i))) @@ -29,11 +40,17 @@ (ros::wait-for-service (format nil "/arm_j~d_controller/set_torque_limit" (1+ i))) ) + ;; services for gripper joint + (ros::wait-for-service + (format nil "/gripper_joint_controller/set_compliance_slope")) + (ros::wait-for-service + (format nil "/gripper_joint_controller/torque_enable")) + (ros::wait-for-service + (format nil "/gripper_joint_controller/set_torque_limit")) ) - ;; define actions + ;; arm controller action (dolist (l (list (cons :fullbody-controller "fullbody_controller/follow_joint_trajectory") - (cons :gripper-controller "gripper_controller/follow_joint_trajectory") )) (let ((type (car l)) (name (cdr l)) @@ -48,7 +65,18 @@ control_msgs::followjointtrajectoryaction :groupname groupname)))) )) + + ;; gripper controller action + (setq gripper-action (instance ros::simple-action-client :init + "/gripper_controller/follow_joint_trajectory" + control_msgs::FollowJointTrajectoryAction + :groupname groupname)) + ;; wait for gripper-action server + (unless (and joint-action-enable (send gripper-action :wait-for-server 3)) + (setq joint-action-enable nil) + (ros::ros-warn "~A is not respond, robot-interface is disabled" gripper-action)) ) + ;; TODO ;; This method is tempolary code. ;; dynamixel_controller_manager should publish /dxl_7dof_arm/joint_states @@ -58,11 +86,11 @@ (dolist (key '(:position :velocity :effort :name)) ;; neglect /joint_states from turtlebot (unless (and (cdr (assoc key robot-state)) - (= (length (send robot :angle-vector)) (length (cdr (assoc key robot-state))))) + (= (1+ (length (send robot :angle-vector))) (length (cdr (assoc key robot-state))))) (send self :set-robot-state1 key (if (eq key :name) - (make-list (length (send robot :angle-vector))) - (instantiate float-vector (length (send robot :angle-vector))))))) + (make-list (1+ (length (send robot :angle-vector)))) + (instantiate float-vector (1+ (length (send robot :angle-vector)))))))) ;; update values (dolist (key '(:position :velocity :effort :name)) (setf (elt (cdr (assoc key robot-state)) (1- (elt (send msg :motor_ids) 0))) @@ -74,6 +102,38 @@ ) ) ) + ;; TODO + ;; Because turtlebot kobuki also publish the wheel states as "joint_states", it conflicts with arm joint states. + ;; We have to separate these two topics in the future. + ;; Temporary, we check the number of the joint states and distinguish the origin. + ;; However, the arm joint states may not be updated in the eus model on time, if we only oprate "spinOnce" for one time. + (:joint-states-callback + (msg) + ;; maybe from wheel (TODO: remove joint_state for kobuki_gazebo_plugin) + (unless (eq (length (send msg :name)) (+ (length (send robot :angle-vector)) 1)) + (return-from :joint-states-callback nil)) + ;; for initialize + (dolist (key '(:position :velocity :effort :name)) + (unless (and (cdr (assoc key robot-state)) + (= (length (send msg :name)) (length (cdr (assoc key robot-state))))) + (send self :set-robot-state1 key + (if (eq key :name) + (make-list (length (send msg :name))) + (instantiate float-vector (length (send msg :name))))))) + ;; update values + (dotimes (i (length (send msg :name))) + (dolist (key '(:position :velocity :effort :name)) + (setf (elt (cdr (assoc key robot-state)) i) + (case key + (:position (elt (send msg :position) i)) + (:name (elt (send msg :name) i)) + (:velocity (elt (send msg :velocity) i)) + (:effort (elt (send msg :effort) i))) + ) + ) + ) + ) + (:fullbody-controller () (list @@ -82,14 +142,11 @@ (cons :controller-state "fullbody_controller/state") (cons :action-type control_msgs::FollowJointTrajectoryAction) (cons :joint-names (mapcar #'(lambda (n) (if (symbolp n) (symbol-name n) n)) - (send-all - (remove-if #'(lambda (x) - (member x (send robot :gripper :arm :joint-list))) - (send robot :joint-list)) - :name) + (send-all (send robot :joint-list) :name) ))) ) ) + #| (:gripper-controller () (list @@ -102,6 +159,8 @@ ))) ) ) + |# + (:default-controller () (send self :fullbody-controller) @@ -113,9 +172,11 @@ ;; http://www.besttechnology.co.jp/modules/knowledge/?Dynamixel%E3%82%B3%E3%83%B3%E3%83%88%E3%83%AD%E3%83%BC%E3%83%AB%E3%83%86%E3%83%BC%E3%83%96%E3%83%AB%28DX%2CRX%2CAX%E3%82%B7%E3%83%AA%E3%83%BC%E3%82%BA%E7%94%A8%29#m041ac16 (:set-compliance-slope ;; for one joint (id slope) - "Set compliance slope for one joint. id should be 1-7. slope is 32 by default." + "Set compliance slope for one joint. id should be 1-6. slope is 32 by default." (ros::service-call - (format nil "/arm_j~d_controller/set_compliance_slope" id) + (if (eq id 7) + (format nil "/gripper_joint_controller/set_compliance_slope") + (format nil "/arm_j~d_controller/set_compliance_slope" id)) (instance dynamixel_controllers::setcomplianceslopeRequest :init :slope (round slope))) ) @@ -129,14 +190,18 @@ (id torque-limit) "Set torque limit for one joint. id should be 1-7. torque-limit should be within [0, 1]." (ros::service-call - (format nil "/arm_j~d_controller/set_torque_limit" id) + (if (eq id 7) + (format nil "/gripper_joint_controller/set_torque_limit" id) + (format nil "/arm_j~d_controller/set_torque_limit" id)) (instance dynamixel_controllers::SetTorqueLimitRequest :init :torque_limit torque-limit))) (:torque-enable (id torque-enable) "Configure joint torque mode for one joint. id sohuld be 1-7. If torque-enable is t, move to torque control mode, otherwise, move to joint positoin mode." (ros::service-call - (format nil "/arm_j~d_controller/torque_enable" id) + (if (eq id 7) + (format nil "/gripper_joint_controller/torque_enable" id) + (format nil "/arm_j~d_controller/torque_enable" id)) (instance dynamixel_controllers::TorqueEnableRequest :init :torque_enable torque-enable))) @@ -152,12 +217,12 @@ (:servo-on-all () "Servo On for all joints." - (dotimes (i (length (send robot :angle-vector))) + (dotimes (i (+ (length (send robot :angle-vector)) 1)) (send self :servo-on-off (1+ i) t))) (:servo-off-all () "Servo Off for all joints." - (dotimes (i (length (send robot :angle-vector))) + (dotimes (i (+ (length (send robot :angle-vector)) 1)) (send self :servo-on-off (1+ i) nil))) (:servo-on-off (id on/off) ;; id = 1-7, t -> "On", nil -> "Off" @@ -166,32 +231,67 @@ (if on/off ;; just for servo off->on (send self :set-torque-limit id 1.0))) + (:move-gripper + (pos &key (tm 1000) (wait t)) + (unless joint-action-enable + (send (send robot :gripper_joint) :joint-angle pos ) + (send self :publish-joint-state) + (if viewer (send self :draw-objects)) + (return-from :move-gripper t)) + ;; for real robot + (let* ((goal (send gripper-action :make-goal-instance)) + (goal-points nil) + (joint-names (list (send (send robot :gripper_joint) :name)))) + (send goal :header :seq 1) + (send goal :header :stamp (ros::time-now)) + + (send goal :goal :trajectory :joint_names joint-names) + (send goal :goal :trajectory :header :stamp (ros::time-now)) + + (push (instance trajectory_msgs::JointTrajectoryPoint + :init + :positions (float-vector (deg2rad pos)) + :velocities (float-vector 0) + :time_from_start (ros::time (/ tm 1000.0))) + goal-points) + + (send self :spin-once) + (send goal :goal :trajectory :points goal-points) + (send gripper-action :send-goal goal) + ) + #| + (send self :send-ros-controller + gripper-action (list (send (send robot :gripper_joint) :name)) ;; action server and joint-names + 0 ;; start time + (list + (list (float-vector pos) ;; positions + (instantiate float-vector 1) ;; velocities + (/ tm 1000.0)))) + |# + (if wait (send gripper-action :wait-for-result)) + ) + ;; 把持モード開始メソッド (:start-grasp - (&optional (arm :arm) &key ((:gain g) 0.5) ((:objects objs) objects)) + (&key ((:gain g) 0.5)) "Start grasp mode." - (send self :set-compliance-slope 7 1023) - (send self :set-torque-limit 7 g) - (send robot :gripper arm :angle-vector - (send-all (send robot :gripper arm :joint-list) :min-angle)) - (send self :angle-vector (send robot :angle-vector) 1000 :gripper-controller) - (send self :wait-interpolation :gripper-controller) + (unless (or (send self :simulation-modep) (ros::get-param "use_sim_time" nil)) + (send self :set-compliance-slope 7 1023) + (send self :set-torque-limit 7 g)) + (send self :move-gripper (send (send robot :gripper_joint) :min-angle) :tm 1000 :wait t) (send self :state) - (send robot :gripper arm :angle-vector - (mapcar #'(lambda (x) (- x 5)) (send-all (send robot :gripper arm :joint-list) :joint-angle))) ;; 5[deg] - (send self :angle-vector (send robot :angle-vector) 200 :gripper-controller) - (send self :wait-interpolation :gripper-controller) + (send robot :gripper :arm :joint-angle (- (send robot :gripper :arm :joint-angle) 5)) ;; 5[deg] + (send self :move-gripper (send robot :gripper :arm :joint-angle) :tm 200 :wait t) ) + ;; 把持モード停止メソッド (:stop-grasp - (&optional (arm :arm) &key (wait nil)) + () "Stop grasp mode." - (send robot :gripper arm :angle-vector - (send-all (send robot :gripper arm :joint-list) :max-angle)) - (send self :angle-vector (send robot :angle-vector) 1000 :gripper-controller) - (send self :set-compliance-slope 7 32) - (send self :set-torque-limit 7 1.0) - (send self :wait-interpolation :gripper-controller) + (send self :move-gripper (send (send robot :gripper_joint) :max-angle) :tm 1000 :wait t) + (unless (or (send self :simulation-modep) (ros::get-param "use_sim_time" nil)) + (send self :set-compliance-slope 7 32) + (send self :set-torque-limit 7 1.0)) ) ) ) diff --git a/dynamixel_7dof_arm/euslisp/dxl-7dof-arm-interface.l b/dynamixel_7dof_arm/euslisp/dxl-7dof-arm-interface.l index e2011415..798209be 100644 --- a/dynamixel_7dof_arm/euslisp/dxl-7dof-arm-interface.l +++ b/dynamixel_7dof_arm/euslisp/dxl-7dof-arm-interface.l @@ -13,7 +13,7 @@ ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; (defclass dxl-7dof-arm-interface :super robot-interface - :slots ()) + :slots (gripper-action)) (eval `(defmethod dxl-7dof-arm-interface ;; dxl-7dof-arm-interfaceのメソッドをdefmethodする diff --git a/dynamixel_7dof_arm/euslisp/dxl-7dof-arm-robot.l b/dynamixel_7dof_arm/euslisp/dxl-7dof-arm-robot.l index 37529684..ea119391 100644 --- a/dynamixel_7dof_arm/euslisp/dxl-7dof-arm-robot.l +++ b/dynamixel_7dof_arm/euslisp/dxl-7dof-arm-robot.l @@ -276,7 +276,7 @@ (defclass dxl-7dof-arm-robot :super robot-model - :slots (jc0 jc1 jc2 jc3 jc4 jc5 jc6)) ;; 関節インスタンス + :slots (jc0 jc1 jc2 jc3 jc4 jc5 gripper_jc)) ;; 関節インスタンス (defmethod dxl-7dof-arm-robot (:init @@ -304,13 +304,13 @@ (setq jc3 (instance rotational-joint :init :parent-link (elt rarm 2) :child-link (elt rarm 3) :name "arm_joint4" :axis :x :min -180 :max 180 :max-joint-velocity max-joint-velocity :max-joint-torque max-joint-torque)) (setq jc4 (instance rotational-joint :init :parent-link (elt rarm 3) :child-link (elt rarm 4) :name "arm_joint5" :axis :y :min -90 :max 90 :max-joint-velocity max-joint-velocity :max-joint-torque max-joint-torque)) (setq jc5 (instance rotational-joint :init :parent-link (elt rarm 4) :child-link (elt rarm 5) :name "arm_joint6" :axis :x :min -180 :max 180 :max-joint-velocity max-joint-velocity :max-joint-torque max-joint-torque)) - (setq jc6 (instance rotational-joint :init :parent-link (elt rarm 5) :child-link (elt rarm 6) :name "arm_joint7" :axis :z :min -55 :max 50 :max-joint-velocity max-joint-velocity :max-joint-torque max-joint-torque)) + (setq gripper_jc (instance rotational-joint :init :parent-link (elt rarm 5) :child-link (elt rarm 6) :name "gripper_joint" :axis :z :min -55 :max 50 :max-joint-velocity max-joint-velocity :max-joint-torque max-joint-torque)) ) ;; 4. define slots for robot class ;; links and joint-list for cascaded-link. - (setq links (append (list aroot-link) rarm)) - (setq joint-list (list jc0 jc1 jc2 jc3 jc4 jc5 jc6)) + (setq links (append (list aroot-link) (butlast rarm))) + (setq joint-list (list jc0 jc1 jc2 jc3 jc4 jc5)) ;; These are for robot-model. (setq rarm-root-link (car rarm)) ;; end-coords @@ -320,6 +320,9 @@ ;; 5. call :init-ending after defining links and joint-list and return "self" (send self :init-ending) + + ;; 6. overwrite bodies to return draw-things links not (send link :bodies) + (setq bodies (flatten (mapcar #'(lambda (b) (if (find-method b :bodies) (send b :bodies))) (append links (last rarm))))) self)) ;; links (:make-root-link @@ -349,32 +352,57 @@ (:arm_joint4 () jc3) (:arm_joint5 () jc4) (:arm_joint6 () jc5) - (:arm_joint7 () jc6) + (:gripper_joint () gripper_jc) + ;; limbs (:arm (&rest args) "Accessor for arm methods." (unless args (setq args (list nil))) (send* self :limb :rarm args)) + + (:gripper + (limb &rest args) + (let () + (unless (or (eq limb :arm) (eq limb :rarm)) + (error "you can only use ~A, not ~A " ":arm" limb) + (return-from :gripper nil)) + (cond + ((memq :links args) + (list (send gripper_jc :child-link))) + ((memq :joint-list args) + (list gripper_jc)) + ((memq :joint-angle args) + (if (null (cdr args)) + (send gripper_jc :joint-angle) + (send gripper_jc :joint-angle (cadr args)) + )) + (t (send-super* :gripper limb args)) + ))) + ;; poses (:reset-pose () "Reset pose." - (send self :angle-vector (float-vector 0.0 0.0 -90.0 0.0 90.0 0.0 0.0))) + (let () + (send self :angle-vector (float-vector 0.0 0.0 -90.0 0.0 90.0 0.0)) + (send (send self :gripper_joint) :joint-angle 0))) (:reset-pose2 () "Reset pose2." - (send self :angle-vector (float-vector 0.0 150.0 -90.0 0.0 90.0 0.0 0.0))) + (let () + (send self :angle-vector (float-vector 0.0 150.0 -90.0 0.0 90.0 0.0)) + (send (send self :gripper_joint) :joint-angle 0))) (:tuckarm-pose () "Folding arm pose." - (send self :angle-vector (float-vector 0.0 150.0 -90.0 0.0 0.0 0.0 0.0))) + (send self :angle-vector (float-vector 0.0 150.0 -90.0 0.0 0.0 0.0))) (:tuckarm-pose2 () "Folding arm pose2." - (send self :angle-vector (float-vector 90.0 90.0 5.0 0.0 -90.0 90.0 0.0))) + (send self :angle-vector (float-vector 90.0 90.0 5.0 0.0 -90.0 90.0))) (:tuckarm-pose3 () "Folding arm pose3." - (send self :angle-vector (float-vector 0.0 90.0 0.0 -20.0 90.0 0.0 0.0))) + (send self :angle-vector (float-vector 0.0 90.0 0.0 -20.0 90.0 0.0))) ;; inverse-kinematics (:inverse-kinematics (target-coords &rest args &key (link-list) @@ -394,7 +422,6 @@ (setq move-target (send self :arm :end-coords))) (unless link-list (setq link-list (send self :link-list (send move-target :parent)))) - ;; use base (cond (use-base diff --git a/dynamixel_7dof_arm/launch/dynamixel_7dof_arm_bringup.launch b/dynamixel_7dof_arm/launch/dynamixel_7dof_arm_bringup.launch index 3e57e2f8..afd6a178 100644 --- a/dynamixel_7dof_arm/launch/dynamixel_7dof_arm_bringup.launch +++ b/dynamixel_7dof_arm/launch/dynamixel_7dof_arm_bringup.launch @@ -28,7 +28,7 @@ arm_j4_controller arm_j5_controller arm_j6_controller - arm_j7_controller" + gripper_joint_controller" output="screen"/> diff --git a/dynamixel_7dof_arm/launch/gripper_controller_spawner.launch b/dynamixel_7dof_arm/launch/gripper_controller_spawner.launch index 48942938..25228493 100644 --- a/dynamixel_7dof_arm/launch/gripper_controller_spawner.launch +++ b/dynamixel_7dof_arm/launch/gripper_controller_spawner.launch @@ -8,6 +8,6 @@ --port=7dof_arm_port --type=meta gripper_controller - arm_j7_controller" + gripper_joint_controller" output="screen"/> diff --git a/dynamixel_7dof_arm/urdf/dynamixel_7dof_arm.urdf.xacro b/dynamixel_7dof_arm/urdf/dynamixel_7dof_arm.urdf.xacro index 754615de..60032ac3 100644 --- a/dynamixel_7dof_arm/urdf/dynamixel_7dof_arm.urdf.xacro +++ b/dynamixel_7dof_arm/urdf/dynamixel_7dof_arm.urdf.xacro @@ -29,12 +29,12 @@ - - + + - + - + @@ -114,12 +114,12 @@ - - + + - + @@ -220,27 +220,28 @@ - + - - - + + - + - @@ -248,31 +249,33 @@ - + - - + - + - + - @@ -313,13 +316,22 @@ - - - - - - - + + 0.8 + 0.8 + + + 0.8 + 0.8 + + + + + + + + +