diff --git a/.gitignore b/.gitignore index d947871282..570eef3ee0 100644 --- a/.gitignore +++ b/.gitignore @@ -2,4 +2,5 @@ build *# latest_asdf_check -.#* \ No newline at end of file +.#* +*~ diff --git a/LICENSE b/LICENSE new file mode 100644 index 0000000000..cb4ef49684 --- /dev/null +++ b/LICENSE @@ -0,0 +1,30 @@ + +Copyright (c) 2009 - 2021, CRAM team +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + * Neither the name of the Intelligent Autonomous Systems Group/ + Technische Universitaet Muenchen, nor the name of the + Institute for Artificial Intelligence/Universitaet Bremen, + nor the names of their contributors may be used to + endorse or promote products derived from this software without + specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +POSSIBILITY OF SUCH DAMAGE. diff --git a/cram-18.04.rosinstall b/cram-18.04.rosinstall new file mode 100644 index 0000000000..91e1f964ac --- /dev/null +++ b/cram-18.04.rosinstall @@ -0,0 +1,21 @@ +# THIS IS AN AUTOGENERATED FILE, LAST GENERATED USING wstool ON 2018-10-16 +- git: + local-name: cram + uri: https://github.com/cram2/cram.git + version: master-melodic +- git: + local-name: giskard_msgs + uri: https://github.com/SemRoCo/giskard_msgs.git + version: 5bfb2a2dc0d58635fab4eceaf93a43c2729a4cdf +- git: + local-name: iai_common_msgs + uri: https://github.com/code-iai/iai_common_msgs.git + version: 46d6e9b9be386de9cf5e153f489c382e0c66f74c +- git: + local-name: iai_maps + uri: https://github.com/code-iai/iai_maps.git + version: 497632f5bbf8f028b5cf25470efeefbaaf9ce388 +- git: + local-name: genlisp + uri: https://github.com/ros/genlisp.git + version: 3ac633abacdf5ab321d23ed013c7d5b7da97736d diff --git a/cram_3d_world/cl_bullet/cl-bullet-examples.asd b/cram_3d_world/cl_bullet/cl-bullet-examples.asd deleted file mode 120000 index 8ba685709f..0000000000 --- a/cram_3d_world/cl_bullet/cl-bullet-examples.asd +++ /dev/null @@ -1 +0,0 @@ -src/lisp/examples/cl-bullet-examples.asd \ No newline at end of file diff --git a/cram_3d_world/cl_bullet/cl-bullet-examples.asd b/cram_3d_world/cl_bullet/cl-bullet-examples.asd new file mode 100644 index 0000000000..1176bbc060 --- /dev/null +++ b/cram_3d_world/cl_bullet/cl-bullet-examples.asd @@ -0,0 +1,39 @@ +;;; +;;; Copyright (c) 2010, Lorenz Moesenlechner +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Intelligent Autonomous Systems Group/ +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software +;;; without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. +;;; + +(defsystem cl-bullet-examples + :author "Lorenz Moesenlechner " + :license "BSD" + :depends-on (cl-bullet cl-transforms) + :components + ((:module "src/lisp/examples" + :components + ((:file "package") + (:file "hello-world" :depends-on ("package")))))) diff --git a/cram_3d_world/cl_bullet/cl-bullet.asd b/cram_3d_world/cl_bullet/cl-bullet.asd deleted file mode 120000 index 95eb506544..0000000000 --- a/cram_3d_world/cl_bullet/cl-bullet.asd +++ /dev/null @@ -1 +0,0 @@ -src/lisp/cl-bullet.asd \ No newline at end of file diff --git a/cram_3d_world/cl_bullet/cl-bullet.asd b/cram_3d_world/cl_bullet/cl-bullet.asd new file mode 100644 index 0000000000..71e7436411 --- /dev/null +++ b/cram_3d_world/cl_bullet/cl-bullet.asd @@ -0,0 +1,67 @@ +;;; +;;; Copyright (c) 2010, Lorenz Moesenlechner +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Intelligent Autonomous Systems Group/ +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software +;;; without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. +;;; + +(defsystem cl-bullet + :author "Lorenz Moesenlechner " + :license "BSD" + :description "A common lisp wrapper for the bullet library" + + :depends-on (:cffi + :cffi-ros-utils + :trivial-garbage + :ros-load-manifest + :cram-utilities + :split-sequence + :cl-transforms) + :components + ((:module "src/lisp" + :components + ((:file "package") + (:file "foreign-types" :depends-on ("package")) + (:file "cffi" :depends-on ("package" "foreign-types")) + (:file "foreign-class" :depends-on ("package")) + (:file "debug-draw" :depends-on ("package" "foreign-types" "cffi" "foreign-class")) + (:file "bt-world" :depends-on ("package" "cffi" "foreign-class" "rigid-body" "contact-manifold")) + (:file "contact-manifold" :depends-on ("package")) + (:file "motion-state" :depends-on ("package" "cffi" "foreign-class")) + (:file "rigid-body" :depends-on ("package" "cffi" "foreign-class" "motion-state")) + (:file "collision-shapes" :depends-on ("package" "cffi" "foreign-class")) + (:file "constraints" :depends-on ("package" "cffi" "foreign-class")) + (:file "point-2-point-constraint" :depends-on ("package" "cffi" "constraints")) + (:file "hinge-constraint" :depends-on ("package" "cffi" "constraints")) + (:file "slider-constraint" :depends-on ("package" "cffi" "constraints")) + (:file "world-state" :depends-on ("package" + "bt-world" + "rigid-body" + "collision-shapes" + "point-2-point-constraint" + "hinge-constraint" + "slider-constraint")))))) + diff --git a/cram_3d_world/cl_bullet/src/lisp/cl-bullet.asd b/cram_3d_world/cl_bullet/src/lisp/cl-bullet.asd deleted file mode 100644 index c97970f7f3..0000000000 --- a/cram_3d_world/cl_bullet/src/lisp/cl-bullet.asd +++ /dev/null @@ -1,65 +0,0 @@ -;;; -;;; Copyright (c) 2010, Lorenz Moesenlechner -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software -;;; without specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. -;;; - -(defsystem cl-bullet - :author "Lorenz Moesenlechner " - :license "BSD" - :description "A common lisp wrapper for the bullet library" - - :depends-on (:cffi - :cffi-ros-utils - :trivial-garbage - :ros-load-manifest - :cram-utilities - :split-sequence - :cl-transforms) - :components - ((:file "package") - (:file "foreign-types" :depends-on ("package")) - (:file "cffi" :depends-on ("package" "foreign-types")) - (:file "foreign-class" :depends-on ("package")) - (:file "debug-draw" :depends-on ("package" "foreign-types" "cffi" "foreign-class")) - (:file "bt-world" :depends-on ("package" "cffi" "foreign-class" "rigid-body" "contact-manifold")) - (:file "contact-manifold" :depends-on ("package")) - (:file "motion-state" :depends-on ("package" "cffi" "foreign-class")) - (:file "rigid-body" :depends-on ("package" "cffi" "foreign-class" "motion-state")) - (:file "collision-shapes" :depends-on ("package" "cffi" "foreign-class")) - (:file "constraints" :depends-on ("package" "cffi" "foreign-class")) - (:file "point-2-point-constraint" :depends-on ("package" "cffi" "constraints")) - (:file "hinge-constraint" :depends-on ("package" "cffi" "constraints")) - (:file "slider-constraint" :depends-on ("package" "cffi" "constraints")) - (:file "world-state" :depends-on ("package" - "bt-world" - "rigid-body" - "collision-shapes" - "point-2-point-constraint" - "hinge-constraint" - "slider-constraint")))) - diff --git a/cram_3d_world/cl_bullet_vis/src/math-function-visualization.lisp b/cram_3d_world/cl_bullet_vis/src/math-function-visualization.lisp index 2640148e4e..b2c76c7f96 100644 --- a/cram_3d_world/cl_bullet_vis/src/math-function-visualization.lisp +++ b/cram_3d_world/cl_bullet_vis/src/math-function-visualization.lisp @@ -86,9 +86,12 @@ (gl:mult-matrix (pose->gl-matrix pose)) (loop for x from (- (/ width 2)) to (- (/ width 2) step-size) by step-size do (loop for y from (- (/ height 2)) to (- (/ height 2) step-size) by step-size do - (let ((pt-1 (get-point x y))) - (when pt-1 - (let* ((value (cl-transforms:z pt-1)) + (let ((middle-pt (get-point (+ x (/ step-size 2)) + (+ y (/ step-size 2))))) + (when middle-pt + (let* ((value (cl-transforms:z middle-pt)) + (pt-1 (cl-transforms:make-3d-vector + x y value)) (pt-2 (cl-transforms:make-3d-vector (+ x step-size) y value)) (pt-3 (cl-transforms:make-3d-vector diff --git a/cram_3d_world/cram_btr_spatial_relations_costmap/src/cost-functions.lisp b/cram_3d_world/cram_btr_spatial_relations_costmap/src/cost-functions.lisp index 021172795b..095655b133 100644 --- a/cram_3d_world/cram_btr_spatial_relations_costmap/src/cost-functions.lisp +++ b/cram_3d_world/cram_btr_spatial_relations_costmap/src/cost-functions.lisp @@ -131,7 +131,7 @@ ref-sz/2 + ref-padding + max-padding + max-sz + max-padding + for-padding + for- (defun find-levels-under-link (parent-link) "Finds all the child links under the parent link with the name -board or level in them" +board or level or shelf in them" (let ((levels-found)) (labels ((find-levels (link) (let* ((child-joints (cl-urdf:to-joints link)) @@ -139,7 +139,8 @@ board or level in them" (mapcar (lambda (child-link) (let ((child-name (cl-urdf:name child-link))) (if (or (search "board" child-name) - (search "level" child-name)) + (search "level" child-name) + (search "shelf" child-name)) (push child-link levels-found) (find-levels child-link)))) child-links)))) @@ -179,18 +180,49 @@ reverse sort it" ;;;;;;;;;;;;;;;;;;;;;;;; COSTMAPS ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; (defun make-object-bounding-box-costmap-generator (object) - (let* ((bounding-box-dims (btr:calculate-bb-dims object)) - (dimensions-x/2 (/ (cl-transforms:x bounding-box-dims) 2)) - (dimensions-y/2 (/ (cl-transforms:y bounding-box-dims) 2)) - (center-x (cl-transforms:x (cl-transforms:origin (btr:pose object)))) - (center-y (cl-transforms:y (cl-transforms:origin (btr:pose object))))) + "This cost function assumes that one of the planes of the object +is aligned with the horizontal plane, +i.e. the object is lying flatly on the horizontal surface." + (let* ((bounding-box-dims + (btr:calculate-bb-dims object)) + (dimensions-x/2 + (/ (cl-transforms:x bounding-box-dims) 2)) + (dimensions-y/2 + (/ (cl-transforms:y bounding-box-dims) 2)) + (angle-around-map-z + (cram-tf:angle-around-map-z (cl-transforms:orientation (btr:pose object)))) + (object-position + (cl-transforms:origin (btr:pose object))) + (center-x + (cl-transforms:x object-position)) + (center-y + (cl-transforms:y object-position))) + (lambda (x y) - (if (and - (< x (+ center-x dimensions-x/2)) - (> x (- center-x dimensions-x/2)) - (< y (+ center-y dimensions-y/2)) - (> y (- center-y dimensions-y/2))) - 1.0 0.0)))) + (let* ((point-in-bb-frame-identity-orientation + (btr::make-3d-vector + (- x center-x) + (- y center-y) + 0)) + (point-in-bb-frame-bb-orientation + (cl-transforms:rotate + (cl-transforms:axis-angle->quaternion + (cl-transforms:make-3d-vector 0 0 1) + (- angle-around-map-z)) + point-in-bb-frame-identity-orientation)) + (point-in-map-frame + (cl-transforms:v+ + point-in-bb-frame-bb-orientation + (cl-transforms:make-3d-vector center-x center-y 0))) + (new-x (cl-transforms:x point-in-map-frame)) + (new-y (cl-transforms:y point-in-map-frame))) + (if (and + (<= new-x (+ center-x dimensions-x/2)) + (>= new-x (- center-x dimensions-x/2)) + (< new-y (+ center-y dimensions-y/2)) + (> new-y (- center-y dimensions-y/2))) + 1.0 + 0.0))))) (defun make-object-in-object-bounding-box-costmap-generator (container-object inner-object) "Returns a costmap generator, which for any point within @@ -202,24 +234,57 @@ Please note, that if the object is a box, it might not fit into the bounding box when rotated with, e.g., 45 degrees. It will also not be quite correct if the object is placed on its side and not upright." - (let* ((container-obj-bb-dims (btr:calculate-bb-dims container-object)) - (container-dimensions-x/2 (/ (cl-transforms:x container-obj-bb-dims) 2)) - (container-dimensions-y/2 (/ (cl-transforms:y container-obj-bb-dims) 2)) - (container-center-x (cl-transforms:x (cl-transforms:origin (btr:pose container-object)))) - (container-center-y (cl-transforms:y (cl-transforms:origin (btr:pose container-object)))) - (inner-obj-bb-dims (btr:calculate-bb-dims inner-object)) - (inner-obj-x/2 (/ (cl-transforms:x inner-obj-bb-dims) 2)) - (inner-obj-y/2 (/ (cl-transforms:y inner-obj-bb-dims) 2)) - (inner-obj-padding (max inner-obj-x/2 inner-obj-y/2)) - (dimensions-x/2 (- container-dimensions-x/2 inner-obj-padding)) - (dimensions-y/2 (- container-dimensions-y/2 inner-obj-padding))) + (let* ((container-obj-bb-dims + (btr:calculate-bb-dims container-object)) + (angle-around-map-z + (cram-tf:angle-around-map-z + (cl-transforms:orientation (btr:pose container-object)))) + (container-dimensions-x/2 + (/ (cl-transforms:x container-obj-bb-dims) 2)) + (container-dimensions-y/2 + (/ (cl-transforms:y container-obj-bb-dims) 2)) + (container-center-x + (cl-transforms:x (cl-transforms:origin (btr:pose container-object)))) + (container-center-y + (cl-transforms:y (cl-transforms:origin (btr:pose container-object)))) + (inner-obj-bb-dims + (btr:calculate-bb-dims inner-object)) + (inner-obj-x/2 + (/ (cl-transforms:x inner-obj-bb-dims) 2)) + (inner-obj-y/2 + (/ (cl-transforms:y inner-obj-bb-dims) 2)) + (inner-obj-padding + (max inner-obj-x/2 inner-obj-y/2)) + (dimensions-x/2 + (- container-dimensions-x/2 inner-obj-padding)) + (dimensions-y/2 + (- container-dimensions-y/2 inner-obj-padding))) (lambda (x y) - (if (and - (< x (+ container-center-x dimensions-x/2)) - (> x (- container-center-x dimensions-x/2)) - (< y (+ container-center-y dimensions-y/2)) - (> y (- container-center-y dimensions-y/2))) - 1.0 0.0)))) + (let* ((point-in-bb-frame-identity-orientation + (btr::make-3d-vector + (- x container-center-x) + (- y container-center-y) + 0)) + (point-in-bb-frame-bb-orientation + (cl-transforms:rotate + (cl-transforms:axis-angle->quaternion + (cl-transforms:make-3d-vector 0 0 1) + (- angle-around-map-z)) + point-in-bb-frame-identity-orientation)) + (point-in-map-frame + (cl-transforms:v+ + point-in-bb-frame-bb-orientation + (cl-transforms:make-3d-vector + container-center-x container-center-y 0))) + (new-x (cl-transforms:x point-in-map-frame)) + (new-y (cl-transforms:y point-in-map-frame))) + (if (and + (<= new-x (+ container-center-x dimensions-x/2)) + (>= new-x (- container-center-x dimensions-x/2)) + (< new-y (+ container-center-y dimensions-y/2)) + (> new-y (- container-center-y dimensions-y/2))) + 1.0 + 0.0))))) ;;; TODO: maybe include bb into deciding not just the pose and ratio (defun get-closest-edge (obj-pose supp-obj-pose supp-obj-dims) @@ -357,8 +422,11 @@ The function returns one of the following keys: :front, :back, :left, :right." (return (if invert 0.0d0 1.0d0)))))))))) (defun make-slot-cost-function (supp-object paddings-list - preferred-supporting-object-side object-count - max-slot-size min-slot-size position-deviation-threshold) + preferred-supporting-object-side + preferred-supporting-object-axis + object-count + max-slot-size min-slot-size + position-deviation-threshold) "'Divides' the supporting object into `object-count' number of slots and assigns 1s to the centers of those slots and all the points that are not further from the center than `position-deviation-threshold'. @@ -368,7 +436,14 @@ The function returns one of the following keys: :front, :back, :left, :right." The resulting slot sizes are restricted by `max-slot-size' and `min-slot-size', i.e. everything which is out of the boundaries gets truncated to the max or min. - `preferred-supporting-object-size' is either :+ (for positive direction of axis) or :-. + `preferred-supporting-object-side' is either :+ (for positive direction of axis) or :-. + `preferred-supporting-object-axis' is either :X or :Y, + depending on along which axis we want to be putting multiple plates. + In the case of the picture above, it's the axis that has 3 'x'-s, so + the horizontal axis. + Originally, the longer axis was usually preferred to put as many objects + as possible. But since that is not always the case, + the longer axis calculations below are not really used anymore. `paddings-list' is of format '(padd-x+ padd-x- padd-y+ padd-y-). The `supp-object' is supposed to be rectangular with y axis pointing to the left and x - to the back." @@ -377,24 +452,26 @@ The function returns one of the following keys: :front, :back, :left, :right." (type keyword preferred-supporting-object-side) (type integer object-count) (type real max-slot-size min-slot-size position-deviation-threshold)) - (flet ((calculate-points (distance point-count longer-side-axis coord-on-shorter-axis) + (flet ((calculate-points (distance point-count preferred-side-axis coord-on-constant-axis) (loop repeat point-count for next-coord = (* (/ (1- point-count) 2) distance) then (- next-coord distance) collecting - (cond - ((eql longer-side-axis #'cl-transforms:x) - (list next-coord coord-on-shorter-axis)) - ((eql longer-side-axis #'cl-transforms:y) - (list coord-on-shorter-axis next-coord)))))) + (ecase preferred-side-axis + (cl-transforms:x + (list next-coord coord-on-constant-axis)) + (cl-transforms:y + (list coord-on-constant-axis next-coord)))))) + (let* ((supp-obj-dims-in-sem-map-coords (btr:calculate-bb-dims supp-object)) (padded-supp-obj-dims-in-sem-map-coords (cl-transforms:v- supp-obj-dims-in-sem-map-coords - (cl-transforms:make-3d-vector (+ (first paddings-list) (second paddings-list)) - (+ (third paddings-list) (fourth paddings-list)) - 0.0d0))) + (cl-transforms:make-3d-vector + (+ (first paddings-list) (second paddings-list)) + (+ (third paddings-list) (fourth paddings-list)) + 0.0d0))) ;; inverse transform of the origin of the center of the padded region: (padding-center->zero-in-sem-map-coords (cl-transforms:make-transform @@ -406,40 +483,48 @@ The function returns one of the following keys: :front, :back, :left, :right." ;; set initial values for the axis and switch if needed (longer-side-axis #'cl-transforms:x) (shorter-side-axis #'cl-transforms:y) - (longer-side-length nil) + constant-side-axis + (preferred-side-length nil) (max-possible-object-count nil)) (when (> (cl-transforms:y padded-supp-obj-dims-in-sem-map-coords) (cl-transforms:x padded-supp-obj-dims-in-sem-map-coords)) (rotatef longer-side-axis shorter-side-axis)) - (setf longer-side-length - (funcall longer-side-axis padded-supp-obj-dims-in-sem-map-coords)) + (ecase preferred-supporting-object-axis + (cl-transforms:x (setf constant-side-axis 'cl-transforms:y)) + (cl-transforms:y (setf constant-side-axis 'cl-transforms:x))) + (setf preferred-side-length + (funcall (symbol-function preferred-supporting-object-axis) + padded-supp-obj-dims-in-sem-map-coords)) (setf max-possible-object-count - (* (floor longer-side-length min-slot-size) 2)) + (* (floor preferred-side-length min-slot-size) 2)) (when (> object-count max-possible-object-count) (setf object-count max-possible-object-count)) (let* ((object-count-on-preferred-side (ceiling object-count 2)) (object-count-on-other-side (floor object-count 2)) - (coord-on-shorter-axis - (- (/ (funcall shorter-side-axis padded-supp-obj-dims-in-sem-map-coords) + (coord-on-constant-axis + (- (/ (funcall (symbol-function constant-side-axis) + padded-supp-obj-dims-in-sem-map-coords) 2.0) (/ min-slot-size 2.0))) (distance - (/ longer-side-length object-count-on-preferred-side))) + (/ preferred-side-length object-count-on-preferred-side))) (when (> distance max-slot-size) (setf distance max-slot-size)) (ecase preferred-supporting-object-side (:+ nil) - (:- (setf coord-on-shorter-axis (- coord-on-shorter-axis)))) + (:- (setf coord-on-constant-axis (- coord-on-constant-axis)))) (let* ((placement-points (concatenate 'list (calculate-points distance object-count-on-preferred-side - longer-side-axis coord-on-shorter-axis) + preferred-supporting-object-axis + coord-on-constant-axis) (calculate-points distance object-count-on-other-side - longer-side-axis (- coord-on-shorter-axis)))) + preferred-supporting-object-axis + (- coord-on-constant-axis)))) (supp-obj-pose (btr:pose supp-object)) (world->supp-transform @@ -452,15 +537,17 @@ The function returns one of the following keys: :front, :back, :left, :right." padding-center->zero-in-sem-map-coords (cl-transforms:transform-point supp->world-transform - (cl-transforms:make-3d-vector x y 0)))) + (cl-transforms:make-3d-vector x y 1.0)))) (min-dist (reduce #'min (mapcar (lambda (x-and-y) (sqrt (+ (expt (- (cl-transforms:x point) - (first x-and-y)) 2) + (first x-and-y)) + 2) (expt (- (cl-transforms:y point) - (second x-and-y)) 2)))) + (second x-and-y)) + 2)))) placement-points)))) (if (<= min-dist position-deviation-threshold) 1.0 @@ -485,23 +572,25 @@ if it is on the sign side of the axis. " (defparameter *board-thickness* 0.040) -(defun make-object-bounding-box-height-generator (object &optional (tag :on)) +(defun make-object-bounding-box-height-generator (object &optional (tag :on) (z-offset 0.0)) (constantly (list (ecase tag (:on (+ (cl-transforms:z (cl-transforms:origin (btr:pose object))) (/ (cl-transforms:z (btr:calculate-bb-dims object)) - 2.0))) + 2.0) + z-offset)) (:in (+ (cl-transforms:z (cl-transforms:origin (btr:pose object))) (- (/ (cl-transforms:z (btr:calculate-bb-dims object)) 2.0)) + z-offset *board-thickness*)))))) (defun make-object-on/in-object-bb-height-generator (environment-objects for-object - &optional (tag :on)) + &optional (tag :on) (z-offset 0.0)) (let* ((environment-object-top (apply #'max (mapcar (lambda (environment-object) @@ -511,13 +600,15 @@ if it is on the sign side of the axis. " (btr:pose environment-object))) (/ (cl-transforms:z (btr:calculate-bb-dims environment-object)) - 2.0))) + 2.0) + z-offset)) (:in (+ (cl-transforms:z (cl-transforms:origin (btr:pose environment-object))) (- (/ (cl-transforms:z (btr:calculate-bb-dims environment-object)) 2.0)) + z-offset *board-thickness*)))) (if (listp environment-objects) environment-objects diff --git a/cram_3d_world/cram_btr_spatial_relations_costmap/src/knowledge.lisp b/cram_3d_world/cram_btr_spatial_relations_costmap/src/knowledge.lisp index 38356fcebc..121217487d 100644 --- a/cram_3d_world/cram_btr_spatial_relations_costmap/src/knowledge.lisp +++ b/cram_3d_world/cram_btr_spatial_relations_costmap/src/knowledge.lisp @@ -113,8 +113,12 @@ (equal ?threshold 0.2))) ;; table setting related - (<- (%paddings-list :kitchen-island-surface :table-setting (0.03d0 0.03d0 0.8d0 0.03d0))) - (<- (%paddings-list :sink-area-surface :table-setting (0.03d0 0.03d0 0.03d0 0.03d0))) + (<- (%paddings-list :kitchen-island-surface :table-setting + (0.1d0 0.1d0 0.8d0 0.1d0))) + (<- (%paddings-list :sink-area-surface :table-setting + (0.03d0 0.03d0 0.03d0 0.03d0))) + (<- (%paddings-list :dining-area-jokkmokk-table-main :table-setting + (0.1d0 0.1d0 0.1d0 0.1d0))) (<- (paddings-list ?environment-object-name :table-setting ?paddings-list) (setof ?object-name (%paddings-list ?object-name :table-setting ?_) ?defined-paddings-list-objects) @@ -131,6 +135,22 @@ (%preferred-supporting-object-side ?environment-object-name :table-setting ?side) (equal ?side :+))) ;; + (<- (%preferred-supporting-object-axis :dining-area-jokkmokk-table-main + :table-setting + cl-transforms:y)) + (<- (%preferred-supporting-object-axis :kitchen-island-surface + :table-setting + cl-transforms:y)) + (<- (preferred-supporting-object-axis ?environment-object-name :table-setting + ?axis) + (setof ?object-name + (%preferred-supporting-object-axis ?object-name :table-setting ?_) + ?defined-preferred-axis-objects) + (-> (member ?environment-object-name ?defined-preferred-axis-objects) + (%preferred-supporting-object-axis ?environment-object-name + :table-setting ?axis) + (equal ?axis cl-transforms:x))) + ;; (<- (%max-slot-size :plate :table-setting 0.8)) (<- (%max-slot-size :bowl :table-setting 0.6)) (<- (max-slot-size ?environment-object-name :table-setting ?size) @@ -147,7 +167,9 @@ (-> (member ?environment-object-name ?defined-objects) (%min-slot-size ?environment-object-name :table-setting ?size) (equal ?size 0.5))) + ;; (<- (%position-deviation-threshold :plate :table-setting 0.08)) + (<- (%position-deviation-threshold :bowl :table-setting 0.08)) (<- (position-deviation-threshold ?environment-object-name :table-setting ?size) (setof ?object-name (%position-deviation-threshold ?object-name :table-setting ?_) ?defined-objects) diff --git a/cram_3d_world/cram_btr_spatial_relations_costmap/src/prolog.lisp b/cram_3d_world/cram_btr_spatial_relations_costmap/src/prolog.lisp index aded3a3db5..f8a7f0bbb0 100644 --- a/cram_3d_world/cram_btr_spatial_relations_costmap/src/prolog.lisp +++ b/cram_3d_world/cram_btr_spatial_relations_costmap/src/prolog.lisp @@ -31,22 +31,22 @@ (in-package :btr-spatial-cm) (defmethod costmap:costmap-generator-name->score ((name (eql 'environment-free-space))) 4) -(defmethod costmap:costmap-generator-name->score ((name (eql 'supporting-object))) 9) +(defmethod costmap:costmap-generator-name->score ((name (eql 'supporting-object))) 5) (defmethod costmap:costmap-generator-name->score ((name (eql 'slot-generator))) 6) -(defmethod costmap:costmap-generator-name->score ((name (eql 'collision))) 10) +(defmethod costmap:costmap-generator-name->score ((name (eql 'collision))) 20) (defmethod costmap:costmap-generator-name->score ((name (eql 'on-bounding-box))) 5) (defclass side-generator () ()) -(defmethod costmap:costmap-generator-name->score ((name side-generator)) 5) +(defmethod costmap:costmap-generator-name->score ((name side-generator)) 3) (defclass range-generator () ()) (defmethod costmap:costmap-generator-name->score ((name range-generator)) 2) (defclass gaussian-generator () ()) -(defmethod costmap:costmap-generator-name->score ((name gaussian-generator)) 4) +(defmethod costmap:costmap-generator-name->score ((name gaussian-generator)) 7) (defclass field-generator () ()) -(defmethod costmap:costmap-generator-name->score ((name field-generator)) 7) +(defmethod costmap:costmap-generator-name->score ((name field-generator)) 15) ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; @@ -100,11 +100,23 @@ (<- (desig-solution-not-in-collision ?desig ?object-to-check ?pose) (btr:bullet-world ?world) (btr:with-copied-world ?world - (btr-belief:object-designator-name ?object-to-check ?object-name) + (object-designator-from-name-or-type ?object-to-check ?object-name) (btr:object ?world ?object-name) (btr:assert (btr:object-pose ?world ?object-name ?pose)) (forall (btr:contact ?world ?object-name ?other-object-name) - (not (btr:item-type ?world ?other-object-name ?_)))))) + (not (btr:item-type ?world ?other-object-name ?_))))) + + (<- (object-designator-from-name-or-type ?object-designator ?object-name) + (or (and (bound ?object-designator) + (desig:obj-desig? ?object-designator)) + (and (not (bound ?object-designator)) + (lisp-fun btr-belief::unique-object-designators ?object-designators) + (member ?one-desig-from-chain ?object-designators) + (desig:current-designator ?one-desig-from-chain ?object-designator))) + (or (desig:desig-prop ?object-designator (:name ?object-name)) + (and (desig:desig-prop ?object-designator (:type ?object-type)) + (btr:bullet-world ?w) + (btr:item-type ?world ?object-name ?object-type))))) @@ -134,13 +146,25 @@ (def-fact-group spatial-relations-costmap (costmap:desig-costmap) ;;;;;;;;;; REACHABILITY AND VISIBILITY LOCATION padded from environment ;;;;;; (<- (costmap:desig-costmap ?designator ?costmap) - (or (cram-robot-interfaces:visibility-designator ?designator) - (cram-robot-interfaces:reachability-designator ?designator)) + (or (rob-int:visibility-designator ?designator) + (rob-int:reachability-designator ?designator)) + ;; make sure that the location is not on the robot itself + ;; if it is, don't generate a costmap + (-> (desig:desig-prop ?designator (:location ?some-location)) + (and (desig:current-designator ?some-location ?location) + (not (man-int:location-always-reachable ?location))) + (-> (desig:desig-prop ?designator (:object ?some-object)) + (and (desig:current-designator ?some-object ?object) + (-> (desig:desig-prop ?object (:location ?some-loc)) + (not (man-int:location-always-reachable ?some-loc)) + (true))) + (true))) (costmap:costmap ?costmap) + (rob-int:robot ?robot-name) (btr:bullet-world ?world) - (btr:%object ?world :kitchen ?kitchen-object) + (lisp-fun btr:get-environment-object ?kitchen-object) (lisp-fun btr:rigid-bodies ?kitchen-object ?rigid-bodies) - (costmap:costmap-padding ?padding) + (costmap:costmap-padding ?robot-name ?padding) (costmap:costmap-add-function environment-free-space (make-aabbs-costmap-generator @@ -203,14 +227,14 @@ (-> (desig:loc-desig? ?ref-obj) (and (equal ?ref-obj-size 0.1) (equal ?ref-padding 0.1)) - (and (btr-belief:object-designator-name ?ref-obj ?ref-obj-name) + (and (object-designator-from-name-or-type ?ref-obj ?ref-obj-name) (btr:bullet-world ?world) (btr:object ?world ?ref-obj-name) (object-size-without-handles ?world ?ref-obj-name ?ref-obj-size) (padding-size ?world ?ref-obj-name ?ref-padding))) ;; (-> (desig:desig-prop ?designator (:for ?for-obj)) - (and (btr-belief:object-designator-name ?for-obj ?for-obj-name) + (and (object-designator-from-name-or-type ?for-obj ?for-obj-name) (btr:object ?world ?for-obj-name) (object-size-without-handles ?world ?for-obj-name ?for-obj-size) (padding-size ?world ?for-obj-name ?for-padding)) @@ -263,7 +287,7 @@ (-> (desig:loc-desig? ?ref-designator) (and (equal ?edge :front) (lisp-fun cl-transforms:make-identity-pose ?supp-obj-pose)) - (and (btr-belief:object-designator-name ?ref-designator ?obj-name) + (and (object-designator-from-name-or-type ?ref-designator ?obj-name) (btr:bullet-world ?world) (btr:object ?world ?obj-name) (-> (supporting-rigid-body ?world ?obj-name ?supporting-rigid-body) @@ -281,7 +305,9 @@ ;; (btr:assert (btr:object-pose ?world ?supporting-object-name ;; ((0 0 0) (0 0 0 1)))) (lisp-fun cl-bullet:pose ?supporting-rigid-body ?supp-obj-pose) - (lisp-fun btr:calculate-bb-dims ?supporting-rigid-body ?supp-obj-dims) + (lisp-fun btr:aabb ?supporting-rigid-body ?supp-obj-bb) + (lisp-fun cl-bullet:bounding-box-dimensions ?supp-obj-bb + ?supp-obj-dims) (lisp-fun get-closest-edge ?reference-pose ?supp-obj-pose ?supp-obj-dims ?edge)) (and (equal ?edge :front) (lisp-fun cl-transforms:make-identity-pose ?supp-obj-pose))))) @@ -307,22 +333,20 @@ ;; should be using make-aabb-costmap-generator I guess (<- (costmap:desig-costmap ?desig ?cm) (fail) - (or - (desig:desig-prop ?desig (:left-of ?_)) - (desig:desig-prop ?desig (:right-of ?_)) - (desig:desig-prop ?desig (:in-front-of ?_)) - (desig:desig-prop ?desig (:behind ?_)) - (desig:desig-prop ?desig (:far-from ?_)) - (desig:desig-prop ?desig (:near ?_))) + (or (desig:desig-prop ?desig (:left-of ?_)) + (desig:desig-prop ?desig (:right-of ?_)) + (desig:desig-prop ?desig (:in-front-of ?_)) + (desig:desig-prop ?desig (:behind ?_)) + (desig:desig-prop ?desig (:far-from ?_)) + (desig:desig-prop ?desig (:near ?_))) (collision-costmap-padding-in-meters ?padding) (-> (desig:desig-prop ?desig (:for ?object)) - (and - (btr-belief:object-designator-name ?object ?object-name) - (btr:object ?world ?object-name) - (object-size-without-handles ?world ?object-name ?obj-size) - (lisp-fun / ?obj-size 2 ?obj-size/2) - (lisp-fun + ?obj-size/2 ?padding ?overall-padding) - (collision-invert-costmap ?desig ?overall-padding ?cm)) + (and (object-designator-from-name-or-type ?object ?object-name) + (btr:object ?world ?object-name) + (object-size-without-handles ?world ?object-name ?obj-size) + (lisp-fun / ?obj-size 2 ?obj-size/2) + (lisp-fun + ?obj-size/2 ?padding ?overall-padding) + (collision-invert-costmap ?desig ?overall-padding ?cm)) (collision-invert-costmap ?desig ?padding ?cm))) ;; ;;;;;;;;;;;;;;;;;;;;;; height generator for spatial relations ;;;;;;;;;;;;;;; @@ -336,7 +360,7 @@ (desig:desig-prop ?designator (:far-from ?ref-obj)) (desig:desig-prop ?designator (:near ?ref-obj))) (costmap:costmap ?costmap) - (btr-belief:object-designator-name ?ref-obj ?ref-obj-name) + (object-designator-from-name-or-type ?ref-obj ?ref-obj-name) (btr:bullet-world ?world) (btr:object ?world ?ref-obj-name) (-> (bagof ?z (and (supporting-rigid-body ?world ?ref-obj-name ?rigid-body) @@ -344,7 +368,7 @@ ?z-bag) (and (max ?z-bag ?highest-z) (-> (desig:desig-prop ?designator (:for ?for-obj)) - (and (btr-belief:object-designator-name ?for-obj ?for-obj-name) + (and (object-designator-from-name-or-type ?for-obj ?for-obj-name) (btr:object ?world ?for-obj-name) (btr:%object ?world ?for-obj-name ?for-object-instance) (lisp-fun btr:calculate-bb-dims ?for-object-instance ?dimensions) @@ -362,7 +386,9 @@ ;;;;;;;;;;;;;;; spatial relation ON for item objects ;;;;;;;;;;;;;;;;;;;;;; (<- (costmap:desig-costmap ?designator ?costmap) (desig:desig-prop ?designator (:on ?object)) - (btr-belief:object-designator-name ?object ?object-instance-name) + (not (desig:desig-prop ?designator (:attachment ?_))) + (not (desig:desig-prop ?designator (:attachments ?_))) + (object-designator-from-name-or-type ?object ?object-instance-name) (btr:bullet-world ?world) (btr:item-type ?world ?object-instance-name ?_) (btr:%object ?world ?object-instance-name ?object-instance) @@ -376,38 +402,96 @@ ?costmap)) ;; ;;;;;;;;;;;;;;; spatial relation ON for environment objects ;;;;;;;;;;;;;;;;;;;;;; + ;; (<- (costmap:desig-costmap ?designator ?costmap) + ;; (desig:desig-prop ?designator (:on ?object)) + ;; (not (desig:desig-prop ?designator (:attachment ?_))) + ;; (not (desig:desig-prop ?designator (:attachments ?_))) + ;; (spec:property ?object (:urdf-name ?urdf-name)) + ;; (spec:property ?object (:part-of ?environment-name)) + ;; (btr:bullet-world ?world) + ;; (btr:%object ?world ?environment-name ?environment-object) + ;; (lisp-fun get-link-rigid-body ?environment-object ?urdf-name ?environment-link) + ;; (lisp-pred identity ?environment-link) + ;; (costmap:costmap ?costmap) + ;; ;; costmap + ;; (costmap:costmap-add-function + ;; on-bounding-box + ;; (make-object-bounding-box-costmap-generator ?environment-link) + ;; ?costmap) + ;; ;; height generator + ;; (once (or (and (desig:desig-prop ?designator (:for ?for-object)) + ;; (object-designator-from-name-or-type ?for-object ?for-object-name) + ;; (btr:%object ?world ?for-object-name ?for-object-instance) + ;; (costmap:costmap-add-height-generator + ;; (make-object-on/in-object-bb-height-generator + ;; ?environment-link ?for-object-instance :on) + ;; ?costmap)) + ;; (costmap:costmap-add-cached-height-generator + ;; (make-object-bounding-box-height-generator ?environment-link :on) + ;; ?costmap))) + ;; ;; orientation generator + ;; (once (or (desig:desig-prop ?designator (:orientation ?orientation-type)) + ;; (equal ?orientation-type :random))) + ;; (generate-orientations ?orientation-type ?environment-link nil ?costmap)) + + + ;;;;;;;;;;;;;;; spatial relation ABOVE for environment objects ;;;;;;;;;;;; + ;; ABOVE works similar to ON. Major differences are + ;; 1. prismatic containers are opened before manipulation + ;; 2. it requires a z-offset to be provided to calculate height (<- (costmap:desig-costmap ?designator ?costmap) - (desig:desig-prop ?designator (:on ?object)) + (and (desig:desig-prop ?designator (:above ?object)) + (not (desig:desig-prop ?designator (:attachment ?_))) + (not (desig:desig-prop ?designator (:attachments ?_)))) + (desig:desig-prop ?designator (?original-tag ?object)) (spec:property ?object (:urdf-name ?urdf-name)) (spec:property ?object (:part-of ?environment-name)) + (once (or (spec:property ?designator (:z-offset ?z-offset)) + (equal 0.0 ?z-offset))) (btr:bullet-world ?world) (btr:%object ?world ?environment-name ?environment-object) - (lisp-fun get-link-rigid-body ?environment-object ?urdf-name ?environment-link) + (height-calculation-body-or-tag ?environment-object ?object + ?environment-link ?original-tag + ?height-calculation-tag) + ;; Checking whether the object is a container to determine where + ;; z-offset is calculated from. At present, always calculates + ;; from the top of the object (so a location inside the container + ;; needs a negative z-offset). Uncomment the following if-else + ;; if the calculation needs to be contextual. + ;; (-> (man-int:object-type-subtype :container ?object-type) + ;; (equal :in ?height-tag) + (equal :on ?height-tag) + (lisp-pred identity ?environment-link) (costmap:costmap ?costmap) - ;; costmap - (costmap:costmap-add-function - on-bounding-box - (make-object-bounding-box-costmap-generator ?environment-link) - ?costmap) - ;; height generator (once (or (and (desig:desig-prop ?designator (:for ?for-object)) - (btr-belief:object-designator-name ?for-object ?for-object-name) + (object-designator-from-name-or-type ?for-object ?for-object-name) (btr:%object ?world ?for-object-name ?for-object-instance) + (costmap:costmap-add-function + on-bounding-box + (make-object-in-object-bounding-box-costmap-generator + ?environment-link ?for-object-instance) + ?costmap) (costmap:costmap-add-height-generator (make-object-on/in-object-bb-height-generator - ?environment-link ?for-object-instance :on) + ?environment-link ?for-object-instance ?height-tag + ?z-offset) ?costmap)) - (costmap:costmap-add-cached-height-generator - (make-object-bounding-box-height-generator ?environment-link :on) - ?costmap))) - ;; orientation generator + (and (costmap:costmap-add-function + on-bounding-box + (make-object-bounding-box-costmap-generator + ?environment-link) + ?costmap) + (costmap:costmap-add-cached-height-generator + (make-object-bounding-box-height-generator + ?environment-link ?height-tag ?z-offset) + ?costmap)))) (once (or (desig:desig-prop ?designator (:orientation ?orientation-type)) (equal ?orientation-type :random))) (generate-orientations ?orientation-type ?environment-link nil ?costmap)) ;; - ;;;;;;;;;;;;;;; spatial relation IN for environment objects ;;;;;;;;;;;;;;;;;;; + ;;;;;;;;;;;;;;; spatial relation ON/IN for environment objects ;;;;;;;;;;;;;;;;;;; ;; LEVEL relationship for container type locations (<- (level-rigid-body ?environment-object ?urdf-name ?level-relation ?invert ?level-rigid-body) @@ -420,7 +504,7 @@ ?level-rigid-body)) ;; (<- (height-calculation-body-or-tag ?environment-object ?in-object ?link-rigid-body - ?height-calculation-tag) + ?original-tag ?height-calculation-tag) (desig:desig-prop ?in-object (:urdf-name ?urdf-name)) ;; if level keyword is found find sublevels in bottom up order (-> (desig:desig-prop ?in-object (:level ?relation)) @@ -438,21 +522,27 @@ (and (lisp-fun get-link-rigid-body ?environment-object ?urdf-name ?link-rigid-body) (lisp-pred identity ?link-rigid-body) - (equal ?height-calculation-tag :in))))) + (equal ?height-calculation-tag ?original-tag))))) ;; the costmap (<- (costmap:desig-costmap ?designator ?costmap) - (desig:desig-prop ?designator (:in ?object)) - (spec:property ?object (:type ?object-type)) - (man-int:object-type-subtype :container ?object-type) + (or (and (desig:desig-prop ?designator (:in ?object)) + (spec:property ?object (:type ?object-type)) + (man-int:object-type-subtype :container ?object-type)) + (and (desig:desig-prop ?designator (:on ?object)) + (not (desig:desig-prop ?designator (:attachment ?_))) + (not (desig:desig-prop ?designator (:attachments ?_))))) + (desig:desig-prop ?designator (?original-tag ?object)) (spec:property ?object (:urdf-name ?urdf-name)) (spec:property ?object (:part-of ?environment-name)) (btr:bullet-world ?world) (btr:%object ?world ?environment-name ?environment-object) (height-calculation-body-or-tag ?environment-object ?object - ?environment-link ?height-calculation-tag) + ?environment-link ?original-tag + ?height-calculation-tag) + (lisp-pred identity ?environment-link) (costmap:costmap ?costmap) (once (or (and (desig:desig-prop ?designator (:for ?for-object)) - (btr-belief:object-designator-name ?for-object ?for-object-name) + (object-designator-from-name-or-type ?for-object ?for-object-name) (btr:%object ?world ?for-object-name ?for-object-instance) (costmap:costmap-add-function on-bounding-box @@ -485,6 +575,7 @@ ?costmap) (paddings-list ?supp-object-name ?context ?paddings-list) (preferred-supporting-object-side ?supp-object-name ?context ?preferred-side) + (preferred-supporting-object-axis ?supp-object-name ?context ?preferred-axis) (max-slot-size ?object-type ?context ?max-slot-size) (min-slot-size ?object-type ?context ?min-slot-size) (position-deviation-threshold ?object-type ?context ?pos-dev-threshold) @@ -492,7 +583,8 @@ (costmap:costmap ?costmap) (costmap:costmap-add-function slot-generator - (make-slot-cost-function ?supp-object ?paddings-list ?preferred-side + (make-slot-cost-function ?supp-object ?paddings-list + ?preferred-side ?preferred-axis ?object-count ?max-slot-size ?min-slot-size ?pos-dev-threshold) ?costmap)) @@ -508,32 +600,59 @@ (btr:%object ?world ?environment-name ?environment-object) (lisp-fun get-link-rigid-body ?environment-object ?urdf-name ?environment-link) (lisp-pred identity ?environment-link) - (btr-belief:object-designator-name ?for-object ?object-name) + (object-designator-from-name-or-type ?for-object ?object-name) (btr:item-type ?world ?object-name ?object-type) (slot-costmap ?designator ?environment-link ?urdf-name :table-setting ?object-type ?object-count ?costmap)) ;; - ;;;;;;;;;;;;;;;;;;;;;;;;;;;; SIDE relation for ON and IN ;;;;;;;;;;;;;;;;;;; + ;;;;;;;;;;;;;;;;;;;;; SIDE and RANGE relations for ON, IN or ABOVE ;;;;;;;;; (<- (costmap:desig-costmap ?designator ?costmap) - (desig:desig-prop ?designator (:side ?relation)) - (member ?relation (:left :right :front :back)) + (or (and (desig:desig-prop ?designator (:side ?relation)) + (member ?relation (:left :right :front :back))) + (desig:desig-prop ?designator (:range ?range)) + (desig:desig-prop ?designator (:range-invert ?range-invert))) (or (desig:desig-prop ?designator (:on ?on-object)) - (desig:desig-prop ?designator (:in ?on-object))) - (desig:desig-prop ?on-object (:urdf-name ?urdf-name)) - (desig:desig-prop ?on-object (:part-of ?environment-name)) + (desig:desig-prop ?designator (:in ?on-object)) + (desig:desig-prop ?designator (:above ?on-object))) + (not (desig:desig-prop ?designator (:attachment ?_))) + (not (desig:desig-prop ?designator (:attachments ?_))) (costmap:costmap ?costmap) (btr:bullet-world ?world) - (btr:%object ?world ?environment-name ?environment-object) - (lisp-fun get-link-rigid-body ?environment-object ?urdf-name ?environment-link) - (lisp-pred identity ?environment-link) - (lisp-fun btr:pose ?environment-link ?object-pose) - (relation-axis-and-pred ?relation :in-front-of ?axis ?sign) - (instance-of side-generator ?side-generator-id) - (costmap:costmap-add-function - ?side-generator-id - (make-side-costmap-generator ?environment-link ?axis ?sign) - ?costmap) + (once + (or (and (desig:desig-prop ?on-object (:level ?level)) + (desig:desig-prop ?on-object (:urdf-name ?urdf-name)) + (desig:desig-prop ?on-object (:part-of ?environment-name)) + (btr:%object ?world ?environment-name ?environment-object) + (level-rigid-body ?environment-object ?urdf-name ?level nil + ?rigid-body) + (lisp-pred identity ?link-rigid-body)) + (and (desig:desig-prop ?on-object (:level-invert ?level)) + (desig:desig-prop ?on-object (:urdf-name ?urdf-name)) + (desig:desig-prop ?on-object (:part-of ?environment-name)) + (btr:%object ?world ?environment-name ?environment-object) + (level-rigid-body ?environment-object ?urdf-name ?level t + ?rigid-body) + (lisp-pred identity ?link-rigid-body)) + (and (desig:desig-prop ?on-object (:urdf-name ?urdf-name)) + (desig:desig-prop ?on-object (:part-of ?environment-name)) + (btr:%object ?world ?environment-name ?environment-object) + (lisp-fun get-link-rigid-body ?environment-object ?urdf-name + ?rigid-body) + (lisp-pred identity ?rigid-body)) + (and (object-designator-from-name-or-type ?on-object ?object-instance-name) + (btr:item-type ?world ?object-instance-name ?_) + (btr:%object ?world ?object-instance-name ?rigid-body) + (lisp-pred identity ?rigid-body)))) + (lisp-fun btr:pose ?rigid-body ?object-pose) + (-> (desig:desig-prop ?designator (:side ?relation)) + (and (relation-axis-and-pred ?relation :in-front-of ?axis ?sign) + (instance-of side-generator ?side-generator-id) + (costmap:costmap-add-function + ?side-generator-id + (make-side-costmap-generator ?rigid-body ?axis ?sign) + ?costmap)) + (true)) (-> (desig:desig-prop ?designator (:range ?range)) (and (instance-of range-generator ?range-generator-id) (costmap:costmap-add-function diff --git a/cram_3d_world/cram_btr_visibility_costmap/cram-btr-visibility-costmap.asd b/cram_3d_world/cram_btr_visibility_costmap/cram-btr-visibility-costmap.asd index 77b522d632..9aed631c7d 100644 --- a/cram_3d_world/cram_btr_visibility_costmap/cram-btr-visibility-costmap.asd +++ b/cram_3d_world/cram_btr_visibility_costmap/cram-btr-visibility-costmap.asd @@ -37,6 +37,7 @@ cram-location-costmap cram-robot-interfaces + cram-manipulation-interfaces ; for always-reachable cl-transforms cl-bullet-vis diff --git a/cram_3d_world/cram_btr_visibility_costmap/package.xml b/cram_3d_world/cram_btr_visibility_costmap/package.xml index b59ae6760d..0ac77d47e8 100644 --- a/cram_3d_world/cram_btr_visibility_costmap/package.xml +++ b/cram_3d_world/cram_btr_visibility_costmap/package.xml @@ -20,6 +20,7 @@ cram_math cram_location_costmap cram_robot_interfaces + cram_manipulation_interfaces cl_transforms cl_bullet_vis cl_opengl @@ -32,6 +33,7 @@ cram_math cram_location_costmap cram_robot_interfaces + cram_manipulation_interfaces cl_transforms cl_bullet_vis cl_opengl diff --git a/cram_3d_world/cram_btr_visibility_costmap/src/location-designator-facts.lisp b/cram_3d_world/cram_btr_visibility_costmap/src/location-designator-facts.lisp index 0c6124e100..a0c977c435 100644 --- a/cram_3d_world/cram_btr_visibility_costmap/src/location-designator-facts.lisp +++ b/cram_3d_world/cram_btr_visibility_costmap/src/location-designator-facts.lisp @@ -37,16 +37,22 @@ (def-fact-group bullet-reasoning-location-desig (costmap:desig-costmap) (<- (visibility-costmap-metadata ?minimal-height ?maximal-height ?resolution ?size) - (cram-robot-interfaces:robot ?robot) - (cram-robot-interfaces:camera-minimal-height ?robot ?minimal-height) - (cram-robot-interfaces:camera-maximal-height ?robot ?maximal-height) - (costmap:costmap-resolution ?resolution) - (costmap:visibility-costmap-size ?size)) + (rob-int:robot ?robot) + (rob-int:camera-minimal-height ?robot ?minimal-height) + (rob-int:camera-maximal-height ?robot ?maximal-height) + (rob-int:environment-name ?environment-name) + (costmap:costmap-resolution ?environment-name ?resolution) + (costmap:visibility-costmap-size ?robot ?size)) (<- (object-visibility-costmap ?designator ?costmap) (desig:desig-prop ?designator (:object ?object)) (desig:desig-prop ?object (:name ?object-name)) - ;; (btr:bullet-world ?world) + ;; if the object is on the robot, don't need a visibility cm + (desig:current-designator ?object ?current-object) + (-> (desig:desig-prop ?current-object (:location ?loc)) + (not (man-int:location-always-reachable ?loc)) + (true)) + (btr:bullet-world ?world) ;; (btr-belief:object-designator-name ?object ?object-name) (cram-robot-interfaces:robot ?robot) (costmap:costmap ?costmap) @@ -76,6 +82,7 @@ (<- (location-visibility-costmap ?designator ?costmap) (desig:desig-prop ?designator (:location ?location)) + (not (man-int:location-always-reachable ?location)) (btr:bullet-world ?world) (cram-robot-interfaces:robot ?robot) (costmap:costmap ?costmap) @@ -96,19 +103,27 @@ (<- (desig-check-to-see ?desig ?robot-pose) ;; (desig:desig-prop ?desig (:object ?obj)) ;; (desig:desig-location-prop ?desig ?obj-pose) - (desig:desig-prop ?desig (:object ?some-object)) - (desig:current-designator ?some-object ?object) - (lisp-fun man-int:get-object-pose-in-map ?object ?to-see-pose) - (-> (lisp-pred identity ?to-see-pose) - (and (btr:bullet-world ?w) - (cram-robot-interfaces:robot ?robot) - (assert (btr:object-pose ?w ?robot ?robot-pose)) - (btr:object-not-in-collision ?w ?robot) - (cram-robot-interfaces:camera-frame ?robot ?cam-frame) - (btr:head-pointing-at ?w ?robot ?to-see-pose) - (desig:desig-prop ?object (:name ?object-name)) - (-> (btr:object ?w ?object-name) - (btr:visible ?w ?robot ?object-name) + (-> (desig:desig-prop ?desig (:object ?some-object)) + (and (desig:current-designator ?some-object ?object) + (lisp-fun man-int:get-object-pose-in-map ?object ?to-see-pose) + (-> (lisp-pred identity ?to-see-pose) + (and (btr:bullet-world ?w) + (rob-int:robot ?robot) + (assert (btr:object-pose ?w ?robot ?robot-pose)) + ;; There's more to collisions that this, + ;; fancy attachments can exist... + ;; (btr:object-not-in-collision ?w ?robot) + (rob-int:camera-frame ?robot ?cam-frame) + (-> (btr:head-pointing-at ?w ?robot ?to-see-pose) + ;; head-pointing-at is implemented with a simple + ;; internal 2DOF IK solver + ;; if a robot has more than 2DOF in the neck + ;; this will not work + (and (desig:desig-prop ?object (:name ?object-name)) + (-> (btr:object ?w ?object-name) + (btr:visible ?w ?robot ?object-name) + (true))) + (true))) (true))) (true))) diff --git a/cram_3d_world/cram_btr_visibility_costmap/src/location-designator-integration.lisp b/cram_3d_world/cram_btr_visibility_costmap/src/location-designator-integration.lisp index 0b4b29609b..532cd72b08 100644 --- a/cram_3d_world/cram_btr_visibility_costmap/src/location-designator-integration.lisp +++ b/cram_3d_world/cram_btr_visibility_costmap/src/location-designator-integration.lisp @@ -116,7 +116,7 @@ that `designator' tries to reach." (world (bullet:restore-world-state state (make-instance 'btr:bt-reasoning-world :gravity-vector (bullet:gravity-vector state)))) - (robot (btr:object world (btr:get-robot-name)))) + (robot (btr:object world (rob-int:get-robot-name)))) (make-ik-check-function robot (pose-side-properties designator))))))) (funcall cached-function pose)) diff --git a/cram_3d_world/cram_bullet_reasoning/cram-bullet-reasoning-tests.asd b/cram_3d_world/cram_bullet_reasoning/cram-bullet-reasoning-tests.asd index 2115729fa8..15288acfb3 100644 --- a/cram_3d_world/cram_bullet_reasoning/cram-bullet-reasoning-tests.asd +++ b/cram_3d_world/cram_bullet_reasoning/cram-bullet-reasoning-tests.asd @@ -5,13 +5,15 @@ cl-transforms cram-pr2-description cram-robot-interfaces ; for (robot ?robot) + cram-object-knowledge ; for environemnt name + cram-bullet-reasoning-belief-state ; for environment urdf defvar ;;cram-boxy-description roslisp) :components ((:module "tests" :components ((:file "package") - (:file "items-tests" :depends-on ("package")) (:file "objects-tests" :depends-on ("package")) + (:file "items-tests" :depends-on ("package" "objects-tests")) (:file "robot-model-tests" :depends-on ("package")) (:file "robot-model-utils-tests" :depends-on ("package" "robot-model-tests" "objects-tests")) (:file "bounding-box-tests" :depends-on ("package")) diff --git a/cram_3d_world/cram_bullet_reasoning/cram-bullet-reasoning.asd b/cram_3d_world/cram_bullet_reasoning/cram-bullet-reasoning.asd index 5200434b08..63675a4a74 100644 --- a/cram_3d_world/cram_bullet_reasoning/cram-bullet-reasoning.asd +++ b/cram_3d_world/cram_bullet_reasoning/cram-bullet-reasoning.asd @@ -1,10 +1,10 @@ ;;; ;;; Copyright (c) 2010, Lorenz Moesenlechner ;;; All rights reserved. -;;; +;;; ;;; Redistribution and use in source and binary forms, with or without ;;; modification, are permitted provided that the following conditions are met: -;;; +;;; ;;; * Redistributions of source code must retain the above copyright ;;; notice, this list of conditions and the following disclaimer. ;;; * Redistributions in binary form must reproduce the above copyright @@ -14,7 +14,7 @@ ;;; Technische Universitaet Muenchen nor the names of its contributors ;;; may be used to endorse or promote products derived from this software ;;; without specific prior written permission. -;;; +;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" ;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE ;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE @@ -49,10 +49,9 @@ cram-designators roslisp-utilities cram-semantic-map-utils - cram-manipulation-interfaces cram-robot-interfaces cram-occasions-events - cram-utilities ; lazy in pose-generators + cram-utilities ; lazy in pose-generators and with-file-cache cram-occasions-events ; for temporal reasoning cram-tf cram-physics-utils) @@ -64,36 +63,52 @@ (:file "reasoning-world" :depends-on ("package")) (:file "textures" :depends-on ("package")) (:file "utils" :depends-on ("package")) - (:file "objects" :depends-on ("package" "reasoning-world" "textures" "utils")) - (:file "items" :depends-on ("package" "objects" "utils")) + + (:file "objects" :depends-on ("package" "utils" "reasoning-world" "textures")) + (:file "robot-model" :depends-on ("package" "objects" "utils" + "reasoning-world")) + (:file "robot-model-utils" :depends-on ("package" "robot-model")) + (:file "robot-model-facts" :depends-on ("package" "world-facts" + "prolog-handlers" + "robot-model" + "robot-model-utils")) + (:file "items" :depends-on ("package" "objects" "utils" "aabb")) + (:file "aabb" :depends-on ("package" "objects")) + (:file "debug-window" :depends-on ("package")) - (:file "world-utils" :depends-on ("package" "reasoning-world" "objects")) - (:file "world-facts" - :depends-on ("package" "reasoning-world" "items" "objects" "debug-window" "world-utils")) - (:file "prolog-handlers" :depends-on ("package" "reasoning-world" "world-facts")) - (:module "temporal-reasoning" - :depends-on ("package" "reasoning-world" "world-facts" "utils") - :components - ((:file "events") - (:file "timeline" :depends-on ("events")) - (:file "prolog"))) - (:file "pose-generators" :depends-on ("package" "utils" "aabb" "world-facts")) - (:file "pose-sampling-facts" :depends-on ("package" "world-facts" "pose-generators")) - (:file "pose-facts" - :depends-on ("package" "aabb" "world-utils" "pose-generators" "objects" "world-facts")) - (:file "robot-model" :depends-on ("package" "objects" "utils" "reasoning-world")) - (:file "robot-model-utils" :depends-on ("package" "robot-model")) - (:file "robot-model-facts" - :depends-on ("package" "world-facts" "prolog-handlers" "robot-model" "robot-model-utils")) (:file "gl-scenes" :depends-on ("package" "debug-window")) (:file "visibility-reasoning" :depends-on ("package" "gl-scenes")) - (:file "visibility-facts" - :depends-on ("package" "world-facts" "visibility-reasoning" "robot-model-facts")) + (:file "visibility-facts" :depends-on ("package" "world-facts" + "visibility-reasoning" + "robot-model-facts")) + + (:file "world-utils" :depends-on ("package" "reasoning-world" "objects")) + (:file "world-facts" :depends-on ("package" "reasoning-world" "items" + "objects" "debug-window" + "world-utils")) + (:file "prolog-handlers" :depends-on ("package" "reasoning-world" + "world-facts")) + + (:file "pose-generators" :depends-on ("package" "utils" "aabb" "world-facts")) + (:file "pose-sampling-facts" :depends-on ("package" "world-facts" + "pose-generators")) + (:file "pose-facts" :depends-on ("package" "aabb" "world-utils" + "pose-generators" "objects" + "world-facts")) + (:file "semantic-map" :depends-on ("package" "objects" "utils")) (:file "simple-semantic-map" :depends-on ("package" "semantic-map")) - (:file "urdf-semantic-map" - :depends-on ("package" "reasoning-world" "semantic-map" "robot-model")) - (:file "semantic-map-facts" - :depends-on ("package" "semantic-map" "urdf-semantic-map" "world-facts")) - (:file "articulated-objects" :depends-on ("package" "semantic-map")))))) + (:file "urdf-semantic-map" :depends-on ("package" "reasoning-world" + "semantic-map" + "robot-model")) + (:file "semantic-map-facts" :depends-on ("package" "semantic-map" + "urdf-semantic-map" + "world-facts")) + (:file "articulated-objects" :depends-on ("package" "semantic-map")) + + (:module "temporal-reasoning" :depends-on ("package" "reasoning-world" + "world-facts" "utils") + :components ((:file "events") + (:file "timeline" :depends-on ("events")) + (:file "prolog"))))))) diff --git a/cram_3d_world/cram_bullet_reasoning/package.xml b/cram_3d_world/cram_bullet_reasoning/package.xml index 60546e87bd..eb65e7af80 100644 --- a/cram_3d_world/cram_bullet_reasoning/package.xml +++ b/cram_3d_world/cram_bullet_reasoning/package.xml @@ -28,7 +28,6 @@ cram_designators roslisp_utilities cram_semantic_map_utils - cram_manipulation_interfaces cram_robot_interfaces cram_occasions_events cram_utilities diff --git a/cram_3d_world/cram_bullet_reasoning/resource/bowl.dae b/cram_3d_world/cram_bullet_reasoning/resource/bowl.dae new file mode 100644 index 0000000000..479df3e317 --- /dev/null +++ b/cram_3d_world/cram_bullet_reasoning/resource/bowl.dae @@ -0,0 +1,936 @@ + + + + + Blender User + Blender 2.81.16 commit date:2019-11-20, commit time:14:27, hash:26bd5ebd42e3 + + 2019-12-11T14:35:24 + 2019-12-11T14:35:24 + + Z_UP + + + + + + + 39.59775 + 1.777778 + 0.1 + 100 + + + + + + 0 + 0 + 10 + + + + + + + + + 1000 1000 1000 + 1 + 0 + 0.00111109 + + + + + 0 + 0 + 1 + 1 + 1 + 1 + 1 + 0 + 0 + 0 + 1000 + 29.99998 + 75 + 0.15 + 0 + 1 + 2 + 0.04999995 + 30.002 + 1 + 3 + 2880 + 3 + 1 + 1 + 0.1 + 0.1 + 1 + + + + + + + + + + 0.004762947 0.06897699 0.02848595 -0.04438698 0.04887294 0.001641988 -0.043998 0.05567795 0.001895964 -0.043998 0.06010699 0.035142 0.006983995 0.05567795 0.008544981 0.006983995 0.062325 0.03291898 0.006983995 0.06010699 0.001895964 -0.03733998 0.06675899 0.02848595 -0.01739895 0.062325 0.006328999 0.006983995 0.06897699 0.035142 -0.04177194 0.04902595 0.006328999 -0.043998 0.06453996 0.035142 -0.02404099 0.06897699 0.03070199 0.006983995 0.05567795 0.001895964 -0.001883983 0.06675899 0.01741099 -0.043998 0.062325 0.01741099 -0.04177194 0.05789595 0.03070199 -0.02182495 0.06010699 0.001895964 -0.02404099 0.06897699 0.035142 -0.02625697 0.06453996 0.01519399 0.006983995 0.06453996 0.035142 0.004762947 0.06453996 0.01076197 -0.03512495 0.06010699 0.006328999 0.006983995 0.06675899 0.01962 -0.006319999 0.06897699 0.02626997 -0.006319999 0.06675899 0.01741099 -0.03955596 0.04902595 0.001895964 -0.03955596 0.06675899 0.03070199 -0.03733998 0.06010699 0.035142 -0.043998 0.04902595 0.006328999 -0.03955596 0.06675899 0.035142 -0.02404099 0.06675899 0.02183699 + + + + + + + + + + -0.06054806 0.9682791 -0.2424243 1 0 0 0.1188217 -0.9579336 0.2612368 -0.9999326 0 0.01161122 0 0 1 0 1 0 0.004944324 0 -0.9999879 -0.9980089 0.05797696 -0.02483892 -0.9994177 0.03385913 -0.004229784 0.06964296 -0.937424 0.3411541 -0.007536172 0.0377286 -0.9992597 0 0.0226041 -0.9997445 0 0.8943057 -0.4474565 -0.1538386 0.9457524 -0.2861579 5.76874e-5 0.8944333 -0.4472016 -0.2535117 0.8891662 -0.38094 -0.1688752 0.8454434 -0.5066624 -0.1163486 0.9298444 -0.3490735 -0.1163684 0.9300025 -0.3486458 -0.1560374 0.9370233 -0.3124737 0.3903024 0.9114286 -0.1302382 0.057002 0.9717956 -0.2288323 0.4223955 0.848613 -0.3184934 0.06416964 0.9641157 -0.2576105 0 1 1.31707e-6 0.04432582 0.9741092 -0.2216901 -0.07130277 0.9486235 -0.3082684 -0.0232979 0.9360061 -0.351212 0 0.948569 -0.3165706 0 0.9700589 -0.2428697 0.03084129 -0.9994055 0.0154162 0.1319441 -0.9890604 0.06595736 0.06095415 -0.4264591 -0.9024507 0.1414927 -0.9899394 0 -0.1401233 0.9801688 -0.140124 -0.2357376 0.9427914 -0.2357376 -0.5266942 0.8434988 -0.1053718 -0.1415196 0.9899355 0 0 -0.8951519 0.4457613 0.06556689 -0.9178004 0.3915909 0.07067024 -0.706609 0.7040664 -0.9695327 -0.228636 0.08793091 0 -0.9994677 0.03262561 -0.2065435 -0.9132304 0.3512122 0 -0.9397055 0.3419849 -0.4468914 0.8945882 0 -0.1415196 0.9899355 0 -0.1204652 0.963033 -0.2409475 -0.1363208 0.9524031 -0.2726631 -0.06059134 0.968315 -0.2422706 -0.07339477 0.9530261 -0.2938613 + + + + + + + + + + 0.7410212 0.7351642 0.7410212 0.4707164 0.39606 0.6028358 1 0.9336418 1 0.2060596 1 0.007582068 1 0.9336418 1 0.007582068 1 1 1 0.2060596 1 0.9336418 0.05090415 0.1399104 0 0 0.007572352 1 0.007572352 1 0.007572352 1 1 1 0.007572352 1 1 1 0.9567655 0.8013135 0.39606 0.8674627 0 0 1 0.007582068 1 0.007582068 1 0.007582068 1 0.2060596 1 0.007582068 0.007572352 0.007582068 0 0 0.007572352 0.4707164 0 0 0.007572352 1 0.007572352 0.4707164 0.05090415 0.1399104 1 0.9336418 0.05090415 0.8674627 0 0 0.007572352 0.007582068 0.4391972 0.007582068 1 0.007582068 0 0 0.4391972 0.007582068 0.5253548 0.1399104 1 0.007582068 0.4391972 0.007582068 0.007572352 1 1 1 0.39606 1 1 1 0.39606 0.8674627 0.39606 1 0.007572352 0.4707164 0.1371785 0.8013135 0.3529229 0.4045373 1 1 0.007572352 1 1 1 1 0.9336418 1 1 1 1 1 0.007582068 0.5253548 0.1399104 0.9567655 0.2722388 0.007572352 0.007582068 0.007572352 0.4707164 0.1802963 0.1399104 0.4391972 0.007582068 0.007572352 0.007582068 0.1802963 0.1399104 0.5253548 0.1399104 0.4391972 0.007582068 0.1802963 0.1399104 0.3529229 0.4045373 0.5253548 0.1399104 0.1802963 0.1399104 0.007572352 0.4707164 0.3529229 0.4045373 0.1802963 0.1399104 0.9567655 0.8013135 1 1 1 0.5366567 1 1 1 0.007582068 1 0.5366567 0.8273735 0.4707164 0.9567655 0.8013135 1 0.5366567 1 0.007582068 0.9567655 0.2722388 1 0.5366567 0.9567655 0.2722388 0.8273735 0.4707164 1 0.5366567 0.39606 0.8674627 0.9567655 0.8013135 0.7410212 0.7351642 0.9567655 0.8013135 0.8273735 0.4707164 0.7410212 0.7351642 0.5253548 0.1399104 0.3529229 0.4045373 0.7410212 0.4707164 0.9567655 0.2722388 0.5253548 0.1399104 0.7410212 0.4707164 0.8273735 0.4707164 0.9567655 0.2722388 0.7410212 0.4707164 0.7410212 0.7351642 0.8273735 0.4707164 0.7410212 0.4707164 0.05090415 0.1399104 0 0 0.09404134 0.007582068 1 0.2060596 0.05090415 0.1399104 0.09404134 0.007582068 0 0 1 0.007582068 0.09404134 0.007582068 1 0.007582068 1 0.2060596 0.09404134 0.007582068 0.39606 0.8674627 0.1371785 0.8013135 0.09404134 0.8674627 0.1371785 0.8013135 0.007572352 0.4707164 0.09404134 0.8674627 0.007572352 0.4707164 0.007572352 1 0.09404134 0.8674627 0.39606 1 0.39606 0.8674627 0.09404134 0.8674627 0.007572352 1 0.05090415 0.8674627 0.1371785 1 0.05090415 0.8674627 1 0.9336418 0.1371785 1 1 1 0.007572352 1 0.1371785 1 1 0.9336418 1 1 0.1371785 1 0.007572352 1 0 0 0.007572352 0.1399104 0 0 0.05090415 0.1399104 0.007572352 0.1399104 0.05090415 0.8674627 0.007572352 1 0.007572352 0.1399104 0.05090415 0.1399104 0.05090415 0.8674627 0.007572352 0.1399104 0.007572352 1 0.39606 1 0.09404134 1 0.09404134 0.8674627 0.007572352 1 0.09404134 1 0.39606 1 0.09404134 0.8674627 0.09404134 1 0.1371785 0.8013135 0.39606 0.8674627 0.39606 0.6028358 0.3529229 0.4045373 0.1371785 0.8013135 0.39606 0.6028358 0.39606 0.8674627 0.7410212 0.7351642 0.39606 0.6028358 0.7410212 0.4707164 0.3529229 0.4045373 0.39606 0.6028358 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.03955596 0.055673 0.001886963 0.002546966 0.04015898 -0.02692598 -0.02625697 0.04015898 -0.02470898 -0.04177194 0.04015898 -0.00476396 0.006983995 0.05345797 0.001886963 0.006983995 0.05788898 -0.00476396 -0.03290897 0.04680997 -0.01805895 0.006983995 0.04015898 -0.02027595 -0.043998 0.04237896 -0.01584196 -0.043998 0.04680997 0.001886963 -0.008535981 0.06010997 -3.3e-4 -0.01075196 0.05123996 -0.01584196 0.004762947 0.04237896 -0.02692598 -0.03512495 0.05345797 -0.006979942 0.004762947 0.06010997 0.001886963 -0.043998 0.04902899 -0.009196996 -0.02625697 0.04237896 -0.02470898 0.006983995 0.05123996 -0.01584196 -0.043998 0.04015898 -0.01584196 0.006983995 0.04237896 -0.01584196 -0.03512495 0.04237896 -0.02249199 -0.02182495 0.055673 -0.006979942 -0.02847295 0.05788898 -3.3e-4 -0.043998 0.05345797 -3.3e-4 -0.008535981 0.06010997 0.001886963 -0.043998 0.04015898 -0.00476396 -0.02625697 0.04459595 -0.02249199 -0.03955596 0.055673 -3.3e-4 0.006983995 0.04015898 -0.02470898 -0.008535981 0.05788898 -0.00476396 -0.02404099 0.05123996 -0.01362496 -0.04177194 0.04680997 0.001886963 + + + + + + + + + + 0 -0.7071068 0.7071068 0 -1 4.31089e-7 0 -1 -3.70227e-7 1 0 0 0 0 1 0 0 1 0.9280936 0.3098761 0.2064445 0.05021393 0.9522336 -0.3012138 -1 -6.58057e-7 0 -0.2667276 0.8019385 -0.5345569 -0.07674157 0 -0.997051 -0.07110834 0.07098007 -0.99494 1 0 0 0 0.8574179 -0.5146208 0 0.7810822 -0.6244284 0 -1 1.3457e-7 -1 0 0 0.15705 -0.8375096 0.523367 0.1410142 -0.8852501 0.4432238 -0.3188323 0.7452872 -0.5855706 -0.4683979 0.6245064 -0.6249762 -0.2425352 0 -0.9701426 -0.3335338 -0.6659031 -0.6673293 -0.599725 0 -0.8002063 -0.1473492 0.8847619 -0.4421365 -0.1012702 0.909061 -0.4041692 -0.5337745 0.2675195 0.802196 -1 4.23224e-7 0 0 1 0 -0.1362936 0.9528573 0.2710849 -0.110716 0.9938521 0 0 -1 0 -1 7.90008e-7 0 -0.0402494 0.7522131 -0.6576895 -0.05047261 0.7062049 -0.7062063 -0.1849378 0.7397499 -0.6469684 -0.1740776 0.6963098 -0.6963116 -0.2958277 0.829653 -0.4734575 -0.1783084 0.8917831 -0.4158473 -0.1960651 0.9805909 0 -0.4462457 0.8949106 0 -0.4073973 0.8170022 -0.408087 0.4081878 -0.4074516 -0.8169247 0.8144963 0.3624831 -0.4529922 0 0.894104 -0.4478595 0 0.8574176 -0.5146214 -0.05938959 0.8611018 -0.504952 -0.07420825 0.8916397 -0.4466228 -0.1512661 0.833965 -0.5306798 -0.08877223 0.842006 -0.5321141 -0.1406643 0.8446217 -0.5165538 -0.1154106 0.8085496 -0.5769991 -0.09695827 0.807977 -0.5811818 0.09597069 -0.7038428 0.703843 + + + + + + + + + + 0 1 0.04366242 0.7691667 0.04366242 1 0.3479856 0.07694441 0.9129693 0 0.04366242 0.7691667 0.04366242 0.7691667 0.9129693 0 1 0.2307986 1 0.7691667 1 1 1 0.2307986 1 1 0.08712875 1 0 1 0.08712875 1 1 1 0.9564356 1 1 1 1 0.7691667 0.9564356 1 1 0.7691667 0.6955788 0.9230556 0.9564356 1 0 0.3846874 0 1 0 0.6153125 0.1740418 0.692257 0.2175081 0.307743 0 0.6153125 0.9129693 0 0.3479856 0.07694441 0.3479856 0.07694441 0.9564356 0 0.9129693 0 0.3479856 0.07694441 1 0.7691667 1 0.2307986 1 0.3846874 0.6521125 0.3846874 1 0.7691667 1 0.3846874 0.9564356 0 0.6521125 0.3846874 1 0.3846874 0.3479856 0.07694441 0.04366242 0.7691667 0 0.3846874 0 1 0 0.3846874 0 0.3846874 1 1 0.04366242 0.7691667 1 0.3846874 0.04366242 0.7691667 1 0.2307986 1 0.3846874 1 0.2307986 1 1 1 0.3846874 0 0.6153125 0.2175081 0.307743 0.1740418 0.1538888 0 0.3846874 0 0.6153125 0.1740418 0.1538888 0.3479856 0.07694441 0.3479856 0.07694441 0.1740418 0.1538888 0.3479856 0.07694441 0 0.3846874 0.1740418 0.1538888 0 0.3846874 0 0.3846874 0.1740418 0.1538888 0.4349182 0.692257 0.1740418 0.692257 0.3045192 0.9230556 0.6955788 0.9230556 0.4349182 0.692257 0.3045192 0.9230556 0 1 0.08712875 1 0 0.9230556 0 0.6153125 0 1 0 0.9230556 0.08712875 1 0.9564356 1 0.6955788 1 0.9564356 1 0.6955788 0.9230556 0.6955788 1 0.3045192 0.9230556 0.08712875 1 0.6955788 1 0.6955788 0.9230556 0.3045192 0.9230556 0.6955788 1 0.04366242 0.7691667 0 1 0 0.7691667 0 0.3846874 0.04366242 0.7691667 0 0.7691667 0 1 0 0.3846874 0 0.7691667 0.6521125 0.3846874 0.9564356 0 0.3479856 0.1538888 0.9564356 0 0.3479856 0.07694441 0.3479856 0.1538888 0.1740418 0.1538888 0.2175081 0.307743 0.3479856 0.1538888 0.3479856 0.07694441 0.1740418 0.1538888 0.3479856 0.1538888 0.1740418 0.692257 0 0.6153125 0.08712875 0.9230556 0.3045192 0.9230556 0.1740418 0.692257 0.08712875 0.9230556 0.08712875 1 0.3045192 0.9230556 0.08712875 0.9230556 0 0.9230556 0.08712875 1 0.08712875 0.9230556 0 0.6153125 0 0.9230556 0.08712875 0.9230556 1 0.2307986 0.9129693 0 1 0.07694441 0.9129693 0 0.9564356 0 1 0.07694441 1 0.3846874 1 0.2307986 1 0.07694441 0.9564356 0 1 0.3846874 1 0.07694441 0.6955788 0.9230556 1 0.7691667 0.6955788 0.7691667 1 0.7691667 0.6521125 0.3846874 0.6955788 0.7691667 0.6521125 0.3846874 0.4349182 0.692257 0.6955788 0.7691667 0.4349182 0.692257 0.6955788 0.9230556 0.6955788 0.7691667 0.2175081 0.307743 0.1740418 0.692257 0.3914519 0.4616319 0.4349182 0.692257 0.6521125 0.3846874 0.3914519 0.4616319 0.1740418 0.692257 0.4349182 0.692257 0.3914519 0.4616319 0.3479856 0.1538888 0.2175081 0.307743 0.3914519 0.4616319 0.6521125 0.3846874 0.3479856 0.1538888 0.3914519 0.4616319 0.04366242 0.7691667 1 1 0.04366242 1 1 1 0 1 0.04366242 1 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.004099965 0.033499 -0.03357899 -0.03291398 -0.008610963 -0.03135997 -0.03069096 0.020199 -0.03357899 -0.03452295 0.04212599 -0.01743596 0.006988942 -0.008610963 -0.024715 0.007059991 0.04024595 -0.022484 0.006988942 -0.008610963 -0.03135997 -0.03291398 -0.008610963 -0.024715 -0.02626198 0.04015898 -0.02692598 0.006988942 0.03572398 -0.03135997 -0.03291398 0.03128898 -0.03135997 -0.007980942 0.04319596 -0.01959097 0.002547979 0.02907395 -0.03357899 -0.02626198 0.03793895 -0.01806199 -0.01960998 0.03128898 -0.03357899 -0.03291398 0.04015898 -0.024715 -0.02182894 0.03572398 -0.03135997 -0.03069096 0.02685397 -0.03357899 0.006988942 0.03572398 -0.02249497 + + + + + + + + + + 0.1878663 -0.005338609 0.9821802 0.9999991 -0.001453161 0 0 -0.07679438 -0.997047 0 -1 0 -0.9994976 -0.03169655 0 0 -0.1420113 0.9898651 0.9999681 0 -0.007998824 -0.7064692 0 -0.7077438 -0.9933897 0 -0.1147918 -0.05939292 0.9659265 -0.2519101 0.08695292 0.8873721 -0.4527803 0.05111622 0.8712681 -0.4881383 0 0 -1 0.01521599 -0.05698716 -0.998259 0.4469709 0 -0.8945485 0.1481588 0.2225903 -0.9635884 0.005183994 -0.1378518 0.9904393 0.08052676 0.00986284 0.9967037 0.1026908 -0.06847608 0.9923537 -0.09266382 0.9558718 -0.2787878 -0.9449427 0.1961994 -0.2618953 -0.2570726 0.5794167 -0.7734274 0 0.7070268 -0.7071868 0 0.7061513 -0.708061 -0.2264808 0.5660745 -0.7926324 -0.06018692 0.4223971 -0.9044104 -0.1521573 0.3803076 -0.9122579 -0.7064694 0 -0.7077437 -0.1521649 0.3801895 -0.9123057 0.9496355 -0.01567131 0.3129649 0.1664291 -0.04931318 0.9848196 + + + + + + + + + + 0.9430579 1 1 0.6382897 0.8557724 0.9982926 0.9430579 1 0 0.9982926 0 0.9982926 0 0.03869366 0.5561025 0.09215301 0 0.9982926 0 0.9982926 0 0.03869366 0 0.9982926 0.9793464 0 0 0.03869366 0 0.03869366 0 0.9982926 0.9793464 0 0 0.03869366 0 0.03869366 0 0.9982926 0 0.03869366 0.9430579 1 0 0.9982926 0.8557724 0.9982926 0.5561025 0.09215301 0 0.03869366 0.7701662 0.03869366 0 0.03869366 0.9793464 0 0.7701662 0.03869366 0.9413786 0.1986629 0.9793464 0 1 0.6382897 0.9430579 1 0.8557724 0.9982926 1 0.6382897 0.8557724 0.9982926 0.9413786 0.1986629 1 0.6382897 0.5561025 0.09215301 0.8128246 0.7316211 0.7274113 0.8914941 0 0.9982926 0.5561025 0.09215301 0.7274113 0.8914941 0.8557724 0.9982926 0 0.9982926 0.7274113 0.8914941 0.8128246 0.7316211 0.8557724 0.9982926 0.7274113 0.8914941 0.9793464 0 0 0.9982926 0.8985272 0.1986629 1 0.6382897 0.9793464 0 0.8985272 0.1986629 0 0.9982926 1 0.6382897 0.8985272 0.1986629 0.8128246 0.7316211 0.5561025 0.09215301 0.7701662 0.3586322 0.9793464 0 0.9413786 0.1986629 0.9413786 0.03869366 0.7701662 0.03869366 0.9793464 0 0.9413786 0.03869366 0.9413786 0.1986629 0.7701662 0.03869366 0.9413786 0.03869366 0.9413786 0.1986629 0.8557724 0.9982926 0.8557724 0.305269 0.8557724 0.9982926 0.8128246 0.7316211 0.8557724 0.305269 0.7701662 0.03869366 0.9413786 0.1986629 0.8557724 0.305269 0.8128246 0.7316211 0.7701662 0.3586322 0.8557724 0.305269 0.7701662 0.3586322 0.7701662 0.03869366 0.8557724 0.305269 0.5561025 0.09215301 0.7701662 0.03869366 0.68456 0.09215301 0.7701662 0.3586322 0.5561025 0.09215301 0.68456 0.09215301 0.7701662 0.03869366 0.7701662 0.3586322 0.68456 0.09215301 0 0.9982926 0.9430579 1 0.8557724 0.9982926 1 0.6382897 0 0.9982926 0.8557724 0.9982926 + + + + + + + + + + + + + + +

5 0 0 11 0 1 18 0 2 5 1 3 4 1 4 6 1 5 1 2 6 2 2 7 6 2 8 4 3 9 1 3 10 6 3 11 3 4 12 1 4 13 7 4 14 4 5 15 3 5 16 7 5 17 1 3 18 4 3 19 7 3 20 5 6 21 6 6 22 9 6 23 2 7 24 1 7 25 10 7 26 1 8 27 3 8 28 10 8 29 8 9 30 3 9 31 11 9 32 5 10 33 9 10 34 11 10 35 9 11 36 8 11 37 11 11 38 2 12 39 0 12 40 12 12 41 6 13 42 2 13 43 12 13 44 9 14 45 6 14 46 12 14 47 0 15 48 9 15 49 12 15 50 3 16 51 4 16 52 13 16 53 11 17 54 3 17 55 13 17 56 4 18 57 11 18 58 13 18 59 0 12 60 2 12 61 14 12 62 3 19 63 8 19 64 15 19 65 10 20 66 3 20 67 15 20 68 8 21 69 10 21 70 15 21 71 8 22 72 9 22 73 16 22 74 9 23 75 0 23 76 16 23 77 10 24 78 8 24 79 16 24 80 0 25 81 14 25 82 16 25 83 14 26 84 10 26 85 16 26 86 2 27 87 10 27 88 17 27 89 14 12 90 2 12 91 17 12 92 10 28 93 14 28 94 17 28 95 4 29 96 5 29 97 18 29 98 11 30 99 4 30 100 18 30 101

+
+
+
+ + + + -0.03513199 0.00247395 -0.03136199 -0.04177898 0.04015898 -0.006977975 -0.043998 0.04015898 -0.006977975 -0.04177898 -0.008610963 -0.01806199 -0.043998 0.02242398 -0.02470797 -0.03291398 0.04015898 -0.01584696 -0.03291398 -0.008610963 -0.02470797 -0.03291398 0.03572398 -0.02692794 -0.043998 -0.006390988 -0.02692794 -0.043998 0.04015898 -0.01806199 -0.03513199 0.02685397 -0.03136199 -0.03291398 -0.008610963 -0.029145 -0.043998 -0.008610963 -0.01806199 -0.03291398 0.02685397 -0.03136199 -0.04177898 0.03793895 -0.006977975 -0.03734797 0.04015898 -0.022493 -0.039563 -0.008610963 -0.029145 -0.039563 0.03572398 -0.02470797 -0.039563 0.020199 -0.029145 -0.03291398 0.03793895 -0.01584696 -0.04177898 0.03128898 -0.02470797 -0.03291398 0.00247395 -0.03136199 + + + + + + + + + + 1 0 0 0 1 0 1 0 0 -1 0 0 -1 2.9611e-7 0 -0.4472939 0 -0.8943871 0 -1 0 -1 -1.27369e-7 0 0 0.4471337 -0.8944672 0 0 -1 0 0 1 0.7072669 0 0.7069467 0.5892429 -0.1871498 0.7859821 -0.2164615 -0.2163648 0.9520141 0 -0.2316334 0.9728031 0.4865728 0.811089 -0.3246254 0 1 -4.55866e-7 -0.4471862 -1.34132e-4 -0.8944409 0 -0.1961159 -0.9805807 -0.5188856 -0.8292431 -0.2076383 0 -1 0 -0.2771031 0.4841668 -0.8299376 -0.2677261 0.5341865 -0.8018525 -0.4558503 0.5693514 -0.6841342 -0.6921404 0.05544251 -0.7196303 -0.4475626 8.95976e-5 -0.8942527 0.7072657 0 0.7069478 0.7009479 -0.1333684 0.7006317 -0.8141059 0.2037792 -0.5437883 -0.666494 0.3330201 -0.6669958 -0.5750706 0.2873408 -0.7659826 -0.6553409 0.1640392 -0.7373056 -0.6365355 0.1734695 -0.7514859 0 -0.1961166 -0.9805807 + + + + + + + + + + 0.7271888 0 0 0.09092026 0.2272914 0 1 1 1 1 1 0.6362779 1 0.6362779 0 0.2728838 0.9090629 0.1818405 1 1 0.6363543 0.2728838 0.04551976 0.1818405 0.6363543 0.2728838 1 1 1 0.5454397 1 1 1 0.6362779 1 0.5454397 0.2272914 0 0.04551976 0.1818405 0.7271888 0 0 0.2728838 0 0.5454397 0 0.09092026 0.9090629 0.1818405 0 0.2728838 0 0.09092026 1 1 0.04551976 0.1818405 0 0.5454397 0 0.09092026 0 0.5454397 0 0.5454397 0.7271888 0 0.9090629 0.1818405 0.7271888 0 0.2272914 0 0.7271888 0 0.7271888 0 0.9090629 0.1818405 0 0.09092026 0.7271888 0 1 1 1 1 0.9544802 1 1 0.6362779 1 1 0.9544802 1 0 0.5454397 0 0.2728838 0.9544802 1 1 1 0 0.5454397 0.9544802 1 0 0.5454397 0 0.5454397 0.9544802 1 1 0.6362779 0.9090629 0.1818405 1 0.3637221 1 0.5454397 1 0.6362779 1 0.3637221 0.04551976 0.1818405 0.2272914 0 0 0.09092026 0.2272914 0 0 0.09092026 0 0.09092026 0 0.5454397 0.04551976 0.1818405 0 0.09092026 0 0.09092026 0 0.5454397 0 0.09092026 0.9090629 0.1818405 0.7271888 0 0.9090629 0.2728838 1 0.3637221 0.9090629 0.1818405 0.9090629 0.2728838 1 0.5454397 1 0.3637221 0.9090629 0.2728838 0.04551976 0.1818405 0.6363543 0.2728838 0.590732 0.09092026 0.7271888 0 0.04551976 0.1818405 0.590732 0.09092026 0 0.2728838 1 0.6362779 0.9544802 0.6362779 1 0.6362779 0.9544802 1 0.9544802 0.6362779 0.9544802 1 0 0.2728838 0.9544802 0.6362779 0.6363543 0.2728838 1 0.5454397 0.8181259 0.2728838 1 0.5454397 0.9090629 0.2728838 0.8181259 0.2728838 0.9090629 0.2728838 0.7271888 0 0.8181259 0.2728838 0.590732 0.09092026 0.6363543 0.2728838 0.8181259 0.2728838 0.7271888 0 0.590732 0.09092026 0.8181259 0.2728838 0 0.09092026 0.2272914 0 0.2272914 0 0.2272914 0 0.7271888 0 0.2272914 0 + + + + + + + + + + + + + + +

13 0 0 11 0 1 21 0 2 2 1 3 1 1 4 5 1 5 5 2 6 6 2 7 7 2 8 2 3 9 4 3 10 8 3 11 4 4 12 2 4 13 9 4 14 2 1 15 5 1 16 9 1 17 0 5 18 8 5 19 10 5 20 6 6 21 3 6 22 11 6 23 7 0 24 6 0 25 11 0 26 2 7 27 8 7 28 12 7 29 11 6 30 3 6 31 12 6 32 10 8 33 7 8 34 13 8 35 0 9 36 10 9 37 13 9 38 7 0 39 11 0 40 13 0 41 1 10 42 2 10 43 14 10 44 5 11 45 1 11 46 14 11 47 3 12 48 6 12 49 14 12 50 2 13 51 12 13 52 14 13 53 12 14 54 3 14 55 14 14 56 5 15 57 7 15 58 15 15 59 9 16 60 5 16 61 15 16 62 8 17 63 0 17 64 16 17 65 0 18 66 11 18 67 16 18 68 12 19 69 8 19 70 16 19 71 11 20 72 12 20 73 16 20 74 7 21 75 10 21 76 17 21 77 15 22 78 7 22 79 17 22 80 9 23 81 15 23 82 17 23 83 8 24 84 4 24 85 18 24 86 10 25 87 8 25 88 18 25 89 6 0 90 5 0 91 19 0 92 5 26 93 14 26 94 19 26 95 14 27 96 6 27 97 19 27 98 4 28 99 9 28 100 20 28 101 9 29 102 17 29 103 20 29 104 17 30 105 10 30 106 20 30 107 18 31 108 4 31 109 20 31 110 10 32 111 18 32 112 20 32 113 11 33 114 0 33 115 21 33 116 0 9 117 13 9 118 21 9 119

+
+
+
+ + + + 0.02249896 -0.035209 -0.03357899 0.04371994 -0.00783199 -0.02010196 -0.004094958 -0.008613944 -0.02470898 0.04245799 -0.03742897 -0.01362794 -0.00593096 -0.03856498 -0.02479594 -0.004094958 -0.008613944 -0.03135895 0.03579998 -0.03742897 -0.02914196 0.03358995 -0.008613944 -0.03135895 -0.004094958 -0.035209 -0.03357899 0.04245799 -0.02634096 -0.02692598 0.04023396 -0.032992 -0.01362794 0.02915596 -0.02412396 -0.03357899 0.04245799 -0.03742897 -0.02249795 0.04023396 -0.008613944 -0.02914196 0.03579998 -0.02855795 -0.03135895 -0.004094958 -0.03742897 -0.03135895 0.02915596 -0.03742897 -0.03135895 3.39e-4 -0.03077495 -0.03357899 0.02693694 -0.032992 -0.03357899 0.04023396 -0.035209 -0.02692598 0.03579998 -0.01304799 -0.03135895 0.04023396 -0.03742897 -0.01362794 + + + + + + + + + + -0.2351323 0 0.9719635 -0.01635247 0.9998663 0 -0.9981265 0.06118524 0 0 0.9975959 -0.06930088 -0.9799571 0.01657122 -0.1985186 -0.09681457 0.260585 0.9605844 0.3667758 0.1838424 0.9119637 -0.2364473 0.01167201 0.9715743 0 0.1416895 -0.9899112 0 0 -1 0.9990922 -0.04260087 0 0.02346986 -0.9997246 0 0.02463442 -0.9993917 -0.02468621 0.9954622 -0.03529191 -0.08837282 0.03294783 0.9945677 -0.0987398 0.9286025 0.07097029 -0.3642264 0.5614806 -0.03291761 -0.8268349 0 -0.7071066 -0.7071071 -0.9020707 -0.3051787 -0.3051792 0.0207023 -0.9978589 -0.06204265 0 -0.7071084 -0.7071052 0 -0.985348 -0.1705561 -0.08289885 0.08289873 -0.9931041 -0.02199435 0.09529513 -0.9952061 0.2746115 -0.06871438 -0.9590969 0.342296 -0.227812 -0.9115564 0.3017892 -0.3015865 -0.9044163 0.1825391 -0.3654059 -0.912775 0.5775222 -0.5757858 -0.578739 0.8283802 -0.2077494 -0.5202179 0.5184234 -0.2073311 -0.8296089 0.5814704 -0.1458269 -0.8003916 0.1788187 0.08912646 -0.979837 0.3126602 0.1558358 -0.9369946 0.316913 0 -0.9484547 0.4472128 0 -0.8944277 0 -0.9948664 0.1011979 0 0 1 + + + + + + + + + + 0.92979 0.181336 0 0 0.92979 0.03696352 0.03697806 0.974555 1 1 0.03697806 0.974555 0 0 0.03697806 0.974555 0.03697806 0.974555 0.03697806 0.974555 1 1 0.7959759 0.974555 0 0 0.03697806 0.974555 0.03697806 0.1091986 1 1 0.03697806 0.974555 0.92979 0.181336 0.9745826 0.03696352 1 1 0.92979 0.181336 0.03697806 0.974555 0 0 0.92979 0.181336 0.03697806 0.974555 0.7959759 0.974555 0.7066726 0.4698858 0.5725967 0.1091986 0.03697806 0.1091986 0.7066726 0.4698858 1 1 0.9745826 0.03696352 0.9745826 0.03696352 0.9745826 0.03696352 0 0 0.9745826 0.03696352 0 0 0.8404866 0.03696352 0.9745826 0.03696352 0.9745826 0.3977484 1 1 0.9745826 0.03696352 0.7959759 0.974555 1 1 0.92979 0.974555 1 1 0.9745826 0.3977484 0.92979 0.974555 0.92979 0.974555 0.9745826 0.3977484 0.8404866 0.3256109 0.03697806 0.1091986 0.5725967 0.1091986 0.03697806 0.03696352 0 0 0.03697806 0.1091986 0.03697806 0.03696352 0.8404866 0.03696352 0 0 0.7066726 0.03696352 0.03697806 0.03696352 0.5725967 0.1091986 0.7066726 0.03696352 0 0 0.03697806 0.03696352 0.7066726 0.03696352 0.03697806 0.1091986 0.03697806 0.974555 0.1262814 0.2534735 0.03697806 0.974555 0.7066726 0.4698858 0.1262814 0.2534735 0.7066726 0.4698858 0.03697806 0.1091986 0.1262814 0.2534735 0.5725967 0.1091986 0.7066726 0.4698858 0.6619806 0.181336 0.7066726 0.4698858 0.8404866 0.3256109 0.6619806 0.181336 0.8404866 0.3256109 0.8404866 0.03696352 0.6619806 0.181336 0.8404866 0.03696352 0.7066726 0.03696352 0.6619806 0.181336 0.7066726 0.03696352 0.5725967 0.1091986 0.6619806 0.181336 0.9745826 0.03696352 0.8404866 0.03696352 0.92979 0.1091986 0.9745826 0.3977484 0.9745826 0.03696352 0.92979 0.1091986 0.8404866 0.03696352 0.8404866 0.3256109 0.92979 0.1091986 0.8404866 0.3256109 0.9745826 0.3977484 0.92979 0.1091986 0.7066726 0.4698858 0.7959759 0.974555 0.8404866 0.8302801 0.7959759 0.974555 0.92979 0.974555 0.8404866 0.8302801 0.8404866 0.3256109 0.7066726 0.4698858 0.8404866 0.8302801 0.92979 0.974555 0.8404866 0.3256109 0.8404866 0.8302801 0 0 0.9745826 0.03696352 0.92979 0.03696352 0.9745826 0.03696352 0.92979 0.181336 0.92979 0.03696352 + + + + + + + + + + + + + + +

10 0 0 4 0 1 21 0 2 2 1 3 1 1 4 5 1 5 4 2 6 2 2 7 5 2 8 5 3 9 1 3 10 7 3 11 4 4 12 5 4 13 8 4 14 1 5 15 2 5 16 10 5 17 3 6 18 1 6 19 10 6 20 2 7 21 4 7 22 10 7 23 5 8 24 7 8 25 11 8 26 0 9 27 8 9 28 11 9 29 1 10 30 3 10 31 12 10 32 3 11 33 4 11 34 12 11 35 4 12 36 6 12 37 12 12 38 9 13 39 1 13 40 12 13 41 7 14 42 1 14 43 13 14 44 1 15 45 9 15 46 13 15 47 13 16 48 9 16 49 14 16 50 8 17 51 0 17 52 15 17 53 4 18 54 8 18 55 15 18 56 6 19 57 4 19 58 16 19 59 15 20 60 0 20 61 16 20 62 4 21 63 15 21 64 16 21 65 8 22 66 5 22 67 17 22 68 5 23 69 11 23 70 17 23 71 11 9 72 8 9 73 17 9 74 0 9 75 11 9 76 18 9 77 11 24 78 14 24 79 18 24 80 14 25 81 6 25 82 18 25 83 6 26 84 16 26 85 18 26 86 16 27 87 0 27 88 18 27 89 12 28 90 6 28 91 19 28 92 9 29 93 12 29 94 19 29 95 6 30 96 14 30 97 19 30 98 14 31 99 9 31 100 19 31 101 11 32 102 7 32 103 20 32 104 7 33 105 13 33 106 20 33 107 14 34 108 11 34 109 20 34 110 13 35 111 14 35 112 20 35 113 4 36 114 3 36 115 21 36 116 3 37 117 10 37 118 21 37 119

+
+
+
+ + + + 0.04245799 -0.04407799 -0.02027595 -0.004094958 -0.03964698 -0.03136199 -0.004094958 -0.04629498 -0.02692598 0.04023396 -0.04407799 -0.004762947 0.04245799 -0.03742897 -0.01141297 -0.004094958 -0.04407799 -0.01584696 0.03136599 -0.03742897 -0.02914094 -0.004094958 -0.03742897 -0.02249199 0.04245799 -0.04629498 -0.004762947 0.02693694 -0.04629498 -0.02470695 -0.004094958 -0.04629498 -0.01584696 0.02028399 -0.03964698 -0.03136199 -0.004094958 -0.03742897 -0.03136199 0.04245799 -0.03742897 -0.02249199 0.04245799 -0.04629498 -0.01806294 0.03358995 -0.04186195 -0.02692598 0.04023396 -0.03742897 -0.01141297 0.006991982 -0.04629498 -0.02692598 0.04023396 -0.03964698 -0.02470695 0.02028399 -0.03742897 -0.03136199 + + + + + + + + + + 0 0 -1 -1 0 0 0 1 3.31477e-7 -1 -1.48055e-7 0 -0.174155 0.6960914 0.6965104 1 0 0 0.5133209 0.5149433 0.6865385 0 -1 3.98368e-7 -1 0 0 -0.2425715 0 0.9701336 0 -1 0 -0.2256099 -0.2263225 0.9475645 0 -0.5550469 -0.8318191 0 1 0 1 -3.95087e-7 0 1 3.94815e-6 0 0.2712925 -0.7243922 -0.6337637 0.2485913 -0.3302595 -0.9105663 0.1542966 -0.6176044 -0.7712051 0.3338673 -0.6659324 -0.6671332 0 0.7071593 0.7070543 -0.1740155 0.6963709 0.6962659 0 -1 -4.73194e-6 0 -0.5550467 -0.8318192 0.08283412 -0.6624241 -0.7445353 0.783334 -0.1965417 -0.5897112 0.4866271 0.322759 -0.811801 0.3813056 -0.2529814 -0.8891605 0.4220069 -0.5263417 -0.7381563 0.1965078 0 -0.9805023 0 1 -1.07502e-6 + + + + + + + + + + 0.5236827 0 0 0 0.5236827 0 0 0 0 0.1667732 0 0.5832926 1 0.7499906 0.761734 0.08349937 0 0.3334712 0 0 0 0.5832926 0 0.3334712 0 0.5832926 0.9522265 1 0 0.3334712 1 0.4167826 1 0.7499906 1 1 1 0.7499906 0.9522265 1 1 1 1 1 0 0.1667732 0.6665951 0.2501974 0 0.5832926 0 0.1667732 0 0.5832926 0.9522265 1 0 0.5832926 0 0.5832926 0 0.1667732 1 1 0 0.5832926 1 1 0.9522265 1 0 0.5832926 0 0.1667732 0 0 0.5236827 0 0 0.3334712 0.761734 0.08349937 0 0 0 0 0 0.3334712 0 0 0.5236827 0 0 0 0 0 1 0.7499906 1 0.4167826 1 0.3334712 0.761734 0.08349937 1 0.7499906 1 0.3334712 1 0.4167826 1 1 1 0.4999812 1 1 0.6665951 0.2501974 1 0.4999812 1 0.4999812 0.6665951 0.2501974 0.8095074 0.1667732 0.5236827 0 0.761734 0.08349937 0.8095074 0.1667732 0.6665951 0.2501974 0.5236827 0 0.8095074 0.1667732 1 0.4167826 1 0.4999812 0.8095074 0.1667732 0.9522265 1 1 0.7499906 0.9522265 0.7499906 1 0.7499906 0 0.3334712 0.9522265 0.7499906 0 0.3334712 0.9522265 1 0.9522265 0.7499906 0.6665951 0.2501974 0 0.1667732 0.2381587 0.1667732 0 0.1667732 0.5236827 0 0.2381587 0.1667732 0.5236827 0 0.6665951 0.2501974 0.2381587 0.1667732 1 0.3334712 1 0.4167826 0.9522265 0.2501974 0.761734 0.08349937 1 0.3334712 0.9522265 0.2501974 0.8095074 0.1667732 0.761734 0.08349937 0.9522265 0.2501974 1 0.4167826 0.8095074 0.1667732 0.9522265 0.2501974 0.761734 0.08349937 0.5236827 0 0.5236827 0 0 0 0.761734 0.08349937 0.5236827 0 + + + + + + + + + + + + + + +

11 0 0 12 0 1 19 0 2 1 1 3 2 1 4 5 1 5 4 2 6 6 2 7 7 2 8 1 3 9 5 3 10 7 3 11 5 4 12 3 4 13 7 4 14 0 5 15 4 5 16 8 5 17 4 6 18 3 6 19 8 6 20 8 7 21 2 7 22 9 7 23 5 8 24 2 8 25 10 8 26 3 9 27 5 9 28 10 9 29 2 10 30 8 10 31 10 10 32 8 11 33 3 11 34 10 11 35 2 12 36 1 12 37 11 12 38 7 13 39 6 13 40 12 13 41 1 8 42 7 8 43 12 8 44 11 0 45 1 0 46 12 0 47 4 14 48 0 14 49 13 14 50 6 13 51 4 13 52 13 13 53 0 15 54 8 15 55 14 15 56 8 10 57 9 10 58 14 10 59 14 16 60 9 16 61 15 16 62 11 17 63 6 17 64 15 17 65 9 18 66 11 18 67 15 18 68 0 19 69 14 19 70 15 19 71 3 20 72 4 20 73 16 20 74 4 13 75 7 13 76 16 13 77 7 21 78 3 21 79 16 21 80 9 22 81 2 22 82 17 22 83 2 23 84 11 23 85 17 23 86 11 24 87 9 24 88 17 24 89 13 25 90 0 25 91 18 25 92 6 26 93 13 26 94 18 26 95 15 27 96 6 27 97 18 27 98 0 28 99 15 28 100 18 28 101 6 29 102 11 29 103 19 29 104 12 30 105 6 30 106 19 30 107

+
+
+
+ + + + -0.02626198 -0.02413195 -0.03357899 -0.03291398 -0.04407995 -0.02470898 -0.03291398 -0.04407995 -0.01362794 -0.004094958 -0.04407995 -0.01806497 -0.03291398 -0.008613944 -0.02470898 -0.004094958 -0.008613944 -0.02470898 -0.004094958 -0.03520995 -0.03357899 -0.004094958 -0.008613944 -0.03135895 -0.03291398 -0.008613944 -0.03135895 -0.03291398 -0.03520995 -0.03135895 -0.004094958 -0.04407995 -0.02692598 -0.02626198 -0.04185795 -0.01362794 -0.01074695 -0.03742498 -0.03357899 -0.03069597 -0.02855795 -0.03357899 -0.02404195 -0.04407995 -0.02692598 -0.004094958 -0.04185795 -0.01806497 -0.02182495 -0.03520995 -0.03357899 -0.03291398 -0.04185795 -0.01362794 -0.02847599 -0.03742498 -0.03135895 -0.004094958 -0.03299099 -0.03357899 + + + + + + + + + + 1 0 0 0 -1 0 -1 0 0 1 0 0 0 1 0 1 0 0 0 0.1416178 -0.9899214 1 -1.85146e-7 0 0.1384768 -0.4145577 0.8994254 0 0.3162192 0.9486863 -3.5553e-7 0 -1 0.1959267 -0.5883989 -0.784474 -0.09902209 0.09920054 -0.9901283 -0.7074243 0 -0.7067892 4.56135e-7 0 -1 0 -1 1.31624e-6 0 -0.7070007 -0.7072129 0.1962692 0 0.9805501 0.1926057 0.1923105 0.9622473 -0.189904 -0.2532528 -0.9485777 -2.69273e-7 0 -1 0 0 1 0 0.3162192 0.9486863 -0.2868095 -0.5746543 -0.766494 -0.1885912 -0.628373 -0.7547057 -0.09969764 -0.5967782 -0.7961885 -0.1826807 -0.3660218 -0.9124999 -0.1055323 -0.5278038 -0.8427847 0 0 -1 0.03622192 0.09063464 -0.9952254 + + + + + + + + + + 1 1 0.2500987 1 0.3126657 1 0 0 0 0 0 1 0 0 0 0 1 0 1 1 0 1 0.2500987 1 1 0 1 1 1 1 1 1 0.2500987 1 1 1 0 0 1 0 1 0 1 1 0.5624542 0.2308199 1 0 1 0 1 1 1 0 0 0 1 0 0.2500987 0 0 1 0 0 0 1 0.2500987 1 0 1 0 1 0 0 0 1 0.06265151 0.2308199 1 1 1 0 0.06265151 0.2308199 0.5624542 0.2308199 0.2500987 1 0.1876445 0.7691801 0.2500987 1 0 1 0.1876445 0.7691801 1 0 0.5624542 0.2308199 0.4376586 0.07696306 0.2500987 0 1 0 0.4376586 0.07696306 0.5624542 0.2308199 0.1876445 0.7691801 0.4376586 0.07696306 0 1 0 0 0 0.3078525 0.1876445 0.7691801 0 1 0 0.3078525 0 1 1 1 0.06265151 1 0.06265151 0.2308199 0 1 0.06265151 1 1 1 0.06265151 0.2308199 0.06265151 1 0.2500987 0 0.4376586 0.07696306 0.2500987 0.3847809 0.4376586 0.07696306 0.1876445 0.7691801 0.2500987 0.3847809 1 0 0 0 0.06265151 0 0 0 0.06265151 0.2308199 0.06265151 0 0.06265151 0.2308199 1 0 0.06265151 0 0 0 0.2500987 0 0.1876445 0.1539956 0 0.3078525 0 0 0.1876445 0.1539956 0.1876445 0.7691801 0 0.3078525 0.1876445 0.1539956 0.2500987 0 0.2500987 0.3847809 0.1876445 0.1539956 0.2500987 0.3847809 0.1876445 0.7691801 0.1876445 0.1539956 0.2500987 1 0.5624542 0.2308199 0.3126657 1 0.5624542 0.2308199 1 1 0.3126657 1 + + + + + + + + + + + + + + +

7 0 0 6 0 1 19 0 2 2 1 3 1 1 4 3 1 5 1 2 6 2 2 7 4 2 8 5 3 9 3 3 10 6 3 11 4 4 12 5 4 13 7 4 14 5 5 15 6 5 16 7 5 17 1 2 18 4 2 19 8 2 20 7 6 21 0 6 22 8 6 23 4 4 24 7 4 25 8 4 26 1 2 27 8 2 28 9 2 29 3 1 30 1 1 31 10 1 32 6 7 33 3 7 34 10 7 35 2 8 36 3 8 37 11 8 38 5 9 39 4 9 40 11 9 41 0 10 42 6 10 43 12 10 44 6 11 45 10 11 46 12 11 47 8 12 48 0 12 49 13 12 50 9 13 51 8 13 52 13 13 53 0 14 54 12 14 55 13 14 56 10 15 57 1 15 58 14 15 59 12 16 60 10 16 61 14 16 62 3 0 63 5 0 64 15 0 65 11 17 66 3 17 67 15 17 68 5 18 69 11 18 70 15 18 71 9 19 72 13 19 73 16 19 74 13 20 75 12 20 76 16 20 77 4 2 78 2 2 79 17 2 80 2 21 81 11 21 82 17 21 83 11 22 84 4 22 85 17 22 86 1 23 87 9 23 88 18 23 89 14 24 90 1 24 91 18 24 92 12 25 93 14 25 94 18 25 95 9 26 96 16 26 97 18 26 98 16 27 99 12 27 100 18 27 101 6 28 102 0 28 103 19 28 104 0 29 105 7 29 106 19 29 107

+
+
+
+ + + + -0.03513199 -0.03077697 -0.03136199 -0.04177898 -0.04185795 -0.004762947 -0.043998 -0.04185795 -0.004762947 -0.04177898 -0.008613944 -0.01806294 -0.03291398 -0.04185795 -0.01141297 -0.043998 -0.04407995 -0.01806294 -0.03291398 -0.008613944 -0.02470695 -0.043998 -0.008613944 -0.02470695 -0.03291398 -0.04407995 -0.02249199 -0.03291398 -0.015266 -0.03136199 -0.043998 -0.02855795 -0.02470695 -0.039563 -0.008613944 -0.02914094 -0.04177898 -0.04407995 -0.004762947 -0.043998 -0.008613944 -0.01806294 -0.03291398 -0.03964298 -0.02692598 -0.039563 -0.03964298 -0.02470695 -0.03291398 -0.04407995 -0.01141297 -0.03291398 -0.008613944 -0.02914094 -0.039563 -0.02634698 -0.02914094 -0.03291398 -0.03077697 -0.03136199 -0.03734797 -0.04185795 -0.02470695 -0.039563 -0.03520995 -0.02692598 + + + + + + + + + + -0.647236 -0.1848236 -0.7395443 0 0.3714484 0.9284537 0.5711701 0.3048965 0.7621042 0.5715413 0.3046824 0.7619118 -1 0 0 0 1 0 1 0 0 -0.7070269 0 -0.7071867 0 1 -1.48046e-7 -0.2802724 0.0400775 -0.9590836 0 0 1 0.6000719 0 0.7999461 -0.7027049 -0.7017553 0.1172409 0 -1 0 1 -3.2921e-7 0 0.600072 0 0.7999461 0 0.3166983 -0.9485263 -0.7070274 0 -0.7071862 -0.4481002 0 -0.8939834 0 0 -1 0 -0.4474561 -0.894306 -0.1909534 -0.8574193 -0.4778797 -0.1910321 -0.47702 -0.8578804 -8.77144e-4 -0.7068671 -0.7073459 -0.514131 -0.5141335 -0.6865392 -0.4085133 -0.4085149 -0.8162308 -0.7241986 -0.2713573 -0.633957 -0.6655794 -0.3340691 -0.6673844 -0.4084022 -0.4085861 -0.8162506 -0.5889197 -0.1959525 -0.7840767 + + + + + + + + + + 0.4376586 0.2501974 0.5 0.08349937 0.2500987 0.1667732 0.06265151 1 0.06265151 1 1 0.4999812 1 0.4999812 0.06265151 1 1 0.2501974 0.06265151 1 0.06265151 0.7499906 1 0.2501974 0 0.4999812 0.06265151 1 1 0.2501974 1 0.4999812 1 0.2501974 1 0.2501974 1 0.2501974 0.06265151 0.7499906 0 0.3334712 1 0.2501974 0 0.3334712 0.8124401 0 0 0.4999812 1 0.2501974 0.4376586 0.2501974 0.4376586 0.2501974 1 0.2501974 1 0.08349937 1 0.2501974 1 0.2501974 1 0.08349937 0.8124401 0 0.3750916 0 1 0.08349937 0.06265151 1 0.06265151 1 0 1 0.06265151 0.7499906 0.06265151 1 0 1 0.06265151 1 0 0.4999812 0 1 0 0.4999812 0 0.3334712 0 1 0.06265151 1 1 0.4999812 1 0.4999812 1 0.2501974 0.06265151 1 1 0.4999812 1 0.4999812 1 0.2501974 1 0.4999812 0.8124401 0 0 0.3334712 0.1251057 0.1667732 0 0.3334712 0.06265151 0.7499906 0 0.7499906 0.06265151 0.7499906 0 1 0 0.7499906 0 1 0 0.3334712 0 0.7499906 1 0.2501974 0.8124401 0 1 0.08349937 1 0.08349937 1 0.2501974 1 0.08349937 0.8124401 0 1 0.08349937 1 0.08349937 0.4376586 0.2501974 1 0.08349937 0.5 0.08349937 1 0.08349937 0.3750916 0 0.5 0.08349937 0.3750916 0 0.8124401 0 0.3750916 0 0.1251057 0.1667732 0.3750916 0 0.3750916 0 0.8124401 0 0.1251057 0.1667732 0.3750916 0 0 0.3334712 0 0.4999812 0.06265151 0.2501974 0.3750916 0 0.1251057 0.1667732 0.06265151 0.2501974 0.1251057 0.1667732 0 0.3334712 0.06265151 0.2501974 0 0.4999812 0.1251057 0.2501974 0.06265151 0.2501974 0.1251057 0.2501974 0.3750916 0 0.06265151 0.2501974 0 0.4999812 0.4376586 0.2501974 0.2500987 0.1667732 0.1251057 0.2501974 0 0.4999812 0.2500987 0.1667732 0.3750916 0 0.1251057 0.2501974 0.2500987 0.1667732 0.5 0.08349937 0.3750916 0 0.2500987 0.1667732 + + + + + + + + + + + + + + +

10 0 0 18 0 1 21 0 2 2 1 3 1 1 4 3 1 5 3 2 6 1 2 7 6 2 8 1 3 9 4 3 10 6 3 11 5 4 12 2 4 13 7 4 14 3 5 15 6 5 16 7 5 17 6 6 18 4 6 19 8 6 20 6 6 21 8 6 22 9 6 23 5 4 24 7 4 25 10 4 26 10 7 27 7 7 28 11 7 29 7 8 30 6 8 31 11 8 32 9 9 33 0 9 34 11 9 35 1 10 36 2 10 37 12 10 38 4 11 39 1 11 40 12 11 41 2 12 42 5 12 43 12 12 44 5 13 45 8 13 46 12 13 47 2 1 48 3 1 49 13 1 50 7 4 51 2 4 52 13 4 53 3 5 54 7 5 55 13 5 56 9 14 57 8 14 58 14 14 59 8 6 60 4 6 61 16 6 62 4 15 63 12 15 64 16 15 65 12 13 66 8 13 67 16 13 68 6 6 69 9 6 70 17 6 71 11 5 72 6 5 73 17 5 74 9 16 75 11 16 76 17 16 77 10 17 78 11 17 79 18 17 80 11 18 81 0 18 82 18 18 83 0 19 84 9 19 85 19 19 86 14 20 87 0 20 88 19 20 89 9 6 90 14 6 91 19 6 92 8 21 93 5 21 94 20 21 95 0 22 96 14 22 97 20 22 98 14 23 99 8 23 100 20 23 101 5 24 102 15 24 103 20 24 104 15 25 105 0 25 106 20 25 107 5 26 108 10 26 109 21 26 110 15 27 111 5 27 112 21 27 113 0 28 114 15 28 115 21 28 116 18 29 117 0 29 118 21 29 119

+
+
+
+ + + + 0.06683999 0.04459398 0.02627199 0.04467397 0.04015898 -0.01362794 0.04467397 0.04237896 -0.01362794 0.04467397 0.05788898 0.035142 0.05132699 0.06454396 0.03291696 0.06240499 0.04015898 0.035142 0.05575698 0.04902899 0.00189197 0.04467397 0.06010895 0.01518696 0.06462299 0.05345594 0.035142 0.04467397 0.04015898 -0.002542972 0.06240499 0.04015898 0.01075696 0.06240499 0.05567395 0.02848696 0.05132699 0.05567395 0.008542001 0.04467397 0.06454396 0.035142 0.06683999 0.04015898 0.035142 0.04689395 0.04902899 -0.006972968 0.05132699 0.04237896 -0.009192943 0.06018996 0.04015898 0.03291696 0.05575698 0.05788898 0.01962196 0.06240499 0.04902899 0.017407 0.05575698 0.06232398 0.035142 0.06240499 0.04237896 0.01075696 0.05575698 0.04015898 -0.002542972 0.04689395 0.06010895 0.01518696 0.06683999 0.04015898 0.02627199 0.04467397 0.04902899 -0.006972968 0.06683999 0.04681295 0.02848696 0.04467397 0.06454396 0.030707 0.05354398 0.05124598 0.00189197 0.05575698 0.06232398 0.03291696 0.05575698 0.04237896 -0.002542972 0.06683999 0.04681295 0.035142 + + + + + + + + + + 1 0 0 -1 0 0 2.11592e-7 0 1 -1 1.777e-6 0 0 -1 0 0 0 1 0.5546712 0 -0.8320697 0.465586 0.5435282 -0.6984316 -0.5782046 -0.5782365 0.5756059 -0.697337 -0.6485501 0.3051292 0.7683067 0.5489309 -0.3292108 0.1693594 0.8455002 0.5064058 -7.40542e-7 0 1 0.9614889 0 -0.2748439 0.8552303 0.3664572 -0.3664563 0 -1 7.89677e-7 0.5774883 -0.5771788 -0.5773838 0.8944813 0 -0.4471057 0 0.8944276 -0.4472128 0.2190145 0.8727117 -0.4363564 0.3748323 0.8729844 -0.3120881 0.3795634 0.8662303 -0.3249257 0.961489 0 -0.2748436 0 0.7073726 -0.7068409 0 0.8944268 -0.4472144 0.8844988 0.4426973 -0.1472446 1 9.86369e-7 0 0.8636724 0.432274 -0.2592474 0.9046709 0.3010311 -0.3015804 0.9044224 0.3016796 -0.3016781 0 1 0 -1 -2.95933e-6 0 0.08709132 0.9610809 -0.2621809 0 0.9615124 -0.2747616 0.6672921 0.6660909 -0.333233 0.3201501 0.8343123 -0.4488061 0.5779936 0.5769496 -0.5771071 0.5771686 0.5775005 -0.5773817 0.6664241 0.6670261 -0.3330993 0.5008536 0.788114 -0.357802 0.7071936 0.70702 -5.63251e-5 0.5938187 0.7632521 -0.254609 0.4293346 0.8567348 -0.2857925 0.7071877 0.707026 0 0.4480206 0.8940232 0 0.7805928 0.3468008 -0.520004 0.8571853 0.2857491 -0.4284635 0.8322424 0 -0.554412 0.8944805 0 -0.447107 0.9485687 0.3165715 0 + + + + + + + + + + 1 0 0.8635432 0.2728726 1 0.2728726 0 0.09103953 0 0 1 0.7270863 0 0.09103953 1 0.7270863 0.5908346 0.8181259 1 0.7270863 1 0 1 0.5452942 1 0.7270863 0 0 0.2272914 0 0 0 1 0 0.2272914 0 1 0 0 0 0.5 0 0.5908346 0.8181259 1 0.7270863 1 1 1 0.7270863 1 0.5452942 1 1 1 0.5452942 1 0 1 0 1 0 0.5 0 1 0 0 0 0 0.09103953 0.09093701 0.09103953 0 0.09103953 0.1364568 0.3637482 0.09093701 0.09103953 1 0 1 0.7270863 0.9543777 0 1 0.7270863 0.2272914 0 0.9543777 0 0.2272914 0 1 0 0.9543777 0 0.3182284 0.3637482 0.8635432 0.6362518 0.6363543 0.3637482 0.9543777 1 1 1 1 0.9089604 1 1 1 0.5452942 1 0.9089604 0.8181259 0.181874 0.5 0 0.5 0.09103953 0.3182284 0.3637482 0.6363543 0.3637482 0.5 0.09103953 0.5 0 0 0 0.2272914 0 0 0 0.09093701 0.09103953 0.2272914 0 0.5 0.09103953 0.5 0 0.2272914 0 0.1364568 0.3637482 0.5908346 0.8181259 0.5908346 0.8181259 0.4545827 0.6362518 0.1364568 0.3637482 0.5908346 0.8181259 0.9543777 1 0.6817716 0.7270863 0.5908346 0.8181259 0.6817716 0.7270863 0.4545827 0.6362518 0.5908346 0.8181259 0.5 0 0.8181259 0.181874 0.8181259 0 0.8181259 0.181874 1 0 0.8181259 0 1 0 0.5 0 0.8181259 0 0 0.09103953 0.5908346 0.8181259 0.1364568 0.3637482 0.1364568 0.3637482 0 0.09103953 0.1364568 0.3637482 0.5908346 0.8181259 0.1364568 0.3637482 0.1364568 0.3637482 0.8635432 0.6362518 1 0.5452942 0.8635432 0.2728726 1 0 0.8181259 0.181874 0.8635432 0.2728726 0.6363543 0.3637482 0.8635432 0.6362518 0.8635432 0.2728726 0.8181259 0.181874 0.5 0.09103953 0.8635432 0.2728726 0.5 0.09103953 0.6363543 0.3637482 0.8635432 0.2728726 1 1 0.9543777 1 0.9090629 1 0.5908346 0.8181259 1 1 0.9090629 1 0.9543777 1 0.5908346 0.8181259 0.9090629 1 0.5908346 0.8181259 0.5908346 0.8181259 0.9090629 1 0.8635432 0.6362518 0.3182284 0.3637482 0.3182284 0.4546648 0.1364568 0.3637482 0.4545827 0.6362518 0.3182284 0.4546648 0.3182284 0.3637482 0.09093701 0.09103953 0.3182284 0.4546648 0.09093701 0.09103953 0.1364568 0.3637482 0.3182284 0.4546648 0.6817716 0.7270863 0.8635432 0.6362518 0.3182284 0.4546648 0.4545827 0.6362518 0.6817716 0.7270863 0.3182284 0.4546648 1 0.5452942 0.8635432 0.6362518 0.9543777 0.9089604 0.8635432 0.6362518 0.6817716 0.7270863 0.9543777 0.9089604 0.6817716 0.7270863 0.9543777 1 0.9543777 0.9089604 1 0.9089604 1 0.5452942 0.9543777 0.9089604 0.9543777 1 1 0.9089604 0.9543777 0.9089604 0.09093701 0.09103953 0.3182284 0.3637482 0.2272914 0.09103953 0.3182284 0.3637482 0.5 0.09103953 0.2272914 0.09103953 0.2272914 0 0.09093701 0.09103953 0.2272914 0.09103953 0.5 0.09103953 0.2272914 0 0.2272914 0.09103953 1 0.5452942 1 0 1 0.2728726 0.8635432 0.2728726 1 0.5452942 1 0.2728726 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.033589 0.04015898 -0.02249199 0.04467397 0.064543 0.035142 0.04245698 0.06675696 0.035142 0.006988942 0.062325 0.03292095 0.006988942 0.062325 0.006321966 0.006988942 0.04015898 -0.01805096 0.04651099 0.03875398 -0.008165955 0.04245698 0.05346196 -0.002541959 0.006988942 0.05124497 -0.015836 0.04467397 0.05789095 0.03292095 0.006988942 0.06897699 0.035142 0.02472496 0.064543 0.015181 0.02472496 0.04237598 -0.02471196 0.02029496 0.05789095 -0.002541959 0.04467397 0.04680997 -0.01140099 0.04467397 0.05789095 0.008530974 0.007264971 0.04036998 -0.02427297 0.01364398 0.06675696 0.01961594 0.02693796 0.04902994 -0.015836 0.033589 0.06010496 0.035142 0.04245698 0.04237598 -0.01805096 0.04023998 0.05789095 0.03292095 0.04245698 0.06675696 0.03292095 0.006988942 0.06897699 0.03070598 0.04023998 0.06010496 0.01075094 0.006988942 0.04237598 -0.02471196 0.03802299 0.04459595 -0.01805096 0.006988942 0.064543 0.035142 0.033589 0.05567395 -0.002541959 0.04467397 0.04015898 -0.015836 0.01364398 0.062325 0.006321966 0.02915495 0.062325 0.01075094 + + + + + + + + + + 0.1030746 0.9268585 -0.3609835 -1 0 0 -0.1311997 -0.9091151 0.3953435 0.998446 -0.01764875 0.05286097 0 0 1 -1 0 0 0.9920882 0.1217961 -0.03044563 0.9780029 0.1823117 -0.1013545 0.562767 0.7224745 -0.4016515 -0.001462996 -0.9953515 -0.09629791 -0.02674478 -0.9990271 -0.03506451 0.04910516 -0.6018462 -0.797101 0.08732783 0.7865018 -0.6113827 0.09432238 0.8494976 -0.5190928 0.1257864 -0.3141828 0.9409927 0.3184288 0.4243167 -0.8476783 -0.1209185 -0.9067795 0.4038931 0 -0.9064953 0.422216 -0.1137287 -0.8528618 0.5096005 0 -0.7082231 0.7059888 0.7066267 0.7075865 0 0.06246906 0.998047 0 0.7712856 0.6174893 -0.1543546 0.1037059 0.9689208 -0.2245835 0.07132524 0.9854212 -0.1544595 -1 -4.93147e-7 0 -0.1159638 0.958237 -0.2614085 0.06246924 0.9980469 0 0.2402178 0.8837572 -0.401583 0.3007906 0.9047614 -0.3015493 0 0.7073856 -0.7068279 -0.9879895 -0.1466139 -0.04879796 0 -0.213784 -0.976881 0.2678754 0.8014345 -0.5347388 0.1821794 0.7644028 -0.6184652 0.221147 0.8180748 -0.5308932 0.2877683 0.5747582 -0.7660565 0.3589379 0.7169031 -0.5976735 -0.1172405 -0.7027031 0.7017571 -2.4676e-7 0 1 0.1425856 0.8550002 -0.4986423 0.2069815 0.8297959 -0.5182639 0.2211557 0.8866216 -0.4061924 0.1246433 -0.9702442 -0.2075821 0.9686354 0.1378565 -0.2067392 0.4871167 -0.3234027 -0.8112509 0.8109622 0.3246058 -0.4867973 0 0.8944113 -0.4472457 1.53699e-4 0.8943926 -0.447283 0 0.9486691 -0.3162703 0.06283855 0.9467945 -0.3156448 0.176593 0.9394263 -0.2937569 0.1873609 0.9355384 -0.2994391 0.1506394 0.9032939 -0.4017063 0.1807205 0.9023807 -0.391215 0.1081259 0.9191928 -0.3786732 + + + + + + + + + + 0.518495 0.1683872 0.6665052 0.4487627 0.5924918 0.5608522 0.9628931 0 0.518495 0 0.1112874 0 0.9628931 0 0.1112874 0 0.2764393 1 0.1112874 0 0.518495 0 0.1482942 0 0.2764393 1 1 0.9535196 0.9628931 0.9535196 1 0.9535196 1 0.8974242 1 0 0.518495 0 0.9628931 0 1 0 1 0.9535196 0.2764393 1 0.5554015 0.9535196 0.2764393 1 0.2223911 0.9535196 0.5554015 0.9535196 0.2223911 0.9535196 0.3704013 0.8974242 0.5554015 0.9535196 0.03709024 0.6730428 0.2764393 1 0.00733447 0.006983399 0.2764393 1 0.1112874 0 0.00733447 0.006983399 0 0.4487627 0.03709024 0.6730428 0.00733447 0.006983399 0 0.4487627 0.1482942 0 0.1482942 0.5047569 0.1482942 0 0.3704013 0.3366733 0.1482942 0.5047569 0.9628931 0.9535196 1 0.9535196 1 0.6730428 1 0.9535196 1 0 1 0.6730428 0.03709024 0.6730428 0 0.4487627 0.1112874 0.8974242 0.9628931 0 0.2764393 1 0.9628931 0.8413289 0.2764393 1 0.9628931 0.9535196 0.9628931 0.8413289 1 0.6730428 0.9628931 0 0.9628931 0.8413289 0.9628931 0.9535196 1 0.6730428 0.9628931 0.8413289 1 0.8974242 1 0.9535196 0.9628931 0.8974242 1 0 1 0.8974242 0.9628931 0.8974242 1 0.9535196 0.5554015 0.9535196 0.9628931 0.8974242 0.6665052 0.4487627 0.7406021 0.1683872 0.9628931 0.8974242 0.9628931 0.8974242 0.7406021 0.1683872 0.9258863 0 0.518495 0 1 0 0.9258863 0 0.7406021 0.1683872 0.518495 0 0.9258863 0 1 0 0.9628931 0.8974242 0.9258863 0 0.5554015 0.9535196 0.3704013 0.8974242 0.5924918 0.8413289 0.9628931 0.8974242 0.5554015 0.9535196 0.5924918 0.8413289 0.1112874 0 0.1482942 0 0 0 0.1482942 0 0 0.4487627 0 0 0.00733447 0.006983399 0.1112874 0 0 0 0 0.4487627 0.00733447 0.006983399 0 0 0.3704013 0.8974242 0.2223911 0.9535196 0.1112874 0.7852336 0 0.4487627 0.1482942 0.5047569 0.1112874 0.7852336 0.1482942 0.5047569 0.3704013 0.8974242 0.1112874 0.7852336 0.1112874 0.8974242 0 0.4487627 0.1112874 0.7852336 0.2223911 0.9535196 0.1112874 0.8974242 0.1112874 0.7852336 1 0 0.9628931 0 1 0 0.9628931 0 1 0.6730428 1 0 1 0.6730428 1 0 1 0 0.1482942 0.5047569 0.3704013 0.3366733 0.3704013 0.6730428 0.3704013 0.8974242 0.1482942 0.5047569 0.3704013 0.6730428 0.5924918 0.8413289 0.3704013 0.8974242 0.3704013 0.6730428 0.2764393 1 0.03709024 0.6730428 0.1482942 0.9535196 0.2223911 0.9535196 0.2764393 1 0.1482942 0.9535196 0.03709024 0.6730428 0.1112874 0.8974242 0.1482942 0.9535196 0.1112874 0.8974242 0.2223911 0.9535196 0.1482942 0.9535196 0.1482942 0 0.518495 0 0.518495 0.1683872 0.3704013 0.3366733 0.1482942 0 0.518495 0.1683872 0.518495 0 0.7406021 0.1683872 0.518495 0.1683872 0.7406021 0.1683872 0.6665052 0.4487627 0.518495 0.1683872 0.6665052 0.4487627 0.9628931 0.8974242 0.5924918 0.5608522 0.9628931 0.8974242 0.5924918 0.8413289 0.5924918 0.5608522 0.3704013 0.6730428 0.3704013 0.3366733 0.5924918 0.5608522 0.5924918 0.8413289 0.3704013 0.6730428 0.5924918 0.5608522 0.3704013 0.3366733 0.518495 0.1683872 0.5924918 0.5608522 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.062406 0.04015898 0.01074397 0.04059594 -0.008052945 -0.02623897 0.040241 2.59e-4 -0.02914595 0.040241 0.04015898 -0.011406 0.06462097 -0.008610963 0.035142 0.06683796 -0.008610963 0.01074397 0.06905496 0.04015898 0.035142 0.04911094 0.03128898 -0.018058 0.06018894 0.04015898 0.03292 0.057971 -0.008610963 -0.009190976 0.040241 -0.008610963 -0.02027297 0.07127296 -0.008610963 0.035142 0.06683796 0.01134896 0.01074397 0.04246097 0.04015898 -0.02027297 0.07127296 0.02242398 0.03070497 0.05575698 0.01798897 -0.011406 0.04689598 -0.006390988 -0.02470898 0.04246097 0.02463895 -0.02692395 0.057971 0.04015898 -3.25e-4 0.07127296 -0.008610963 0.02626895 0.06462097 0.03128898 0.01074397 0.040241 0.03128898 -0.02470898 0.051328 0.020199 -0.018058 0.040241 0.03793895 -0.011406 0.062406 0.04015898 0.035142 0.06462097 0.00247395 0.004098951 0.06683796 0.03572398 0.01961696 0.057971 0.02907395 -0.00475496 0.057971 0.006908953 -0.009190976 0.04246097 0.00247395 -0.02914595 0.06905496 0.01798897 0.01961696 0.06018894 0.03793895 0.03292 + + + + + + + + + + -0.707903 0 0.7063096 0 1 5.91682e-7 0 1 -3.33884e-7 0 -1 0 -0.9957169 -0.06538593 -0.06536489 -1 0 0 0.05604779 -0.9943932 -0.08967053 0 -1 0 0 0 1 0 1 -4.73791e-7 0.9520531 0.04329854 0.3028533 0.2997246 -0.3035193 -0.9044564 0.3178417 -0.8800841 -0.3527445 0.6393742 0.3028661 -0.706734 0 1 1.04928e-6 0.7229725 0.401652 -0.5621267 0.9615358 0 -0.2746799 1 0 0 0.9042853 0.2258169 -0.3623185 -1 3.11741e-7 0 -0.9114752 0.342252 -0.2282028 -0.4910453 0.1233096 -0.8623626 0.2542018 0.3809595 -0.8889609 0.7352218 0.146978 -0.6616996 -0.9119116 0 0.4103869 -1 0 0 -0.9126498 -0.07648348 0.4015231 0 1 -9.84962e-7 0.9120036 -0.06077158 -0.4056553 0.9485976 0 -0.316485 0.883721 0.4012934 -0.2408335 0.9681155 0.1676446 -0.1861391 0.9118298 0.2277005 -0.3416415 0.8298161 0.2070888 -0.5181888 0.9089624 0.1010619 -0.4044424 0.8979754 0.1633011 -0.4086232 0.8450257 0.1407452 -0.5158707 0.8332435 0.1665737 -0.5272177 0.9043246 0.08698379 -0.4178887 0.9021025 0.08468312 -0.423131 0.8139638 0 -0.5809158 0.8399614 0.0600264 -0.5393162 0.8089346 0.0121876 -0.5877724 0.8942925 0 -0.4474828 0.8910526 0.08907514 -0.445074 0.3012821 -0.3019633 -0.9044597 -0.09903341 0.0992583 -0.9901214 0.7469006 0.04150438 -0.6636391 0.7224412 0.06896913 -0.6879841 0.9669641 0.01702374 -0.2543438 0.9777951 0.02965289 -0.2074549 0.9435257 0.1049049 -0.3142519 0.963078 0.1203912 -0.2408047 0.9477996 0.1184813 -0.2960373 -0.9098574 -0.06708198 0.4094626 -0.6916857 -0.03141456 0.7215151 + + + + + + + + + + 1 1 0.9654368 1 0.9654368 0.9544802 0.6204891 1 0.2759457 1 1 1 1 1 0.2759457 1 0.9654368 1 0.6204891 0 1 0 0.3104001 0 0 0.181874 0.04521834 0.0114414 0.1380195 0 0.2759457 1 0 0.181874 0.1380195 0 0.04521834 0.0114414 0.3104001 0 0.1380195 0 0.3104001 0 1 0 0.1380195 0 1 0 0.6204891 0 1 0 1 1 1 0 1 0 0.2759457 1 0.6204891 1 0.1380195 1 1 1 1 0 0.9309825 0.6363543 0.04521834 0.0114414 0 0.181874 0.06901752 0.04551976 0.3104001 0 0.04521834 0.0114414 0.06901752 0.04551976 0.1380195 1 0.1724739 0.8181259 0.03456318 0.6817716 0.1380195 1 0.6204891 1 0.4483107 1 0.1724739 0.8181259 0.1380195 1 0.4483107 1 1 0 0.6204891 0 0.8619804 0 0.6204891 0 0.6204891 0.409268 0.8619804 0 0.9309825 0.6363543 1 0 0.8619804 0 0.4483107 1 0.6204891 1 0.6204891 0.8181259 0 0.181874 0.2759457 1 0.06901752 0.8181259 0.2759457 1 0.1380195 1 0.06901752 0.8181259 0.03456318 0.6817716 0 0.181874 0.06901752 0.8181259 0.1380195 1 0.03456318 0.6817716 0.06901752 0.8181259 0.03456318 0.6817716 0.1724739 0.8181259 0.1724739 0.590732 0.9654368 1 0.2759457 1 0.2759457 0.9544802 0.2759457 1 0.1380195 0 0.2759457 0.9544802 0.1380195 0 1 0 0.2759457 0.9544802 1 0 1 1 1 1 1 1 0.9654368 1 1 1 0.6204891 0 0.3104001 0 0.5171261 0.2272914 0.6204891 0.409268 0.6204891 0 0.5171261 0.2272914 0.6204891 1 1 1 0.7585086 0.9090629 1 1 0.9309825 0.6363543 0.7585086 0.9090629 0.6204891 0.8181259 0.6204891 1 0.7585086 0.9090629 0.1724739 0.8181259 0.4483107 1 0.3794021 0.7727087 0.6204891 0.8181259 0.6204891 0.409268 0.3794021 0.7727087 0.4483107 1 0.6204891 0.8181259 0.3794021 0.7727087 0.2759457 0.5454173 0.1724739 0.590732 0.3794021 0.7727087 0.1724739 0.590732 0.1724739 0.8181259 0.3794021 0.7727087 0.6204891 0.409268 0.5171261 0.2272914 0.3794021 0.7727087 0.3794021 0.7727087 0.5171261 0.2272914 0.3104001 0.3182284 0.3104001 0 0.06901752 0.04551976 0.3104001 0.3182284 0.1724739 0.590732 0.2759457 0.5454173 0.3104001 0.3182284 0.06901752 0.04551976 0.1724739 0.590732 0.3104001 0.3182284 0.5171261 0.2272914 0.3104001 0 0.3104001 0.3182284 0.2759457 0.5454173 0.3794021 0.7727087 0.3104001 0.3182284 0.06901752 0.04551976 0 0.181874 0 0.2272914 0 0.181874 0.03456318 0.6817716 0 0.2272914 0.1724739 0.590732 0.06901752 0.04551976 0 0.2272914 0.03456318 0.6817716 0.1724739 0.590732 0 0.2272914 0.8619804 0 0.6204891 0.409268 0.7585086 0.5454173 0.9309825 0.6363543 0.8619804 0 0.7585086 0.5454173 0.6204891 0.409268 0.6204891 0.8181259 0.7585086 0.5454173 0.7585086 0.9090629 0.9309825 0.6363543 0.7585086 0.5454173 0.6204891 0.8181259 0.7585086 0.9090629 0.7585086 0.5454173 0.9654368 1 0.2759457 0.9544802 0.9654368 0.9544802 0.2759457 0.9544802 1 0 0.9654368 0.9544802 1 0 1 1 0.9654368 0.9544802 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.040241 0.04015898 -0.02028197 0.006988942 -0.008610963 -0.03135895 0.009208977 0.02685397 -0.03357899 0.006988942 0.04015898 -0.02028197 0.04111295 -0.00988996 -0.02243995 0.03580397 0.020199 -0.03135895 0.04177194 0.03998094 -0.01270896 0.006988942 -0.008610963 -0.02470898 0.03358799 -0.008610963 -0.03135895 0.02472096 0.03128898 -0.03357899 0.006988942 0.03572398 -0.03135895 0.040241 0.02463895 -0.02914196 0.02472096 0.04015898 -0.02692598 0.040241 -0.008610963 -0.02914196 0.03580397 0.03793895 -0.01362794 0.02915495 0.02242398 -0.03357899 0.03358799 0.03128898 -0.03135895 0.03802096 0.03793895 -0.02470898 0.006988942 0.03793895 -0.02028197 0.040241 0.03572398 -0.02470898 0.03580397 0.02907395 -0.03135895 0.009208977 0.03128898 -0.03357899 0.03358799 0.03793895 -0.02692598 0.01807498 0.03572398 -0.03135895 + + + + + + + + + + 0 0.7069467 -0.7072669 0 0.999724 0.02349871 -0.07222825 -0.190092 0.9791058 -1 0 0 -0.03745466 -0.9992984 0 0 -0.9898739 -0.1419497 -0.7071064 0 -0.7071073 -1 0 0 0.9951333 0.006041169 -0.0983529 0 1 -1.05388e-6 -0.1379386 0.919481 -0.3681408 0.0650531 -0.9786 -0.1952185 0.3160486 -0.02430981 -0.9484315 0.9916417 0 -0.129023 0.4469711 0 -0.8945485 -0.2085331 0.1765404 0.9619499 -0.09018933 -0.1774529 0.979988 -0.0136848 -0.06161552 -0.9980062 0 -0.07134985 -0.9974514 0.3094335 -0.02380084 -0.9506232 0 0 -1 -0.2250001 0 0.9743588 -0.2240405 -0.09226816 0.9702023 0.9631885 0.1899188 -0.1902598 0.9874217 0.05870896 -0.1468055 0.5761348 0.5774344 -0.5784792 0.4569281 0.4579589 -0.7625551 0.4469707 0 -0.8945486 0.3166986 0 -0.9485263 0.2159678 0.1080203 -0.9704069 0.2360034 0.2361103 -0.9426316 0.6409793 0.2850089 -0.7126819 0.4572924 0.4574984 -0.7626133 0 0.4476171 -0.8942254 -0.7071073 0 -0.7071063 0.2112421 0.8437325 -0.4934493 0.1485599 0.5933708 -0.7911012 0.203944 0.5430133 -0.8145819 0.2680018 0.8006274 -0.5358831 0.3841927 0.5121015 -0.768211 0 0.4476174 -0.8942253 0.132023 0.5947763 -0.7929761 + + + + + + + + + + 0.9113869 0 1 0.5097893 0.9113869 0.3187189 1 0.9559842 1 0 0.9964435 1 0 0.981054 0.9964435 1 0.02555495 0 1 0 0.02555495 0 0.02555495 0 0.02555495 0 0 0.981054 0.02555495 0 0 0.981054 0.02555495 0 0.02555495 0.7647126 0.7341606 0.06382423 0.02555495 0 0.9113869 0 0.02555495 0 1 0 0.9113869 0 0.9964435 1 0 0.981054 0.6899039 0.9559842 1 0 1 0.9559842 1 0.5097893 0.9113869 0 1 0 1 0.5097893 0 0.981054 0.02555495 0.7647126 0.02555495 0.9559842 0.02555495 0.7647126 0.6011908 0.828422 0.02555495 0.9559842 0.6899039 0.9559842 0 0.981054 0.02555495 0.9559842 0.6011908 0.828422 0.6899039 0.9559842 0.02555495 0.9559842 0.9964435 1 1 0 0.9556435 0.828422 0.02555495 0 0.9964435 1 0.9556435 0.828422 0.02555495 0 0.7341606 0.06382423 0.6456473 0.6372653 0.02555495 0.7647126 0.02555495 0 0.6456473 0.6372653 0.6011908 0.828422 0.02555495 0.7647126 0.6456473 0.6372653 0.7341606 0.06382423 0.8227737 0.5097893 0.6456473 0.6372653 1 0 0.02555495 0 0.9556435 0 0.9556435 0.828422 1 0 0.9556435 0 0.02555495 0 0.9556435 0.828422 0.9556435 0 1 0.9559842 0.9964435 1 0.9113869 0.9559842 0.9964435 1 0.6899039 0.9559842 0.9113869 0.9559842 0.9556435 0.8921599 1 0.9559842 0.9113869 0.9559842 0.8227737 0.7647126 0.9556435 0.8921599 0.9113869 0.9559842 0.6899039 0.9559842 0.6011908 0.828422 0.7785171 0.828422 0.6011908 0.828422 0.6456473 0.6372653 0.7785171 0.828422 0.6456473 0.6372653 0.8227737 0.5097893 0.7785171 0.828422 0.8227737 0.5097893 0.8227737 0.7647126 0.7785171 0.828422 0.9113869 0.9559842 0.6899039 0.9559842 0.7785171 0.828422 0.8227737 0.7647126 0.9113869 0.9559842 0.7785171 0.828422 0.8227737 0.5097893 0.7341606 0.06382423 0.8227737 0.06382423 0.9113869 0 0.8227737 0.5097893 0.8227737 0.06382423 0.7341606 0.06382423 0.9113869 0 0.8227737 0.06382423 1 0.5097893 1 0.9559842 0.9556435 0.7647126 0.8227737 0.5097893 1 0.5097893 0.9556435 0.7647126 0.8227737 0.7647126 0.8227737 0.5097893 0.9556435 0.7647126 1 0.9559842 0.9556435 0.8921599 0.9556435 0.7647126 0.9556435 0.8921599 0.8227737 0.7647126 0.9556435 0.7647126 0.8227737 0.5097893 0.9113869 0 0.9113869 0.3187189 1 0.5097893 0.8227737 0.5097893 0.9113869 0.3187189 + + + + + + + + + + + + + + +

10 0 0 12 0 1 23 0 2 0 1 3 3 1 4 6 1 5 4 2 6 6 2 7 7 2 8 3 3 9 1 3 10 7 3 11 1 4 12 4 4 13 7 4 14 4 5 15 1 5 16 8 5 17 2 6 18 1 6 19 10 6 20 1 7 21 3 7 22 10 7 23 6 8 24 4 8 25 11 8 26 3 9 27 0 9 28 12 9 29 10 10 30 3 10 31 12 10 32 4 11 33 8 11 34 13 11 35 8 12 36 5 12 37 13 12 38 11 13 39 4 13 40 13 13 41 5 14 42 11 14 43 13 14 44 6 15 45 3 15 46 14 15 47 7 16 48 6 16 49 14 16 50 1 17 51 2 17 52 15 17 53 8 18 54 1 18 55 15 18 56 5 19 57 8 19 58 15 19 59 2 20 60 9 20 61 15 20 62 3 7 63 7 7 64 18 7 65 14 21 66 3 21 67 18 21 68 7 22 69 14 22 70 18 22 71 0 23 72 6 23 73 19 23 74 6 24 75 11 24 76 19 24 77 17 25 78 0 25 79 19 25 80 16 26 81 17 26 82 19 26 83 11 27 84 5 27 85 20 27 86 5 28 87 15 28 88 20 28 89 15 29 90 9 29 91 20 29 92 9 30 93 16 30 94 20 30 95 19 31 96 11 31 97 20 31 98 16 32 99 19 32 100 20 32 101 9 20 102 2 20 103 21 20 104 10 33 105 9 33 106 21 33 107 2 34 108 10 34 109 21 34 110 12 35 111 0 35 112 22 35 113 9 36 114 12 36 115 22 36 116 16 37 117 9 37 118 22 37 119 0 38 120 17 38 121 22 38 122 17 39 123 16 39 124 22 39 125 9 40 126 10 40 127 23 40 128 12 41 129 9 41 130 23 41 131

+
+
+
+ + + + -0.04621696 0.06454396 0.02848696 -0.04621696 0.04015898 -0.01362794 -0.04621696 0.04237896 -0.01362794 -0.066163 0.04015898 0.030707 -0.043998 0.05788898 0.03291696 -0.05951297 0.05788898 0.02848696 -0.05951297 0.04015898 0.035142 -0.043998 0.04015898 -0.002542972 -0.05507999 0.05345594 0.008542001 -0.043998 0.05345594 -3.23e-4 -0.05507999 0.06232398 0.035142 -0.05951297 0.04237896 0.008542001 -0.043998 0.06454396 0.035142 -0.063946 0.05124598 0.035142 -0.05065 0.05788898 0.01075696 -0.061728 0.04902899 0.01962196 -0.043998 0.06010895 0.01297199 -0.05286699 0.04015898 -0.004758 -0.043998 0.04237896 -0.01362794 -0.04621696 0.04902899 -0.006972968 -0.05507999 0.06232398 0.030707 -0.066163 0.04015898 0.035142 -0.05286699 0.04237896 -0.004758 -0.05729597 0.04015898 0.030707 -0.063946 0.05124598 0.030707 -0.063946 0.04237896 0.02183198 -0.043998 0.06010895 0.035142 -0.05951297 0.04015898 0.008542001 -0.066163 0.04459398 0.03291696 -0.04621696 0.06232398 0.01962196 -0.061728 0.05567395 0.035142 + + + + + + + + + + -0.8430483 0.5274829 -0.1050311 0 -1 3.03728e-7 0 -1 0 1 3.70405e-7 0 1 1.10164e-6 0 -0.1960025 0.9784232 0.06535285 0 0 1 -0.5965371 0.7451309 -0.2982006 -0.8174003 0.4965567 -0.2920416 -0.8594388 0.3439468 -0.3782402 0.5070617 0.8451647 -0.1690712 1 -2.62985e-6 0 -0.1477975 0.8844582 -0.4425944 -0.8001077 0 -0.5998563 0 -1 0 0 0 -1 0.7002831 -0.699966 -0.1401827 1 0 0 0.3586671 0.7173866 -0.5972558 -0.6623252 0.5299748 -0.5295773 -0.4854851 0.7274441 -0.4849014 -0.2397723 0.8431355 -0.4812814 0 0.7073717 -0.7068419 -0.2429735 0.9700329 0 -0.5963556 0.7453119 -0.298111 -0.6979833 0.4888625 -0.5232905 -0.8421944 0.3370449 -0.4208437 -0.8001077 0 -0.5998564 -0.8945341 0 -0.4469998 0.7236159 -0.5878212 0.3617269 0.7454059 -0.596235 0.2981175 -0.8407998 0.4732326 -0.2628819 -0.942691 0.2360444 -0.2358322 -0.9281373 0.2066788 -0.3095887 0.6731455 -0.5235011 0.5223234 -0.8945354 0 -0.4469969 -0.9405881 -0.1888368 -0.2821965 -0.9486189 0 -0.3164211 -1 1.47966e-6 0 -0.9133085 0.1826276 0.3640258 -0.9486972 0.3161859 0 -0.9427617 0.2359037 -0.2356907 -0.9705598 0.1074247 -0.2155775 0.2336466 0.9431965 -0.2361982 -0.183052 0.9127885 -0.3651154 -0.2907023 0.9281532 -0.2324302 -0.3452885 0.896972 -0.2760744 -0.7072132 0.7070004 0 -0.7072435 0.70697 -9.20609e-5 -0.8941047 0.447858 0 + + + + + + + + + + 0.8635432 0.7270863 0.9090629 0.4546648 1 0.6362518 0.9090629 0 0 0 1 0 1 0 0 0 0.2272914 0 0.9543777 0.7270863 0.2272914 0 0.2728111 0.5452942 0.9543777 0.7270863 0.2728111 0.5452942 1 1 0.8635432 1 1 0.9089604 1 1 1 0.9089604 1 0 1 1 1 0 1 0.9089604 1 0.4546648 0.4545827 0.5452942 0.8635432 0.7270863 0.5 0.7270863 0.8635432 0.7270863 0.4545827 0.5452942 0.6817716 0.3637482 0.4545827 0.5452942 0.4545827 0.09103953 0.6817716 0.3637482 0.8635432 1 1 1 0.5454173 0.8181259 1 1 0.2728111 0.5452942 0.5454173 0.8181259 0.2728111 0.5452942 0.5 0.7270863 0.5454173 0.8181259 0 0.09103953 0 0 0.181874 0 0 0 0.9090629 0 0.181874 0 0 0 0 0.09103953 0 0.09103953 0.2272914 0 0 0 0 0.09103953 0.2728111 0.5452942 0.2272914 0 0 0.09103953 0.2728111 0.5452942 0 0.09103953 0.1364568 0.3637482 0 0.09103953 0.4545827 0.5452942 0.1364568 0.3637482 0.4545827 0.5452942 0.5 0.7270863 0.1364568 0.3637482 0.5 0.7270863 0.2728111 0.5452942 0.1364568 0.3637482 0 0.09103953 0 0.09103953 0.1364568 0.3637482 1 0.9089604 0.8635432 1 0.9090629 0.9089604 0.5 0.7270863 0.8635432 0.7270863 0.9090629 0.9089604 0.9090629 0 1 0 1 0 1 0 1 0.4546648 1 0 0.4545827 0.5452942 0 0.09103953 0.181874 0.09103953 0.4545827 0.09103953 0.4545827 0.5452942 0.181874 0.09103953 0 0.09103953 0.181874 0 0.181874 0.09103953 0.181874 0 0.4545827 0.09103953 0.181874 0.09103953 0.9543777 0.7270863 1 0 0.9090629 0 0.2272914 0 0.9543777 0.7270863 0.9090629 0 1 0 0.2272914 0 0.9090629 0 0.8635432 0.7270863 0.6817716 0.3637482 0.9090629 0.4546648 0.9090629 0.4546648 0.6817716 0.3637482 0.7270863 0.09103953 0.6817716 0.3637482 0.4545827 0.09103953 0.7270863 0.09103953 1 0 0.9543777 0.7270863 1 0.8181259 0.9543777 0.7270863 1 1 1 0.8181259 1 1 1 0 1 0.8181259 0.181874 0 0.9090629 0 0.4545827 0 0.4545827 0.09103953 0.181874 0 0.4545827 0 0.9090629 0 0.7270863 0.09103953 0.4545827 0 0.7270863 0.09103953 0.4545827 0.09103953 0.4545827 0 0.9090629 0 1 0 0.9543777 0.181874 1 0 1 0.4546648 0.9543777 0.181874 1 0.4546648 0.9090629 0.4546648 0.9543777 0.181874 0.9090629 0.4546648 0.7270863 0.09103953 0.9543777 0.181874 0.7270863 0.09103953 0.9090629 0 0.9543777 0.181874 0.8635432 1 0.5454173 0.8181259 0.6817716 0.9089604 0.5454173 0.8181259 0.5 0.7270863 0.6817716 0.9089604 0.9090629 0.9089604 0.8635432 1 0.6817716 0.9089604 0.5 0.7270863 0.9090629 0.9089604 0.6817716 0.9089604 1 0.4546648 1 0.9089604 1 0.6362518 1 0.9089604 0.9090629 0.9089604 1 0.6362518 0.9090629 0.9089604 0.8635432 0.7270863 1 0.6362518 0.9090629 0.4546648 1 0.4546648 1 0.6362518 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.06616199 0.033499 0.02183794 -0.04621797 -0.008610963 -0.02249497 -0.04415398 -0.008328974 -0.02216196 -0.07059895 -0.008610963 0.035142 -0.05951297 0.04015898 0.035142 -0.04621797 0.04015898 -0.01362097 -0.05951297 0.004693984 -0.004756987 -0.06394398 -0.008610963 0.035142 -0.04399996 0.03572398 -0.004756987 -0.06616199 0.04015898 0.035142 -0.06837797 -0.008610963 0.01961499 -0.04399996 -0.008610963 -0.01584398 -0.05729997 0.04015898 0.001893997 -0.04621797 0.020199 -0.02249497 -0.07059895 0.01356399 0.030707 -0.06616199 0.01356399 0.01296395 -0.05286794 -0.008610963 -0.01584398 -0.04399996 0.03572398 -0.01806098 -0.05729997 0.02463895 -0.004756987 -0.04399996 0.04015898 -0.004756987 -0.04621797 0.03572398 -0.01806098 -0.05951297 0.03572398 0.035142 -0.05951297 -0.008610963 -0.004756987 -0.05065196 0.01356399 -0.01806098 -0.061728 0.03793895 0.01075196 -0.06837797 0.033499 0.035142 -0.07059895 -0.006390988 0.02626699 -0.06394398 0.020199 0.008534967 -0.06616199 0.04015898 0.02848994 -0.05065196 0.03128898 -0.01362097 -0.04399996 0.020199 -0.02249497 -0.06837797 0.02685397 0.02626699 + + + + + + + + + + -0.9728671 0.1852045 -0.1386681 0 -1 0 0 0 1 0 1 -3.59057e-7 0 -1 0 0.1427529 -0.9886128 -0.04760551 0 -1 0 0 1 0 1 0 0 0.9320306 0 0.36238 0.7842134 0.5886453 -0.1962301 1 0 0 -0.7033305 0.50294 -0.5023722 0 0.7075045 -0.7067089 0 0.2746232 -0.9615519 0.9320304 0 0.3623799 0.9272785 -0.0926755 0.36272 0.9282269 -0.0902518 0.3609008 -0.9397282 -0.008611381 -0.3418141 -0.9362663 0 -0.3512913 -0.8577387 0 -0.514086 -0.7071071 0 -0.7071066 -0.7071599 -2.14203e-5 -0.7070537 -0.8410416 0.03004562 -0.5401355 -0.8565954 0.09504371 -0.5071598 -0.8975965 0.1736373 -0.4051799 1.11191e-6 0 1 -0.9656873 0.05093324 0.2546645 -0.8614729 -0.4926256 -0.1232258 -1 -3.11342e-7 0 -0.9485446 -1.8169e-4 -0.3166434 -0.9687163 0.05390012 -0.2422472 -0.9247701 0.05810844 -0.3760636 -0.9499504 0.127045 -0.2854014 -0.9029618 0.1001884 -0.4178785 -0.9370784 0.1560833 -0.3122855 -0.9032323 0.162467 -0.39721 -0.9272646 0.2645873 -0.264904 -0.8023563 0.5336176 -0.2673514 -0.9488545 0.3157138 0 -0.8508717 0.2069434 -0.4828995 -0.8067864 0.2928835 -0.5131424 -0.7778028 0.1726031 -0.6043434 -0.8000645 0.1457709 -0.5819345 -0.8381148 0.1325475 -0.5291454 0.1609175 -0.01238828 -0.9868901 0.9996808 -0.005683958 -0.02462065 0 0 -1 0 0.2746232 -0.961552 -0.9669536 0.08081126 -0.2418065 -0.9500895 0.1268729 -0.2850146 -0.9863411 0.1318532 -0.09872275 -0.9622035 0.1924512 -0.1926841 + + + + + + + + + + 1 0.8634406 0.884588 1 0.846019 0.7271888 1 0 0 0 1 0 1 1 1 0 1 0 1 0 1 1 1 1 1 1 0.1539636 1 1 1 0 0 1 0 0.7306071 0 0 0 0.005777537 0.005782186 0.1153946 0 1 0 0 0 0.1153946 0 1 1 0.1539636 1 0.4231483 1 0 0 0.7306071 0 0.1153946 0 0.3077537 0.9090629 0.1153946 0 0.07692974 0.9090629 0.1539636 1 1 1 0.3077537 1 1 1 0.3077537 0.9090629 0.3077537 1 0.07692974 0.9090629 0.1539636 1 0.3077537 1 0.3077537 0.9090629 0.07692974 0.9090629 0.3077537 1 0.4231483 1 0.1539636 1 0.07692974 0.9090629 0.1539636 1 0.07692974 0.9090629 0.07692974 0.9090629 0.07692974 0.9090629 0 0.590732 0.07692974 0.9090629 1 1 1 0 1 0.9090629 0.3077537 0.9090629 1 1 1 0.9090629 1 0 0.1153946 0 1 0.9090629 0.1153946 0 0.3077537 0.9090629 1 0.9090629 0.7306071 0 0.6152125 0.4546853 0.3077537 0 0.6152125 0.4546853 0.3077537 0.2728111 0.3077537 0 0.1153946 0 0.7306071 0 0.3077537 0 0.3077537 0.2728111 0.1153946 0 0.3077537 0 0 0.590732 0 0 0.07692974 0.4546853 0 0 0.1153946 0 0.07692974 0.4546853 0.1153946 0 0.3077537 0.2728111 0.07692974 0.4546853 0.3077537 0.2728111 0.3077537 0.6817716 0.07692974 0.4546853 0.4231483 1 0.3077537 0.6817716 0.5768343 0.9544802 1 0 1 1 1 0.8634406 0.9230529 0.4546853 1 0 1 0.8634406 0.7306071 0 1 0 0.846019 0.04551976 1 0 0.9230529 0.4546853 0.846019 0.04551976 0.6152125 0.4546853 0.7306071 0 0.846019 0.04551976 0.9230529 0.4546853 0.6152125 0.4546853 0.846019 0.04551976 0.3077537 0.2728111 0.6152125 0.4546853 0.5383695 0.590732 0.6152125 0.4546853 0.7691761 0.8634406 0.5383695 0.590732 0.3077537 0.6817716 0.3077537 0.2728111 0.5383695 0.590732 0.7691761 0.8634406 0.5768343 0.9544802 0.5383695 0.590732 0.5768343 0.9544802 0.3077537 0.6817716 0.5383695 0.590732 1 1 0.4231483 1 0.884588 1 0.5768343 0.9544802 0.7691761 0.8634406 0.884588 1 0.4231483 1 0.5768343 0.9544802 0.884588 1 1 0.8634406 1 1 0.884588 1 0.3077537 0.6817716 0.4231483 1 0.1539636 0.8181259 0.4231483 1 0.07692974 0.9090629 0.1539636 0.8181259 0.07692974 0.9090629 0 0.590732 0.1539636 0.8181259 0 0.590732 0.07692974 0.4546853 0.1539636 0.8181259 0.07692974 0.4546853 0.3077537 0.6817716 0.1539636 0.8181259 0.005777537 0.005782186 0 0 0 0.590732 0.1153946 0 0.005777537 0.005782186 0 0.590732 0 0 0 0.590732 0 0.590732 0.07692974 0.9090629 0.1153946 0 0 0.590732 0 0.590732 0.07692974 0.9090629 0 0.590732 0.6152125 0.4546853 0.9230529 0.4546853 0.846019 0.7271888 0.7691761 0.8634406 0.6152125 0.4546853 0.846019 0.7271888 0.9230529 0.4546853 1 0.8634406 0.846019 0.7271888 0.884588 1 0.7691761 0.8634406 0.846019 0.7271888 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.01142495 -0.05516695 -0.015836 0.04245799 -0.06181198 0.035142 0.03579998 -0.06181198 0.035142 -0.004094958 -0.07289797 0.02626496 -0.004094958 -0.04629898 -0.01362097 0.04245799 -0.05516695 -0.006976962 -0.004094958 -0.06402695 0.03292095 0.04245799 -0.04629898 -0.002541959 0.04245799 -0.07067698 0.03292095 3.39e-4 -0.04851698 -0.02471196 0.02028399 -0.068461 0.01297199 0.03358995 -0.04629898 -0.02027696 -0.004094958 -0.06181198 -0.004750967 -0.004094958 -0.07289797 0.035142 0.04023396 -0.06402695 0.008530974 0.02249896 -0.05959796 -0.006976962 0.02693694 -0.04851698 -0.02249199 0.02471798 -0.07289797 0.035142 0.04245799 -0.04851698 -0.015836 -0.003787994 -0.04647397 -0.02212595 0.006991982 -0.068461 0.01075094 0.02471798 -0.07067698 0.02182996 0.04023396 -0.04629898 -0.002541959 -0.004094958 -0.06624299 0.035142 -0.004094958 -0.05516695 -0.015836 0.03358995 -0.05516695 -0.01140099 0.009205996 -0.06181198 -0.004750967 0.004771947 -0.04629898 -0.02471196 0.006991982 -0.07289797 0.02626496 0.04245799 -0.07067698 0.035142 0.02915596 -0.06402695 0.004106998 0.04023396 -0.068461 0.02182996 + + + + + + + + + + 0.1347202 -0.9432864 -0.3034158 -1 0 0 0 0.9247121 0.3806673 1 -1.44442e-7 0 1 0 0 0 1 -2.40075e-7 -1 0 0 0 0 1 -1 0 0 0.7646709 -0.6006336 -0.2334906 0.05347222 -0.7659643 -0.6406555 0 -1 0 1 1.07738e-6 0 0.3126204 0.9369274 -0.1563191 0.3810341 -0.2556049 -0.8885264 -0.09370452 -0.9375135 -0.3350939 0.1023468 -0.9811861 -0.1637039 -0.07210373 0.9252632 0.3724101 -0.08861267 0.9308269 0.3545548 0 1 1.88988e-5 0 0.9247126 0.3806661 -0.07838213 0.7057238 0.7041379 0 -0.8003028 -0.5995961 -1 0 0 0 -0.8576979 -0.5141542 -0.9993014 0.00905621 -0.0362575 -0.6231996 -0.4438868 -0.6438841 0.2284992 -0.8590663 -0.4580321 0.11035 -0.826842 -0.5515028 0.1119588 -0.8212054 -0.5595417 0.286899 -0.7661305 -0.5750942 0.2600932 -0.7513329 -0.6065068 0 -0.8576979 -0.5141541 0.05897402 -0.8613671 -0.5045481 0.06442761 -0.9204227 -0.385579 0 -0.9190313 -0.3941847 0 1 -6.48652e-7 0.08204942 -0.1639882 -0.9830442 0.1343538 0.4688303 -0.8730105 -0.02693778 0.9994052 -0.02153587 -0.2575603 0.5147723 -0.8177239 0 -1 -1.18285e-6 0 -0.9614515 -0.274975 0.04589796 -0.9604381 -0.2746854 0.05361145 -0.9620611 -0.267515 0.0821352 -0.9830332 -0.1640107 1 0 0 -1.85062e-7 0 1 0.1242274 -0.9922538 0 0.1331877 -0.9332907 -0.3335111 0.1792639 -0.8754219 -0.4488886 0.1696594 -0.875809 -0.4518566 0.07063007 -0.9186193 -0.3887802 0.08215969 -0.9074891 -0.4119629 0.5343012 -0.8018984 -0.2673597 0.1390722 -0.9394429 -0.3132187 0.137903 -0.9655719 -0.2205755 + + + + + + + + + + 0.7775921 0.618929 0.6295987 0.5236827 0.7775921 0.9522265 0.1853009 0 0.8516891 0 0.9628931 0 1 0.8569802 1 1 0.3704013 1 1 1 0.2963044 1 0.3704013 1 0.2963044 1 1 1 0.9628931 1 0.1853009 0 0.3704013 1 0.07409697 0.8095074 0.8516891 0 0.1853009 0 0.3334949 0 1 1 1 0.8569802 1 0 0.9628931 0 0.8516891 0 1 0 0.2963044 1 0.9628931 1 0.5554015 0.9522265 0.1482942 0.3333835 0 0.09524625 0.03709024 0.6665951 1 1 1 0 1 0.618929 1 0 0.8516891 0 1 0.618929 0.3704013 1 0.2963044 1 0.1482942 1 0.07409697 0.8095074 0.3704013 1 0.1482942 1 0.03709024 0.6665951 0.07409697 0.8095074 0.1482942 1 0.8516891 0 0.3334949 0 0.5924918 0.2381587 0.9628931 1 1 0.618929 0.7775921 0.618929 0.9628931 0 1 0.8569802 0.3704013 0.9522265 0.1853009 0 0.9628931 0 0.3704013 0.9522265 0.3704013 1 0.1853009 0 0.3704013 0.9522265 1 0.8569802 0.3704013 1 0.3704013 0.9522265 1 0.8569802 0.9628931 0 1 0 1 0 1 0.8569802 1 0 0.9628931 0 1 0 1 0 0 0.09524625 0.1482942 0.3333835 0.1482942 0 0.3334949 0 0.1853009 0 0.1482942 0 0.1482942 0.3333835 0.3334949 0 0.1482942 0 0.1853009 0 0.04320508 0.006594598 0.1482942 0 0.04320508 0.006594598 0 0.09524625 0.1482942 0 0.2963044 1 0.5554015 0.9522265 0.2223911 0.8095074 0.2963044 0.5712628 0.1482942 0.3333835 0.2223911 0.8095074 0.1482942 0.3333835 0.03709024 0.6665951 0.2223911 0.8095074 0.1482942 1 0.2963044 1 0.2223911 0.8095074 0.03709024 0.6665951 0.1482942 1 0.2223911 0.8095074 0.3334949 0 0.1482942 0.3333835 0.3334949 0.2857174 0.1482942 0.3333835 0.2963044 0.5712628 0.3334949 0.2857174 0.6295987 0.5236827 0.5924918 0.2381587 0.3334949 0.2857174 0.5924918 0.2381587 0.3334949 0 0.3334949 0.2857174 0.1853009 0 0.07409697 0.8095074 0 0.1904711 0.03709024 0.6665951 0 0.09524625 0 0.1904711 0.07409697 0.8095074 0.03709024 0.6665951 0 0.1904711 0.04320508 0.006594598 0.1853009 0 0 0.1904711 0 0.09524625 0.04320508 0.006594598 0 0.1904711 1 0.618929 0.8516891 0 0.8516891 0.2381587 0.8516891 0 0.5924918 0.2381587 0.8516891 0.2381587 0.5924918 0.2381587 0.6295987 0.5236827 0.8516891 0.2381587 0.6295987 0.5236827 0.7775921 0.618929 0.8516891 0.2381587 0.7775921 0.618929 1 0.618929 0.8516891 0.2381587 0.9628931 1 1 1 1 1 1 1 1 0.618929 1 1 1 0.618929 0.9628931 1 1 1 0.5554015 0.9522265 0.6295987 0.5236827 0.4814883 0.7142612 0.2223911 0.8095074 0.5554015 0.9522265 0.4814883 0.7142612 0.2963044 0.5712628 0.2223911 0.8095074 0.4814883 0.7142612 0.6295987 0.5236827 0.3334949 0.2857174 0.4814883 0.7142612 0.3334949 0.2857174 0.2963044 0.5712628 0.4814883 0.7142612 0.5554015 0.9522265 0.9628931 1 0.7775921 0.9522265 0.6295987 0.5236827 0.5554015 0.9522265 0.7775921 0.9522265 0.9628931 1 0.7775921 0.618929 0.7775921 0.9522265 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.03512299 -0.050731 -0.015836 -0.004094958 -0.06624597 0.035142 -0.004094958 -0.07289797 0.035142 -0.043998 -0.06846296 0.035142 -0.043998 -0.04407995 -0.002541959 -0.004094958 -0.04407995 -0.02471196 -0.01296496 -0.06624597 0.006321966 -0.05202019 -0.05959498 0.035142 -0.004094958 -0.04407995 -0.015836 -0.043998 -0.06181198 0.008530974 -0.004094958 -0.05516594 -0.015836 -0.043998 -0.04407995 -0.015836 -0.02847599 -0.07067799 0.02626496 -0.004094958 -0.06402599 0.03292095 -0.02183198 -0.04629695 -0.02471196 -0.004094958 -0.07067799 0.01961594 -0.02626097 -0.05959498 -0.004750967 -0.03955698 -0.05959498 0.035142 -0.043998 -0.05516594 -0.004750967 -0.01739895 -0.07289797 0.03292095 -0.03955698 -0.06624597 0.017407 -0.01517999 -0.057383 -0.01140099 -0.043998 -0.06846296 0.02847999 -0.03069394 -0.06402599 0.006321966 -0.037346 -0.04629695 -0.02027696 -0.04177898 -0.04407995 -0.002541959 -0.01296496 -0.07067799 0.01961594 -0.02183198 -0.04407995 -0.02471196 -0.004094958 -0.06624597 0.006321966 -0.004094958 -0.04629695 -0.02471196 -0.01961696 -0.050731 -0.02027696 -0.02183198 -0.06846296 0.015181 + + + + + + + + + + -0.1106465 -0.9597558 -0.2581208 0 0 1 1 0 0 0 0 1 -0.6802636 -0.6153832 -0.3981769 1 -1.47926e-7 0 0 1 0 -1 1.4617e-7 0 1 0 0 -1 4.93852e-7 0 0 0.9246949 0.3807092 0.1314975 0.7011244 0.7008088 0.1380276 0.9166883 0.3750081 -1 -7.91152e-7 0 -0.2093728 -0.8384836 -0.503099 -0.2179405 -0.8727952 -0.4367269 -0.09212267 -0.8288574 0.5518233 0.0236234 -0.9896554 -0.141507 -6.71321e-5 -0.8944002 -0.4472676 -0.1569569 -0.8287236 -0.537198 -0.08370387 -0.8954037 -0.4373168 -1 0 0 -0.1644653 -0.9863829 0 -0.1515449 -0.9854863 -0.07649153 -0.3004704 -0.9048278 -0.3016691 -0.1726216 -0.9501966 -0.2594771 -0.2177504 -0.8729565 -0.4364993 -0.1134402 -0.9059362 -0.407935 -0.21011 -0.9125909 -0.3507591 -0.3425834 -0.7450143 -0.5723551 -0.5777032 -0.5771477 -0.5771999 0 1 2.95977e-6 0 0.9246947 0.3807094 0.1308205 0.9194399 0.3708319 0 -0.9486688 -0.3162713 -0.08163416 -0.9782992 -0.190438 0 -0.986364 -0.1645785 0 1 -1.47891e-6 0 0 -1 -0.274861 0 -0.961484 -0.298214 0.5970329 -0.7447282 0 -0.8944112 -0.4472458 1 -2.96413e-7 0 0 -0.9486691 -0.3162705 0 -0.7071865 -0.707027 -0.06775438 -0.8143366 -0.5764246 -0.1551245 -0.8261815 -0.5416275 -0.1851271 -0.7402161 -0.6463807 -0.1849822 -0.7396371 -0.6470847 1.13867e-4 -0.707386 -0.7068275 -0.1538179 -0.9471588 -0.2814789 -0.1164262 -0.9297823 -0.3492131 -0.1564544 -0.9368709 -0.3127218 -0.07854837 -0.9457383 -0.3152926 + + + + + + + + + + 0.7406021 0.777711 0.8516891 0.3889933 0.6665052 0.5554971 1 1 1 1 1 0 1 1 1 1 0 1 1 0 1 1 1 0 0.3704013 0 1 0 1 0 1 1 0 1 0.1482942 1 0 1 0.3704013 0 0.1482942 1 1 0 0.3704013 0 0.5554015 0 0 1 1 1 0.1482942 1 0.3704013 0 0 1 0.1482942 0 0.5554015 0 0.3704013 0 0.1482942 0 1 1 0.1482942 1 0.9628931 1 0.1482942 1 1 1 0.7406021 1 1 0 1 1 1 0.1112949 0.3704013 0 1 0 1 0.1112949 1 1 0.9628931 1 1 0.1112949 0.9628931 1 0.1482942 1 1 0.1112949 0.5554015 0 0.1482942 0 0.3334949 0 0.1482942 0.2224143 0.3334949 0.4445029 0.3334949 0 0.3334949 0.4445029 0.5554015 0 0.3334949 0 1 1 1 0 0.9628931 0.6665915 0.7406021 1 1 1 0.9628931 0.6665915 0.1482942 1 0.518495 0.777711 0.2223911 0.7222014 0.3334949 0.4445029 0.1482942 0.2224143 0.2223911 0.7222014 0.518495 0.777711 0.3334949 0.4445029 0.2223911 0.7222014 1 0 0.5554015 0 0.8886958 0 0.9628931 0.6665915 1 0 0.8886958 0 0.8516891 0.3889933 0.9628931 0.6665915 0.8886958 0 0.5554015 0 0.7036957 0.1112949 0.8886958 0 0.7036957 0.1112949 0.8516891 0.3889933 0.8886958 0 0.5554015 0 0.3334949 0.4445029 0.518495 0.3334085 0.3334949 0.4445029 0.518495 0.777711 0.518495 0.3334085 0.7036957 0.1112949 0.5554015 0 0.518495 0.3334085 0.1482942 0.2224143 0.3334949 0 0.07409697 0.1667042 0.3334949 0 0.1482942 0 0.07409697 0.1667042 0.1482942 1 0.3704013 0 0.3704013 0.05560982 0.3704013 0 1 0.1112949 0.3704013 0.05560982 1 0.1112949 0.1482942 1 0.3704013 0.05560982 0.518495 0.777711 0.7406021 1 0.7406021 0.777711 0.9628931 0.6665915 0.8516891 0.3889933 0.7406021 0.777711 0.7406021 1 0.9628931 0.6665915 0.7406021 0.777711 0.1482942 0 0 1 0 0.5554971 0 1 0 0.5554971 0 0.5554971 0 0.5554971 0.07409697 0.1667042 0 0.5554971 0.07409697 0.1667042 0.1482942 0 0 0.5554971 0.518495 0.777711 0.1482942 1 0.518495 1 0.1482942 1 0.7406021 1 0.518495 1 0.7406021 1 0.518495 0.777711 0.518495 1 0 1 0.1482942 1 0 1 0 0.5554971 0 1 0 1 0 0.5554971 0 1 0.07409697 0.6110067 0.1482942 1 0.2223911 0.7222014 0.07409697 0.6110067 0.2223911 0.7222014 0.1482942 0.2224143 0.07409697 0.6110067 0.1482942 0.2224143 0.07409697 0.1667042 0.07409697 0.6110067 0.07409697 0.1667042 0 0.5554971 0.07409697 0.6110067 0 1 0.1482942 1 0.07409697 0.6110067 0.8516891 0.3889933 0.7036957 0.1112949 0.6665052 0.5554971 0.518495 0.3334085 0.518495 0.777711 0.6665052 0.5554971 0.7036957 0.1112949 0.518495 0.3334085 0.6665052 0.5554971 0.518495 0.777711 0.7406021 0.777711 0.6665052 0.5554971 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.04689496 -0.057374 -3.16e-4 0.071276 -0.008610963 0.035142 0.071276 -0.008610963 0.02847999 0.04245799 -0.008610963 -0.01805096 0.04245799 -0.061809 0.035142 0.06240397 -0.05959397 0.035142 0.05797296 -0.02191597 -0.006976962 0.06462395 -0.008610963 0.035142 0.04245799 -0.03521597 -0.02249199 0.06018996 -0.04407399 0.006321966 0.05354398 -0.008610963 -0.015836 0.04245799 -0.066244 0.017407 0.06905597 -0.03521597 0.02847999 0.066841 -0.01083099 0.01075094 0.05576097 -0.066244 0.03070598 0.04689496 -0.03963899 -0.01805096 0.05797296 -0.052944 0.008530974 0.04245215 -0.008610963 -0.02471196 0.066841 -0.05072999 0.03292095 0.05132895 -0.06846398 0.035142 0.04245799 -0.05072999 -0.01140099 0.04689496 -0.02634495 -0.02249199 0.066841 -0.02634495 0.015181 0.05132895 -0.05072999 -0.004750967 0.071276 -0.024131 0.035142 0.05354398 -0.061809 0.015181 0.06240397 -0.05515897 0.02182996 0.04295694 -0.07134586 0.03501582 0.06462395 -0.04629498 0.01961594 0.05576097 -0.03963899 -0.004750967 0.06240397 -0.008610963 -3.16e-4 0.06240397 -0.028566 0.004106998 0.05371278 -0.03520995 0.008545458 0.05649238 -0.04292392 0.0260092 0.05601197 -0.05159753 0.035142 0.04727578 -0.04027783 0.00608915 + + + + + + + + + + 0.9042319 -0.0924102 -0.4169235 0 1 0 0 0 1 -0.9595603 0.1671019 0.2265415 0 -0.2572073 0.9663563 -0.6552221 0.7171458 0.2374572 0 1 0 -0.9854528 0.1648727 -0.0412296 -0.9999997 -1.45506e-4 8.719e-4 0 1 -1.97098e-7 -1.90983e-7 0 1 0.6086894 -0.7600041 0.2277963 0.2359506 -0.9426669 -0.2360223 -0.1326376 -0.8726665 -0.4699579 -1 -8.47083e-7 0 0.2283013 -0.5662117 -0.792012 0.8229655 -0.09856981 -0.5594747 0.535142 -0.2676615 -0.8012369 0.1639312 -0.08199346 -0.9830583 0.6237281 0.05868697 -0.7794352 0.9729663 -0.08118736 -0.2162066 0.9698742 -0.06688791 -0.2342436 0.4382616 -0.6827367 -0.5846345 0.4868352 -0.5841498 -0.649431 1 0 0 -1.69093e-6 0 1 0.9783486 -0.08163654 -0.1901828 0.6965325 -0.1742564 0.696044 0.9852218 -0.1589401 -0.06384581 0.2791013 -0.8848651 -0.372983 0.3013612 -0.9046042 -0.3014513 0.6395956 -0.6395138 -0.4265437 0.5795276 -0.6832622 -0.4441854 0.7576329 -0.61922 -0.2062986 0.8666561 -0.4733286 -0.1576935 0.7032713 -0.6507165 -0.2863171 0.7142639 -0.6118081 -0.3398794 -0.9985392 -0.05242025 0.01310873 -0.01032507 -0.0137639 0.9998521 0.3168541 -0.9085699 -0.2722209 0.8859385 -0.3078317 -0.3469188 0.9532806 -0.2007274 -0.2257535 0.94911 -0.1650968 -0.2682039 0.8858844 -0.3084239 -0.3465307 0.9221629 -0.2937976 -0.251592 0.8277912 -0.3214199 -0.4598382 0.8242869 -0.1706818 -0.5398324 0.8181432 -0.1821929 -0.5453876 0.7895684 -0.3155135 -0.5263392 0.8217211 -0.3283627 -0.4657814 0 1 -1.2391e-7 0.8677202 -0.04098242 -0.4953608 0.8740215 0.4044409 -0.2692846 0.9187493 -0.08544236 -0.385486 0.9303536 -0.1006762 -0.3525714 0.9236747 -0.1801699 -0.3381773 0.9253147 -0.1773401 -0.3351768 0.8772826 -0.1660553 -0.4503342 0.8838546 -0.1873973 -0.4285832 1.67596e-7 0 1 -0.9230467 -0.005961716 0.3846418 -0.6360496 0.6633355 0.3942424 -0.4867315 0.6460551 0.5879672 -0.9101823 0.3231948 0.2590625 -0.6575513 0.6533586 0.3751653 -0.9385782 -0.05681389 0.3403574 -0.9422118 0.2644618 0.205662 + + + + + + + + + + 0.2963044 0.7777054 0.4075918 1 0.4814883 0.6665998 1 1 0.8886958 1 0.1112874 1 1 0.2817977 1 0.1481964 1 1 1 1 0.1112874 1 1 1 0.5556437 0.5555946 1 0.5555946 1 1 1 1 1 1 1 0.5555946 0.5556437 0.5555946 0.03709024 0.5554944 0.2203751 0.4709232 0.1112874 1 0.8886958 1 0.1482942 1 0.2203751 0.4709232 0.7036957 0.03709083 1 0.1111891 0.03709024 0.5554944 0.1112874 1 0 1 0.1112874 1 0.1482942 1 0 1 1 0.1481964 1 0.1111891 1 0 0.9258863 0.03709083 1 0.1481964 1 0 0.7036957 0.03709083 0.9258863 0.03709083 1 0 0.4075918 0.1852872 0.7036957 0.03709083 0.2223911 0.2962926 0.7036957 0.03709083 0.03709024 0.5554944 0.2223911 0.2962926 0.03709024 0.5554944 0.1112874 0.4815966 0.2223911 0.2962926 0.1482942 1 0.2963044 0.7777054 0.03709024 0.7037074 0.1112874 0.4815966 0.03709024 0.5554944 0.03709024 0.7037074 0.03709024 0.5554944 0 1 0.03709024 0.7037074 0 1 0.1482942 1 0.03709024 0.7037074 0.8886958 1 0.8886958 0.5554943 0.6665052 0.7037074 0.5924918 0.9629091 0.8886958 1 0.6665052 0.7037074 0.4075918 0.1852872 0.2223911 0.2962926 0.3334949 0.2962926 0.2223911 0.2962926 0.1112874 0.4815966 0.3334949 0.2962926 0.8886958 1 1 1 1 0.740698 1 1 1 0.1481964 1 0.740698 0.8886958 0.5554943 0.8886958 1 1 0.740698 1 0.1481964 0.9628931 0.2962926 1 0.740698 0.9628931 0.2962926 0.8886958 0.5554943 1 0.740698 0.7036957 0.03709083 0.4075918 0.1852872 0.6665052 0.1111891 0.9258863 0.03709083 0.7036957 0.03709083 0.6665052 0.1111891 0.3334949 0.2962926 0.5554015 0.259302 0.6665052 0.1111891 0.4075918 0.1852872 0.3334949 0.2962926 0.6665052 0.1111891 1 0.1481964 0.9258863 0.03709083 0.7775921 0.2222946 0.9628931 0.2962926 1 0.1481964 0.7775921 0.2222946 0.9258863 0.03709083 0.6665052 0.1111891 0.7775921 0.2222946 0.6665052 0.1111891 0.5554015 0.259302 0.7775921 0.2222946 1 0.1111891 0.7036957 0.03709083 0.9826578 0.01732575 1 0 1 0.1111891 0.9826578 0.01732575 0.7036957 0.03709083 1 0 0.9826578 0.01732575 0.5554015 0.259302 0.518495 0.4074984 0.7406021 0.3703908 0.8886958 0.5554943 0.9628931 0.2962926 0.7406021 0.3703908 0.6665052 0.7037074 0.8886958 0.5554943 0.7406021 0.3703908 0.7775921 0.2222946 0.5554015 0.259302 0.7406021 0.3703908 0.9628931 0.2962926 0.7775921 0.2222946 0.7406021 0.3703908 0.518495 0.4074984 0.5554015 0.259302 0.3334949 0.4815966 0.03709024 0.7037074 0.2963044 0.7777054 0.3334949 0.4815966 0.1112874 0.4815966 0.03709024 0.7037074 0.3334949 0.4815966 0.3334949 0.2962926 0.1112874 0.4815966 0.3334949 0.4815966 0.5554015 0.259302 0.3334949 0.2962926 0.3334949 0.4815966 0.1482942 1 0.8886958 1 0.4075918 1 0.2963044 0.7777054 0.1482942 1 0.4075918 1 0.8886958 1 0.5924918 0.9629091 0.4075918 1 0.4075918 1 0.5924918 0.9629091 0.4814883 0.6665998 0.5924918 0.9629091 0.6665052 0.7037074 0.4814883 0.6665998 0.7406021 0.3703908 0.518495 0.4074984 0.4814883 0.6665998 0.6665052 0.7037074 0.7406021 0.3703908 0.4814883 0.6665998 0.3334949 0.4815966 0.2963044 0.7777054 0.4814883 0.6665998 0.518495 0.4074984 0.3334949 0.4815966 0.4814883 0.6665998 1 0.2817977 1 0.1111891 1 0.1481964 1 1 0.1112874 1 0.5556437 0.5555946 0.5556437 0.5555946 1 0.1111891 1 0.5555946 1 0.5555946 1 0.1111891 1 0.2817977 1 0.2817977 1 1 1 0.5555946 0.2203751 0.4709232 1 0.1111891 0.5556437 0.5555946 0.5556437 0.5555946 0.1112874 1 0.03709024 0.5554944 0.2203751 0.4709232 0.03709024 0.5554944 0.7036957 0.03709083 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.05951297 -0.061809 0.02848994 -0.06394398 -0.008610963 0.035142 -0.04399996 -0.008610963 -0.01844763 -0.05143553 -0.05959367 0.03416001 -0.04843395 -0.03521597 -0.01806098 -0.06837797 -0.008610963 0.01961499 -0.04399996 -0.05515897 -0.002539992 -0.06616199 -0.052944 0.035142 -0.05951297 -0.04629498 0.006322979 -0.05286794 -0.008610963 -0.01584398 -0.04399996 -0.06846398 0.035142 -0.07059895 -0.024131 0.03292399 -0.06394398 -0.01969599 0.006322979 -0.04399996 -0.02634495 -0.02249497 -0.05729997 -0.052944 0.006322979 -0.06837797 -0.03521597 0.02626699 -0.04843395 -0.06402897 0.01739799 -0.07059895 -0.008610963 0.035142 -0.04621797 -0.04407399 -0.01584398 -0.05729997 -0.024131 -0.006968975 -0.04621797 -0.008610963 -0.02249497 -0.06394398 -0.04629498 0.01739799 -0.05286794 -0.066244 0.035142 -0.04843395 -0.052944 -0.004756987 -0.06394398 -0.057374 0.030707 -0.06394398 -0.008610963 0.006322979 -0.05508399 -0.04185897 -0.004756987 -0.07059895 -0.01748096 0.02848994 -0.04621797 -0.02634495 -0.02249497 -0.05508399 -0.061809 0.01961499 -0.06616199 -0.028566 0.01518595 -0.04399996 -0.04407399 -0.01584398 -0.05966109 -0.04544466 0.03443253 -0.05278205 -0.03410232 0.00785613 + + + + + + + + + + 0 -0.3512448 -0.9362837 0.7956495 0.4548493 0.4000676 0 1 0 0.8844684 0.1508914 0.4415287 0.07835131 0.02635586 0.9965775 0 1 0 0.7340517 0.6403496 0.2260985 0.1784099 0.2547626 0.9504031 1 0 0 -0.9853065 -0.1569209 -0.06743156 0.3627043 -0.8787367 -0.31027 0 1 0 0 0 1 -0.8163721 -0.08170562 0.5717175 -0.8196874 -0.08946251 -0.565782 -0.9034625 -0.1505031 -0.4013781 -0.894508 -2.02205e-4 -0.4470519 0.871721 0.1090265 -0.4777193 -0.8870597 -0.2952424 -0.3549042 -0.9543086 -0.2203406 -0.2018545 6.58221e-7 0 1 -0.2389297 -0.9544247 -0.1788467 -0.2176734 -0.8728625 -0.4367257 -0.06986415 -0.7720882 -0.6316636 -0.6736927 -0.5055052 -0.5390758 -0.7455684 -0.5897827 -0.3102971 -0.9422823 -0.2573286 -0.2142105 -0.8781441 -0.3676748 -0.3060689 -0.655764 -0.7370051 0.1636981 -0.6670507 -0.6667495 0.3323979 0 1 2.9738e-7 -0.8945483 0 -0.4469713 -0.9486119 0 -0.3164421 -0.8467143 -0.2818127 -0.4512831 -0.7683861 -0.3295379 -0.5486233 -0.7582217 -0.378832 -0.530647 -0.8453127 -0.1689084 -0.5068694 -0.8915744 -0.1641129 -0.4220926 -0.9824208 -0.1035625 -0.1553199 -0.9843892 0.1055986 -0.1408079 -1 0 0 -0.8107102 -0.08686792 -0.5789672 0 -0.351245 -0.9362837 -0.4233738 -0.3182116 -0.8482312 -0.7071598 0 -0.7070538 0 0 -1 -0.667335 -0.6661502 -0.3330284 -0.3984974 -0.8953503 -0.1988661 -0.3709064 -0.9055954 -0.2057314 -0.4086372 -0.8162304 -0.4083916 -0.5169458 -0.7494403 -0.4136501 -0.9122572 -0.1519688 -0.3803845 -0.9580435 -0.04351145 -0.2833009 -0.9164268 -0.1603969 -0.3666535 -0.9471502 -0.1536294 -0.2816106 -0.9580564 -0.04352343 -0.2832556 -0.9648638 -0.08988511 -0.2468978 0 -0.7682683 -0.6401279 0.9365592 0.03700429 0.3485509 0.9509633 0.10497 0.2909471 0.9339194 0.2794193 0.222979 0.115042 -0.005755603 0.993344 + + + + + + + + + + 0.4074984 0.1153946 0.7037074 0 0.4074984 0.1153946 0.3845939 1 0.1481964 1 0.5740982 0.5769818 1 1 1 0.1539636 1 0.7306071 0.5740982 0.5769818 0.2222946 0.3462186 1 0.1539636 0.3845939 1 0.259302 1 0.1481964 1 1 0.7306071 1 0.1539636 1 0.1153946 0.2222946 0.3462186 0.1481964 1 0 1 0.1481964 1 0.259302 1 0 1 1 0.1539636 0.2222946 0.3462186 0.7037074 0 0.259302 1 0.740698 0.9615178 0.5554943 0.846019 0.2222946 0.3462186 0 1 0.07409816 0.6921422 1 1 1 0.7306071 1 1 0.259302 1 1 1 1 1 0.740698 0.9615178 0.259302 1 1 1 1 0.1153946 0.5554943 0.07692974 0.740698 0.2693756 0.3703908 0.4999913 0.8147963 0.4999913 0.740698 0.2693756 0.8147963 0.4999913 1 0.1153946 0.740698 0.2693756 1 0.1153946 1 0.1539636 1 0 1 0.1539636 0.7037074 0 1 0 0.3703908 0.4999913 0.259302 0.4999913 0.3703908 0.6921422 0.259302 1 0.5554943 0.846019 0.3703908 0.6921422 0 1 0.259302 1 0.03709083 1 0.07409816 0.6921422 0 1 0.03709083 1 0.2222946 0.3462186 0.07409816 0.6921422 0.259302 0.3077537 0.4074984 0.1153946 0.2222946 0.3462186 0.259302 0.3077537 0.259302 0.4999913 0.4074984 0.1153946 0.259302 0.3077537 0.259302 0.4999913 0.1111891 0.884588 0.1852872 0.9230529 0.259302 1 0.3703908 0.6921422 0.1852872 0.9230529 0.3703908 0.6921422 0.259302 0.4999913 0.1852872 0.9230529 0.1111891 0.884588 0.03709083 1 0.1852872 0.9230529 0.03709083 1 0.259302 1 0.1852872 0.9230529 1 0.7306071 1 0.1153946 1 0.4999913 1 0.1153946 0.8147963 0.4999913 1 0.4999913 0.8147963 0.4999913 1 0.7306071 1 0.4999913 0.259302 0.4999913 0.3703908 0.4999913 0.4445057 0.3077537 0.5554943 0.07692974 0.4074984 0.1153946 0.4445057 0.3077537 0.4074984 0.1153946 0.259302 0.4999913 0.4445057 0.3077537 0.740698 0.2693756 0.5554943 0.07692974 0.4445057 0.3077537 0.3703908 0.4999913 0.740698 0.2693756 0.4445057 0.3077537 0.5554943 0.846019 0.740698 0.9615178 0.8518036 0.884588 1 1 1 0.7306071 0.8518036 0.884588 0.740698 0.9615178 1 1 0.8518036 0.884588 0.5554943 0.07692974 1 0.1153946 0.7037074 0 0.7037074 0 0.4074984 0.1153946 0.7037074 0 0.4074984 0.1153946 0.5554943 0.07692974 0.7037074 0 1 0.1153946 1 0 0.7037074 0 1 0 0.7037074 0 0.7037074 0 0.1111891 0.884588 0.259302 0.4999913 0.1111891 0.7306071 0.03709083 1 0.1111891 0.884588 0.1111891 0.7306071 0.07409816 0.6921422 0.03709083 1 0.1111891 0.7306071 0.259302 0.3077537 0.07409816 0.6921422 0.1111891 0.7306071 0.259302 0.4999913 0.259302 0.3077537 0.1111891 0.7306071 0.8147963 0.4999913 0.3703908 0.4999913 0.6665998 0.6537641 1 0.7306071 0.8147963 0.4999913 0.6665998 0.6537641 0.3703908 0.4999913 0.3703908 0.6921422 0.6665998 0.6537641 0.3703908 0.6921422 0.5554943 0.846019 0.6665998 0.6537641 0.8518036 0.884588 1 0.7306071 0.6665998 0.6537641 0.5554943 0.846019 0.8518036 0.884588 0.6665998 0.6537641 0.7037074 0 0.2222946 0.3462186 0.4074984 0.1153946 0.2222946 0.3462186 0.4074984 0.1153946 0.4074984 0.1153946 0.5740982 0.5769818 1 0.1539636 1 1 1 1 0.3845939 1 0.5740982 0.5769818 0.5740982 0.5769818 0.1481964 1 0.2222946 0.3462186 0.3845939 1 1 1 0.259302 1 + + + + + + + + + 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 1 + + + + + + + + + + + + + + + + + +

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

+
+
+
+
+ + + + -1 8.7449e-8 -8.73965e-8 0 -8.74228e-8 -0.9999999 -3.00288e-4 0 -8.74228e-8 -3.00288e-4 0.9999999 0 0 0 0 1 + + + + -1 8.7449e-8 -8.73965e-8 0 -8.74228e-8 -0.9999999 -3.00288e-4 0 -8.74228e-8 -3.00288e-4 0.9999999 0 0 0 0 1 + + + + -1 8.7449e-8 -8.73965e-8 0 -8.74228e-8 -0.9999999 -3.00288e-4 0 -8.74228e-8 -3.00288e-4 0.9999999 0 0 0 0 1 + + + + -1 8.7449e-8 -8.73965e-8 0 -8.74228e-8 -0.9999999 -3.00288e-4 0 -8.74228e-8 -3.00288e-4 0.9999999 0 0 0 0 1 + + + + -1 8.7449e-8 -8.73965e-8 0 -8.74228e-8 -0.9999999 -3.00288e-4 0 -8.74228e-8 -3.00288e-4 0.9999999 0 0 0 0 1 + + + + -1 8.7449e-8 -8.73965e-8 0 -8.74228e-8 -0.9999999 -3.00288e-4 0 -8.74228e-8 -3.00288e-4 0.9999999 0 0 0 0 1 + + + + -1 8.7449e-8 -8.73965e-8 0 -8.74228e-8 -0.9999999 -3.00288e-4 0 -8.74228e-8 -3.00288e-4 0.9999999 0 0 0 0 1 + + + + -1 8.7449e-8 -8.73965e-8 0 -8.74228e-8 -0.9999999 -3.00288e-4 0 -8.74228e-8 -3.00288e-4 0.9999999 0 0 0 0 1 + + + + -1 8.7449e-8 -8.73965e-8 0 -8.74228e-8 -0.9999999 -3.00288e-4 0 -8.74228e-8 -3.00288e-4 0.9999999 0 0 0 0 1 + + + + -1 8.7449e-8 -8.73965e-8 0 -8.74228e-8 -0.9999999 -3.00288e-4 0 -8.74228e-8 -3.00288e-4 0.9999999 0 0 0 0 1 + + + + -1 8.7449e-8 -8.73965e-8 0 -8.74228e-8 -0.9999999 -3.00288e-4 0 -8.74228e-8 -3.00288e-4 0.9999999 0 0 0 0 1 + + + + -1 8.7449e-8 -8.73965e-8 0 -8.74228e-8 -0.9999999 -3.00288e-4 0 -8.74228e-8 -3.00288e-4 0.9999999 0 0 0 0 1 + + + + -1 8.7449e-8 -8.73965e-8 0 -8.74228e-8 -0.9999999 -3.00288e-4 0 -8.74228e-8 -3.00288e-4 0.9999999 0 0 0 0 1 + + + + -1 8.7449e-8 -8.73965e-8 0 -8.74228e-8 -0.9999999 -3.00288e-4 0 -8.74228e-8 -3.00288e-4 0.9999999 0 0 0 0 1 + + + + -1 8.7449e-8 -8.73965e-8 0 -8.74228e-8 -0.9999999 -3.00288e-4 0 -8.74228e-8 -3.00288e-4 0.9999999 0 0 0 0 1 + + + + -1 8.7449e-8 -8.73965e-8 0 -8.74228e-8 -0.9999999 -3.00288e-4 0 -8.74228e-8 -3.00288e-4 0.9999999 0 0 0 0 1 + + + + -1 8.7449e-8 -8.73965e-8 0 -8.74228e-8 -0.9999999 -3.00288e-4 0 -8.74228e-8 -3.00288e-4 0.9999999 0 0 0 0 1 + + + + -1 8.7449e-8 -8.73965e-8 0 -8.74228e-8 -0.9999999 -3.00288e-4 0 -8.74228e-8 -3.00288e-4 0.9999999 0 0 0 0 1 + + + + 0.6859207 -0.3240135 0.6515582 7.358891 0.7276763 0.3054208 -0.6141704 -6.925791 0 0.8953956 0.4452714 4.958309 0 0 0 1 + + + + -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 + + + + + + + +
\ No newline at end of file diff --git a/cram_3d_world/cram_bullet_reasoning/resource/bowl_jeroen.obj b/cram_3d_world/cram_bullet_reasoning/resource/bowl_jeroen.obj new file mode 100644 index 0000000000..f14870ddce --- /dev/null +++ b/cram_3d_world/cram_bullet_reasoning/resource/bowl_jeroen.obj @@ -0,0 +1,6905 @@ +# Blender v2.83.4 OBJ File: '' +# www.blender.org +mtllib bowl_39.mtl +o Bowl_hull_1 +v 0.033177 -0.029301 -0.019176 +v -0.003464 0.040094 -0.026073 +v -0.003464 0.040094 -0.025642 +v -0.038369 -0.021546 -0.019609 +v -0.005614 -0.037064 -0.033400 +v 0.036191 0.009906 -0.033400 +v -0.034060 0.015950 -0.033400 +v 0.026701 0.035337 -0.018744 +v -0.033189 0.029301 -0.018744 +v 0.009896 0.036201 -0.033400 +v -0.018102 -0.040086 -0.019177 +v 0.028859 -0.024136 -0.033400 +v -0.030175 -0.022410 -0.033400 +v 0.040084 -0.018532 -0.018744 +v 0.019385 -0.039654 -0.018744 +v 0.039652 0.019388 -0.018744 +v -0.017694 0.033187 -0.033400 +v -0.019398 0.039646 -0.018744 +v -0.040104 0.018532 -0.018744 +v -0.037506 -0.002582 -0.032969 +v 0.028859 0.024136 -0.033400 +v 0.015932 -0.034042 -0.033400 +v 0.037046 -0.005597 -0.033400 +v 0.018522 0.040086 -0.018744 +v -0.022420 -0.030172 -0.033400 +v -0.028448 -0.033618 -0.019177 +v 0.003428 -0.040094 -0.026073 +v 0.040076 0.003862 -0.026073 +v -0.040096 0.003438 -0.026073 +v -0.008205 0.036632 -0.033400 +v 0.019817 0.031884 -0.033400 +v -0.039656 -0.018964 -0.019177 +v -0.024146 0.028877 -0.033400 +v -0.034923 -0.013791 -0.033400 +v -0.040104 0.004741 -0.018744 +v 0.026709 -0.035345 -0.019176 +v 0.033177 -0.017669 -0.033400 +v 0.033177 0.029301 -0.019176 +v 0.008177 -0.036632 -0.033400 +v -0.036642 0.008195 -0.033400 +v -0.025434 0.036201 -0.019176 +v -0.015960 -0.034050 -0.033400 +v 0.032745 0.018532 -0.033400 +v 0.007745 -0.039654 -0.018744 +v -0.030175 0.022410 -0.033400 +v 0.024119 -0.028869 -0.033400 +v 0.002988 0.037496 -0.032969 +v -0.033620 -0.028438 -0.019609 +v 0.010759 0.040086 -0.023918 +v -0.039656 -0.010345 -0.024779 +v 0.040084 -0.013367 -0.022622 +v -0.037930 0.022841 -0.019176 +v -0.011643 -0.040086 -0.023486 +v -0.023707 -0.037064 -0.019609 +v 0.037917 -0.022841 -0.019176 +v 0.024119 0.028877 -0.033400 +v 0.037917 0.022833 -0.019176 +v -0.018534 0.039646 -0.020038 +v 0.039652 0.018532 -0.020038 +v 0.018514 -0.039654 -0.020038 +v -0.040096 -0.003438 -0.026073 +v -0.040104 0.015510 -0.021331 +v 0.034896 -0.013783 -0.033400 +v 0.040076 -0.003870 -0.026073 +v 0.037486 0.002991 -0.032969 +v 0.018090 0.040086 -0.019609 +v -0.036642 -0.008171 -0.033400 +v -0.033189 0.029301 -0.019176 +v -0.024146 -0.028869 -0.033400 +v 0.022823 0.037927 -0.019176 +v 0.015932 0.034050 -0.033400 +v -0.009924 -0.036209 -0.033400 +v 0.002572 -0.040086 -0.019609 +v -0.003464 -0.040094 -0.026073 +v 0.002988 -0.037504 -0.032969 +v 0.022831 -0.037928 -0.019176 +v 0.040084 0.000424 -0.019609 +v -0.001282 0.040086 -0.019609 +v -0.029311 0.033187 -0.019176 +v -0.033197 -0.017669 -0.033400 +v 0.039652 0.010345 -0.024777 +v -0.018102 -0.040086 -0.019609 +v 0.026701 0.035337 -0.019176 +v -0.039656 -0.018964 -0.019609 +v 0.009472 -0.039654 -0.025212 +v 0.033177 -0.029301 -0.018744 +v 0.040084 -0.018100 -0.019609 +v 0.019817 -0.031884 -0.033400 +v -0.009484 0.039646 -0.025212 +v -0.013809 0.034913 -0.033400 +v -0.028448 -0.033618 -0.019609 +v 0.003420 0.040094 -0.026073 +v -0.005622 0.037072 -0.033400 +v 0.036191 -0.009906 -0.033400 +v -0.028887 0.024136 -0.033400 +v -0.028887 -0.024136 -0.033400 +v 0.034896 0.013791 -0.033400 +v -0.040104 0.009474 -0.024350 +v -0.037066 0.005596 -0.033400 +v -0.035339 -0.026287 -0.019609 +v -0.022836 0.037927 -0.019176 +v 0.029299 0.033187 -0.019176 +v -0.040104 0.018100 -0.019609 +v 0.029299 -0.033187 -0.019176 +v 0.035335 0.026287 -0.019609 +v -0.035347 0.026279 -0.019609 +v -0.017686 -0.033187 -0.033400 +v 0.037046 0.005596 -0.033400 +v -0.035339 -0.026287 -0.019177 +v 0.035335 -0.026287 -0.019609 +v 0.030155 -0.022402 -0.033400 +v -0.039656 -0.014655 -0.022624 +v -0.036211 0.009906 -0.033400 +v 0.005586 0.037064 -0.033400 +v -0.022420 0.030165 -0.033400 +v -0.033197 0.017669 -0.033400 +v 0.011191 -0.035769 -0.033400 +v 0.033177 0.029301 -0.018744 +v 0.014637 -0.039654 -0.022622 +v 0.040084 -0.008626 -0.024777 +v -0.014657 0.039646 -0.022622 +v -0.037082 -0.005597 -0.033400 +vt 0.037882 0.430207 +vt 0.043168 0.601899 +vt 0.037686 0.569793 +vt 0.951449 0.376468 +vt 0.430110 0.962216 +vt 0.075372 0.301096 +vt 0.623532 0.048551 +vt 0.860023 0.800998 +vt 0.123825 0.779464 +vt 0.833105 0.059319 +vt 0.086237 0.134593 +vt 1.000000 0.731108 +vt 0.741875 0.994518 +vt 0.994616 0.258222 +vt 0.279464 0.086139 +vt 0.456930 0.000000 +vt 0.456930 0.000000 +vt 0.258222 0.005579 +vt 0.000000 0.268892 +vt 0.860023 0.199002 +vt 0.698806 0.924530 +vt 0.962118 0.569793 +vt 0.731108 0.000098 +vt 0.220536 0.876272 +vt 0.397807 0.043168 +vt 0.747259 0.102388 +vt 0.199002 0.139879 +vt 0.064605 0.671985 +vt 0.000000 0.440877 +vt 0.913861 0.720341 +vt 0.602095 0.956832 +vt 0.043168 0.397807 +vt 0.182948 0.048551 +vt 0.301096 0.924628 +vt 0.908477 0.268892 +vt 0.274374 0.999902 +vt 0.596711 0.994518 +vt 0.145360 0.919244 +vt 0.123825 0.220536 +vt 0.800901 0.860024 +vt 0.027114 0.215153 +vt 0.204483 0.962216 +vt 0.800901 0.139879 +vt 0.268990 0.005579 +vt 0.999902 0.451840 +vt 0.994616 0.268892 +vt 0.972984 0.215251 +vt 0.542874 1.000000 +vt 0.731010 0.994518 +vt 0.000098 0.457126 +vt 0.032400 0.532204 +vt 0.000098 0.542874 +vt 0.005579 0.736492 +vt 0.000000 0.306578 +vt 0.935298 0.671887 +vt 0.999902 0.548258 +vt 0.967600 0.462706 +vt 0.634299 0.000098 +vt 0.725724 0.000098 +vt 0.086237 0.134593 +vt 0.199002 0.860024 +vt 0.784749 0.027016 +vt 0.698806 0.075372 +vt 0.376370 0.951547 +vt 0.354933 0.999902 +vt 0.532204 0.999902 +vt 0.456930 1.000000 +vt 0.537392 0.967698 +vt 0.833203 0.940779 +vt 0.784847 0.972984 +vt 1.000000 0.494714 +vt 1.000000 0.666699 +vt 0.484143 0.000098 +vt 0.134593 0.086139 +vt 0.021633 0.768696 +vt 0.086139 0.720341 +vt 0.994616 0.370987 +vt 0.274374 0.999902 +vt 0.833105 0.059319 +vt 0.005579 0.736492 +vt 0.618246 0.994518 +vt 0.913861 0.865407 +vt 0.913861 0.865407 +vt 0.972984 0.784847 +vt 1.000000 0.725724 +vt 0.747259 0.897612 +vt 0.327917 0.064605 +vt 0.080854 0.854640 +vt 0.145360 0.919244 +vt 0.542776 0.000000 +vt 0.537392 0.032400 +vt 0.430012 0.037686 +vt 0.381852 0.005579 +vt 0.951449 0.623532 +vt 0.139879 0.199002 +vt 0.139879 0.800998 +vt 0.935298 0.328015 +vt 0.000000 0.381852 +vt 0.059417 0.827819 +vt 0.215348 0.027016 +vt 0.913861 0.134593 +vt 0.865505 0.086139 +vt 0.000000 0.274276 +vt 0.865505 0.913861 +vt 0.940779 0.172181 +vt 0.059319 0.172279 +vt 0.279561 0.913861 +vt 0.962118 0.430207 +vt 0.059417 0.827819 +vt 0.940779 0.827819 +vt 0.876175 0.779366 +vt 0.005579 0.629013 +vt 0.005579 0.682753 +vt 0.048551 0.376468 +vt 0.569793 0.037784 +vt 0.220536 0.123825 +vt 0.086139 0.279659 +vt 0.639683 0.946065 +vt 0.913861 0.134593 +vt 0.682655 0.994518 +vt 1.000000 0.607576 +vt 0.317345 0.005579 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -0.0000 1.0000 +vn -0.0281 0.9996 0.0000 +vn -0.2679 0.3571 0.8948 +vn 0.0000 -0.7084 0.7058 +vn -0.0163 -0.0261 0.9995 +vn -0.0146 -0.0157 0.9998 +vn -0.5507 0.3536 0.7560 +vn -0.3851 -0.6160 0.6872 +vn -0.0405 0.9988 -0.0270 +vn 0.9989 0.0396 -0.0262 +vn 0.8735 0.4061 -0.2685 +vn 0.8100 0.4106 -0.4187 +vn 0.0398 -0.9988 -0.0268 +vn -0.9362 0.0000 -0.3516 +vn -0.9996 -0.0192 0.0204 +vn -1.0000 -0.0000 0.0000 +vn 0.9261 -0.0285 -0.3762 +vn 0.9362 0.0000 -0.3516 +vn 0.2274 0.8937 -0.3869 +vn -0.8062 0.5917 0.0000 +vn 0.4155 0.7156 0.5616 +vn 0.4215 0.8821 -0.2103 +vn 0.4082 0.8111 -0.4189 +vn 0.3044 0.8542 -0.4215 +vn 0.4401 0.7892 -0.4284 +vn -0.1797 -0.9052 -0.3852 +vn 0.0070 -0.9424 0.3345 +vn 0.0000 -1.0000 0.0012 +vn 0.0254 -0.9997 0.0046 +vn 0.0000 -1.0000 0.0011 +vn -0.1120 -0.9295 -0.3515 +vn 0.0162 -0.5190 -0.8546 +vn -0.0286 -0.9267 -0.3748 +vn 0.0000 -0.9362 -0.3516 +vn 0.3738 -0.5613 0.7384 +vn 0.4037 -0.8736 -0.2718 +vn 0.4081 -0.8109 -0.4195 +vn 0.9702 0.0110 0.2420 +vn 0.9997 0.0223 0.0106 +vn 1.0000 0.0000 0.0000 +vn -0.0238 0.9997 0.0099 +vn -0.0001 1.0000 0.0013 +vn -0.0112 0.9665 0.2565 +vn -0.3263 0.4198 0.8469 +vn -0.5571 0.7167 -0.4194 +vn -0.7078 0.7064 0.0000 +vn -0.7639 -0.4869 -0.4234 +vn 0.9022 0.2160 -0.3732 +vn 0.9807 0.0979 -0.1692 +vn -0.4746 -0.8802 0.0000 +vn -0.3054 -0.8540 -0.4212 +vn -0.2335 -0.8912 -0.3890 +vn -0.0005 -1.0000 0.0000 +vn -0.0020 -1.0000 -0.0034 +vn 0.5172 0.7400 -0.4300 +vn 0.5555 0.8315 0.0000 +vn 0.5026 0.7523 -0.4259 +vn -0.8950 -0.4461 0.0000 +vn -0.9996 -0.0283 0.0000 +vn -0.8127 -0.4051 -0.4187 +vn -0.8280 -0.3687 -0.4225 +vn 0.1253 -0.9242 -0.3609 +vn 0.1181 -0.9271 -0.3557 +vn 0.2483 -0.3308 0.9104 +vn 0.8062 -0.5917 0.0000 +vn 0.5483 -0.3517 0.7587 +vn 0.8817 -0.4222 -0.2107 +vn 0.8108 -0.4088 -0.4189 +vn 0.8274 -0.3661 -0.4259 +vn 0.5179 -0.7391 -0.4308 +vn 0.5014 -0.7529 -0.4262 +vn 0.4388 -0.7898 -0.4286 +vn -0.3679 0.8279 -0.4234 +vn -0.7076 -0.7066 0.0000 +vn -0.5343 -0.7351 -0.4172 +vn -0.5879 -0.8089 0.0000 +vn -0.5466 -0.7244 -0.4200 +vn 0.0000 1.0000 0.0000 +vn 0.0001 1.0000 0.0009 +vn 0.0000 0.9358 -0.3525 +vn 0.0007 1.0000 -0.0003 +vn 0.0021 1.0000 -0.0036 +vn -0.0269 0.9269 -0.3744 +vn -0.1189 0.9298 -0.3484 +vn -0.1564 0.9187 -0.3626 +vn 0.9053 -0.1798 -0.3848 +vn 0.8805 -0.2545 -0.3998 +vn 0.8630 -0.2882 -0.4149 +vn -0.6397 0.6397 -0.4261 +vn -0.6405 0.6392 -0.4258 +vn -0.6421 -0.6411 -0.4203 +vn -0.6409 -0.6419 -0.4209 +vn 0.8651 0.2884 -0.4103 +vn 0.8239 0.3738 -0.4259 +vn -1.0000 0.0000 -0.0046 +vn -1.0000 -0.0005 -0.0005 +vn -0.9084 0.1870 -0.3739 +vn -0.9268 0.0301 -0.3744 +vn -0.9295 0.1001 -0.3549 +vn -0.9163 0.1495 -0.3716 +vn -0.7635 -0.4879 -0.4231 +vn -0.7261 -0.5413 -0.4241 +vn -0.7089 -0.5666 -0.4200 +vn -0.3739 0.5625 0.7374 +vn -0.4034 0.8745 -0.2692 +vn -0.4081 0.8116 -0.4180 +vn 0.6403 0.6390 -0.4263 +vn 0.6395 0.6395 -0.4267 +vn 0.6377 0.7703 0.0000 +vn 0.5781 0.6983 -0.4221 +vn -0.8810 0.4233 -0.2112 +vn 0.6403 -0.6390 -0.4263 +vn 0.6389 -0.6400 -0.4269 +vn 0.5802 -0.6962 -0.4226 +vn 0.7078 -0.7064 0.0000 +vn 0.4173 -0.5007 0.7584 +vn 0.7078 0.5674 -0.4208 +vn 0.7424 0.5147 -0.4289 +vn 0.8029 0.5886 -0.0942 +vn 0.7494 0.5070 -0.4258 +vn -0.7490 0.5092 -0.4238 +vn -0.8013 0.5881 -0.1096 +vn -0.7260 0.5412 -0.4242 +vn -0.7089 0.5666 -0.4201 +vn -0.4858 -0.7629 -0.4266 +vn -0.4321 -0.8013 -0.4139 +vn -0.4061 -0.8123 -0.4186 +vn 0.6996 0.0000 -0.7145 +vn 0.9277 0.0969 -0.3606 +vn 0.9095 0.1806 -0.3743 +vn 0.9267 0.1310 -0.3522 +vn -0.7800 -0.4598 0.4245 +vn -0.0178 -0.0167 0.9997 +vn -0.0320 -0.0189 0.9993 +vn -0.6489 -0.6100 0.4549 +vn -0.8426 -0.5385 0.0000 +vn -0.7811 -0.6243 0.0000 +vn 0.7078 -0.5674 -0.4208 +vn 0.8022 -0.5887 -0.0991 +vn 0.7493 -0.5082 -0.4246 +vn 0.7609 -0.4858 -0.4303 +vn 0.7253 -0.5415 -0.4250 +vn -0.9751 -0.0992 -0.1984 +vn -0.8742 -0.2674 -0.4054 +vn -0.9128 -0.1826 -0.3652 +vn -0.9926 -0.0694 -0.0992 +vn -0.8696 -0.2830 -0.4046 +vn -0.8919 0.2250 -0.3922 +vn -0.8542 0.3040 -0.4218 +vn -0.8724 0.2706 -0.4071 +vn 0.1812 0.9041 -0.3870 +vn 0.0955 0.9295 -0.3561 +vn 0.1048 0.9296 -0.3534 +vn 0.0005 0.7075 -0.7067 +vn -0.5416 0.7265 -0.4230 +vn -0.5008 0.7535 -0.4259 +vn -0.4866 0.7608 -0.4295 +vn -0.7614 0.4853 -0.4298 +vn -0.8113 0.4075 -0.4191 +vn -0.8103 0.4099 -0.4187 +vn 0.3108 -0.8534 -0.4185 +vn 0.5918 0.3866 0.7073 +vn 0.8065 0.5912 0.0000 +vn 0.6197 0.6648 0.4172 +vn 0.7078 0.7064 0.0000 +vn 0.0723 -0.9915 -0.1084 +vn 0.0991 -0.9753 -0.1976 +vn 0.1834 -0.9125 -0.3658 +vn 0.2526 -0.8817 -0.3986 +vn 0.2674 -0.8760 -0.4013 +vn 0.9083 -0.1731 -0.3808 +vn 0.9276 -0.0967 -0.3608 +vn 1.0000 0.0000 -0.0061 +vn 1.0000 0.0005 -0.0009 +vn -0.0737 0.9911 -0.1106 +vn -0.1013 0.9740 -0.2024 +vn -0.1826 0.9131 -0.3646 +vn -0.2681 0.8741 -0.4050 +vn -0.2698 0.8736 -0.4049 +vn -0.9299 -0.0795 -0.3591 +vn -0.9300 -0.1240 -0.3460 +vn -0.9193 -0.1569 -0.3610 +vn -0.7090 0.0010 -0.7052 +usemtl None +s off +f 99/1/1 67/2/1 122/3/1 +f 6/4/1 5/5/1 7/6/1 +f 6/4/1 7/6/1 10/7/1 +f 5/5/1 6/4/1 12/8/1 +f 7/6/1 5/5/1 13/9/1 +f 8/10/2 9/11/2 14/12/2 +f 14/12/2 9/11/2 15/13/2 +f 8/10/2 14/12/2 16/14/2 +f 10/7/1 7/6/1 17/15/1 +f 3/16/3 2/17/3 18/18/3 +f 9/11/2 8/10/2 18/18/2 +f 15/13/2 9/11/2 19/19/2 +f 6/4/1 10/7/1 21/20/1 +f 5/5/1 12/8/1 22/21/1 +f 12/8/1 6/4/1 23/22/1 +f 18/18/2 8/10/2 24/23/2 +f 13/9/1 5/5/1 25/24/1 +f 10/7/1 17/15/1 30/25/1 +f 21/20/1 10/7/1 31/26/1 +f 17/15/1 7/6/1 33/27/1 +f 7/6/1 13/9/1 34/28/1 +f 15/13/2 19/19/2 35/29/2 +f 12/8/1 23/22/1 37/30/1 +f 5/5/1 22/21/1 39/31/1 +f 7/6/1 34/28/1 40/32/1 +f 9/11/4 18/18/4 41/33/4 +f 25/24/1 5/5/1 42/34/1 +f 6/4/1 21/20/1 43/35/1 +f 11/36/5 15/13/5 44/37/5 +f 26/38/6 11/36/6 44/37/6 +f 15/13/2 35/29/2 44/37/2 +f 35/29/7 26/38/7 44/37/7 +f 33/27/1 7/6/1 45/39/1 +f 22/21/1 12/8/1 46/40/1 +f 19/19/8 9/11/8 52/41/8 +f 11/36/9 26/38/9 54/42/9 +f 21/20/1 31/26/1 56/43/1 +f 18/18/10 2/17/10 58/44/10 +f 16/14/11 28/45/11 59/46/11 +f 57/47/12 16/14/12 59/46/12 +f 43/35/13 57/47/13 59/46/13 +f 15/13/14 27/48/14 60/49/14 +f 29/50/15 20/51/15 61/52/15 +f 32/53/16 35/29/16 61/52/16 +f 35/29/17 19/19/17 62/54/17 +f 37/30/1 23/22/1 63/55/1 +f 64/56/18 23/22/18 65/57/18 +f 28/45/19 64/56/19 65/57/19 +f 10/7/20 49/58/20 66/59/20 +f 40/32/1 34/28/1 67/2/1 +f 52/41/21 9/11/21 68/60/21 +f 13/9/1 25/24/1 69/61/1 +f 24/23/22 8/10/22 70/62/22 +f 66/59/23 24/23/23 70/62/23 +f 66/59/24 70/62/24 71/63/24 +f 31/26/1 10/7/1 71/63/1 +f 10/7/25 66/59/25 71/63/25 +f 70/62/26 31/26/26 71/63/26 +f 42/34/1 5/5/1 72/64/1 +f 5/5/27 53/65/27 72/64/27 +f 15/13/28 11/36/28 73/66/28 +f 11/36/29 27/48/29 73/66/29 +f 27/48/30 15/13/30 73/66/30 +f 27/48/31 11/36/31 74/67/31 +f 53/65/32 5/5/32 74/67/32 +f 5/5/33 39/31/33 75/68/33 +f 74/67/34 5/5/34 75/68/34 +f 27/48/35 74/67/35 75/68/35 +f 36/69/36 15/13/36 76/70/36 +f 15/13/37 60/49/37 76/70/37 +f 60/49/38 22/21/38 76/70/38 +f 16/14/39 14/12/39 77/71/39 +f 28/45/40 16/14/40 77/71/40 +f 14/12/41 51/72/41 77/71/41 +f 3/16/42 18/18/42 78/73/42 +f 24/23/43 3/16/43 78/73/43 +f 18/18/44 24/23/44 78/73/44 +f 9/11/45 41/33/45 79/74/45 +f 41/33/46 33/27/46 79/74/46 +f 68/60/47 9/11/47 79/74/47 +f 13/9/48 4/75/48 80/76/48 +f 34/28/1 13/9/1 80/76/1 +f 6/4/49 59/46/49 81/77/49 +f 59/46/50 28/45/50 81/77/50 +f 11/36/51 54/42/51 82/78/51 +f 42/34/52 72/64/52 82/78/52 +f 72/64/53 53/65/53 82/78/53 +f 74/67/54 11/36/54 82/78/54 +f 53/65/55 74/67/55 82/78/55 +f 56/43/56 31/26/56 83/79/56 +f 70/62/57 8/10/57 83/79/57 +f 31/26/58 70/62/58 83/79/58 +f 4/75/59 32/53/59 84/80/59 +f 32/53/60 61/52/60 84/80/60 +f 80/76/61 4/75/61 84/80/61 +f 34/28/62 80/76/62 84/80/62 +f 75/68/63 39/31/63 85/81/63 +f 27/48/64 75/68/64 85/81/64 +f 14/12/2 15/13/2 86/82/2 +f 15/13/65 36/69/65 86/82/65 +f 1/83/66 55/84/66 86/82/66 +f 55/84/67 14/12/67 86/82/67 +f 51/72/41 14/12/41 87/85/41 +f 14/12/68 55/84/68 87/85/68 +f 55/84/69 37/30/69 87/85/69 +f 37/30/70 63/55/70 87/85/70 +f 22/21/1 46/40/1 88/86/1 +f 46/40/71 36/69/71 88/86/71 +f 36/69/72 76/70/72 88/86/72 +f 76/70/73 22/21/73 88/86/73 +f 30/25/1 17/15/1 90/87/1 +f 17/15/74 58/44/74 90/87/74 +f 26/38/75 48/88/75 91/89/75 +f 25/24/76 54/42/76 91/89/76 +f 54/42/77 26/38/77 91/89/77 +f 69/61/78 25/24/78 91/89/78 +f 2/17/79 3/16/79 92/90/79 +f 3/16/80 24/23/80 92/90/80 +f 47/91/81 2/17/81 92/90/81 +f 24/23/82 66/59/82 92/90/82 +f 66/59/83 49/58/83 92/90/83 +f 10/7/1 30/25/1 93/92/1 +f 2/17/84 47/91/84 93/92/84 +f 89/93/85 2/17/85 93/92/85 +f 30/25/86 89/93/86 93/92/86 +f 23/22/87 51/72/87 94/94/87 +f 63/55/1 23/22/1 94/94/1 +f 51/72/88 87/85/88 94/94/88 +f 87/85/89 63/55/89 94/94/89 +f 33/27/1 45/39/1 95/95/1 +f 79/74/90 33/27/90 95/95/90 +f 68/60/91 79/74/91 95/95/91 +f 13/9/1 69/61/1 96/96/1 +f 91/89/92 48/88/92 96/96/92 +f 69/61/93 91/89/93 96/96/93 +f 6/4/1 43/35/1 97/97/1 +f 59/46/94 6/4/94 97/97/94 +f 43/35/95 59/46/95 97/97/95 +f 29/50/96 61/52/96 98/98/96 +f 61/52/97 35/29/97 98/98/97 +f 35/29/17 62/54/17 98/98/17 +f 62/54/98 40/32/98 98/98/98 +f 20/51/99 29/50/99 99/1/99 +f 40/32/1 67/2/1 99/1/1 +f 29/50/100 98/98/100 99/1/100 +f 98/98/101 40/32/101 99/1/101 +f 4/75/102 13/9/102 100/99/102 +f 13/9/103 96/96/103 100/99/103 +f 96/96/104 48/88/104 100/99/104 +f 41/33/105 18/18/105 101/100/105 +f 18/18/106 58/44/106 101/100/106 +f 58/44/107 17/15/107 101/100/107 +f 38/101/108 21/20/108 102/102/108 +f 21/20/109 56/43/109 102/102/109 +f 83/79/110 8/10/110 102/102/110 +f 56/43/111 83/79/111 102/102/111 +f 19/19/112 52/41/112 103/103/112 +f 62/54/17 19/19/17 103/103/17 +f 12/8/113 1/83/113 104/104/113 +f 46/40/114 12/8/114 104/104/114 +f 36/69/115 46/40/115 104/104/115 +f 1/83/116 86/82/116 104/104/116 +f 86/82/117 36/69/117 104/104/117 +f 21/20/118 38/101/118 105/105/118 +f 43/35/119 21/20/119 105/105/119 +f 38/101/120 57/47/120 105/105/120 +f 57/47/121 43/35/121 105/105/121 +f 45/39/122 52/41/122 106/106/122 +f 52/41/123 68/60/123 106/106/123 +f 95/95/124 45/39/124 106/106/124 +f 68/60/125 95/95/125 106/106/125 +f 25/24/1 42/34/1 107/107/1 +f 54/42/126 25/24/126 107/107/126 +f 82/78/127 54/42/127 107/107/127 +f 42/34/128 82/78/128 107/107/128 +f 23/22/1 6/4/1 108/108/1 +f 65/57/129 23/22/129 108/108/129 +f 28/45/130 65/57/130 108/108/130 +f 6/4/131 81/77/131 108/108/131 +f 81/77/132 28/45/132 108/108/132 +f 32/53/133 4/75/133 109/109/133 +f 26/38/134 35/29/134 109/109/134 +f 35/29/135 32/53/135 109/109/135 +f 48/88/136 26/38/136 109/109/136 +f 4/75/137 100/99/137 109/109/137 +f 100/99/138 48/88/138 109/109/138 +f 1/83/139 12/8/139 110/110/139 +f 55/84/140 1/83/140 110/110/140 +f 55/84/141 110/110/141 111/111/141 +f 12/8/1 37/30/1 111/111/1 +f 37/30/142 55/84/142 111/111/142 +f 110/110/143 12/8/143 111/111/143 +f 61/52/144 50/112/144 112/113/144 +f 67/2/145 34/28/145 112/113/145 +f 50/112/146 67/2/146 112/113/146 +f 84/80/147 61/52/147 112/113/147 +f 34/28/148 84/80/148 112/113/148 +f 7/6/1 40/32/1 113/114/1 +f 40/32/149 62/54/149 113/114/149 +f 103/103/150 7/6/150 113/114/150 +f 62/54/151 103/103/151 113/114/151 +f 49/58/152 10/7/152 114/115/152 +f 47/91/153 92/90/153 114/115/153 +f 92/90/154 49/58/154 114/115/154 +f 10/7/1 93/92/1 114/115/1 +f 93/92/155 47/91/155 114/115/155 +f 17/15/1 33/27/1 115/116/1 +f 33/27/156 41/33/156 115/116/156 +f 41/33/157 101/100/157 115/116/157 +f 101/100/158 17/15/158 115/116/158 +f 45/39/1 7/6/1 116/117/1 +f 52/41/159 45/39/159 116/117/159 +f 7/6/160 103/103/160 116/117/160 +f 103/103/161 52/41/161 116/117/161 +f 39/31/1 22/21/1 117/118/1 +f 22/21/162 60/49/162 117/118/162 +f 8/10/2 16/14/2 118/119/2 +f 16/14/163 57/47/163 118/119/163 +f 57/47/164 38/101/164 118/119/164 +f 102/102/165 8/10/165 118/119/165 +f 38/101/166 102/102/166 118/119/166 +f 60/49/167 27/48/167 119/120/167 +f 27/48/168 85/81/168 119/120/168 +f 85/81/169 39/31/169 119/120/169 +f 39/31/170 117/118/170 119/120/170 +f 117/118/171 60/49/171 119/120/171 +f 51/72/172 23/22/172 120/121/172 +f 23/22/173 64/56/173 120/121/173 +f 64/56/174 28/45/174 120/121/174 +f 28/45/175 77/71/175 120/121/175 +f 77/71/41 51/72/41 120/121/41 +f 58/44/176 2/17/176 121/122/176 +f 2/17/177 89/93/177 121/122/177 +f 89/93/178 30/25/178 121/122/178 +f 30/25/179 90/87/179 121/122/179 +f 90/87/180 58/44/180 121/122/180 +f 61/52/181 20/51/181 122/3/181 +f 50/112/182 61/52/182 122/3/182 +f 67/2/183 50/112/183 122/3/183 +f 20/51/184 99/1/184 122/3/184 +o Bowl_hull_2 +v 0.033184 -0.043115 -0.001496 +v 0.021546 -0.080619 0.050235 +v 0.021115 -0.080619 0.050235 +v 0.039651 -0.068111 0.049366 +v 0.021115 -0.040100 -0.009251 +v 0.039651 -0.040100 0.010149 +v 0.021115 -0.076305 0.049794 +v 0.040082 -0.072857 0.048938 +v 0.021546 -0.040100 -0.017020 +v 0.040082 -0.040100 0.002816 +v 0.030600 -0.077600 0.049366 +v 0.040082 -0.058200 0.026950 +v 0.021115 -0.057343 0.010584 +v 0.040082 -0.068977 0.050235 +v 0.040082 -0.039667 0.009280 +v 0.021115 -0.039667 -0.017020 +v 0.021979 -0.078891 0.046785 +v 0.034478 -0.075439 0.048503 +v 0.040082 -0.073286 0.050235 +v 0.024996 -0.040100 -0.013991 +v 0.021979 -0.056914 0.010149 +v 0.040082 -0.050876 0.016608 +v 0.034911 -0.039667 -0.003649 +v 0.021115 -0.039667 -0.010114 +v 0.040082 -0.066387 0.039023 +v 0.034911 -0.040096 -0.003649 +v 0.038359 -0.073286 0.048075 +v 0.021979 -0.050010 -0.001055 +v 0.024132 -0.079320 0.048510 +v 0.021979 -0.076305 0.050235 +v 0.040082 -0.041391 0.004113 +v 0.021979 -0.065529 0.024363 +v 0.028013 -0.041395 -0.009251 +v 0.021115 -0.079753 0.048075 +v 0.039651 -0.039667 0.001953 +v 0.022409 -0.046562 -0.006230 +v 0.028013 -0.076734 0.046351 +v 0.034048 -0.076305 0.050235 +vt 0.980717 0.810475 +vt 1.000000 0.820950 +vt 1.000000 0.894665 +vt 0.115505 0.010573 +vt 1.000000 1.000000 +vt 0.993442 0.894665 +vt 0.403974 0.010573 +vt 0.987079 0.694567 +vt 0.294930 0.010573 +vt 0.653778 0.452570 +vt 0.410435 0.431620 +vt 1.000000 1.000000 +vt 1.000000 0.715712 +vt 0.391053 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.010573 +vt 0.045027 0.010573 +vt 0.230814 0.084190 +vt 0.500000 0.273715 +vt 0.198806 0.000000 +vt 0.102682 0.000000 +vt 0.833301 0.652472 +vt 0.198806 0.010475 +vt 0.974256 0.873519 +vt 0.967893 0.820950 +vt 0.237373 0.252570 +vt 0.987079 0.926285 +vt 0.403974 0.421145 +vt 0.974354 0.968282 +vt 1.000000 0.894665 +vt 0.314213 0.042095 +vt 0.615309 0.631522 +vt 0.948708 0.957807 +vt 0.115505 0.042193 +vt 0.967893 0.978855 +vt 0.282106 0.000000 +vt 0.160435 0.168380 +vt 0.942247 0.905140 +vn 0.4290 -0.8576 -0.2837 +vn -1.0000 -0.0000 0.0000 +vn -0.4800 0.7479 0.4586 +vn -0.3273 0.7689 0.5492 +vn 1.0000 -0.0000 0.0000 +vn 0.0000 -0.0000 1.0000 +vn 0.3342 0.7669 0.5478 +vn 0.4184 0.7386 0.5286 +vn -0.6461 -0.6428 -0.4116 +vn 0.5515 0.5487 -0.6283 +vn 0.5136 -0.7002 -0.4959 +vn 0.0000 1.0000 -0.0000 +vn 0.4422 0.7722 -0.4563 +vn -0.4251 0.8089 0.4061 +vn -0.3056 0.9040 0.2989 +vn 0.4357 -0.7509 -0.4963 +vn 0.5513 -0.6699 -0.4973 +vn 0.7219 0.0000 -0.6920 +vn 0.4078 -0.8164 -0.4088 +vn 0.4342 -0.7544 -0.4923 +vn 0.4258 -0.7569 -0.4958 +vn 0.0769 -0.8462 -0.5274 +vn 0.3360 -0.8009 -0.4957 +vn 0.1571 -0.8408 -0.5180 +vn 0.3247 -0.8053 -0.4961 +vn 0.2808 -0.9204 -0.2721 +vn -0.4531 0.0907 0.8869 +vn -0.3098 0.7324 0.6064 +vn -0.2512 0.6205 0.7429 +vn 0.5779 -0.6500 -0.4935 +vn 0.6612 -0.5317 -0.5292 +vn 0.1619 -0.8439 -0.5115 +vn 0.2323 -0.8355 -0.4979 +vn 0.5106 -0.7022 -0.4962 +vn 0.4689 -0.7311 -0.4957 +vn 0.4642 -0.7338 -0.4960 +vn 0.5394 -0.6712 -0.5085 +vn 0.5501 -0.6477 -0.5271 +vn 0.0000 -0.9281 -0.3722 +vn 0.1862 -0.8985 -0.3975 +vn 0.1903 -0.8704 -0.4541 +vn 0.0494 -0.8573 -0.5124 +vn 0.0922 -0.8554 -0.5097 +vn 0.7508 0.6591 -0.0441 +vn 0.7072 -0.4237 -0.5660 +vn 0.7634 0.0000 -0.6459 +vn 0.3788 -0.7814 -0.4958 +vn 0.3882 -0.7766 -0.4962 +vn 0.3293 -0.7982 -0.5044 +vn 0.3606 -0.7898 -0.4962 +vn 0.3061 -0.8126 -0.4959 +vn 0.2842 -0.8289 -0.4819 +vn 0.2881 -0.8189 -0.4964 +vn 0.2738 -0.8245 -0.4953 +vn 0.3241 -0.9392 0.1137 +vn 0.4167 -0.8503 -0.3216 +vn 0.4034 -0.8546 -0.3271 +usemtl None +s off +f 130/123/185 141/124/185 160/125/185 +f 127/126/186 125/127/186 129/128/186 +f 128/129/187 127/126/187 129/128/187 +f 126/130/188 128/129/188 129/128/188 +f 132/131/189 130/123/189 134/132/189 +f 125/127/186 127/126/186 135/133/186 +f 125/127/190 124/134/190 136/135/190 +f 130/123/189 132/131/189 136/135/189 +f 128/129/191 126/130/191 137/136/191 +f 126/130/192 136/135/192 137/136/192 +f 136/135/189 132/131/189 137/136/189 +f 135/133/186 127/126/186 138/137/186 +f 131/138/193 135/133/193 138/137/193 +f 136/135/190 124/134/190 141/124/190 +f 130/123/189 136/135/189 141/124/189 +f 131/138/194 138/137/194 142/139/194 +f 134/132/195 123/140/195 144/141/195 +f 132/131/189 134/132/189 144/141/189 +f 138/137/196 137/136/196 145/142/196 +f 142/139/197 138/137/197 145/142/197 +f 127/126/198 128/129/198 146/143/198 +f 128/129/199 137/136/199 146/143/199 +f 138/137/186 127/126/186 146/143/186 +f 137/136/196 138/137/196 146/143/196 +f 134/132/189 130/123/189 147/144/189 +f 131/138/200 142/139/200 147/144/200 +f 144/141/201 123/140/201 148/145/201 +f 142/139/202 145/142/202 148/145/202 +f 130/123/203 140/146/203 149/147/203 +f 147/144/204 130/123/204 149/147/204 +f 131/138/205 147/144/205 149/147/205 +f 135/133/206 131/138/206 150/148/206 +f 140/146/207 133/149/207 150/148/207 +f 143/150/208 135/133/208 150/148/208 +f 133/149/209 143/150/209 150/148/209 +f 133/149/210 124/134/210 151/151/210 +f 129/128/211 125/127/211 152/152/211 +f 126/130/212 129/128/212 152/152/212 +f 125/127/190 136/135/190 152/152/190 +f 136/135/213 126/130/213 152/152/213 +f 132/131/189 144/141/189 153/153/189 +f 144/141/214 148/145/214 153/153/214 +f 148/145/215 132/131/215 153/153/215 +f 135/133/216 143/150/216 154/154/216 +f 151/151/217 139/155/217 154/154/217 +f 123/140/218 134/132/218 155/156/218 +f 134/132/219 147/144/219 155/156/219 +f 147/144/220 142/139/220 155/156/220 +f 148/145/221 123/140/221 155/156/221 +f 142/139/222 148/145/222 155/156/222 +f 124/134/223 125/127/223 156/157/223 +f 125/127/186 135/133/186 156/157/186 +f 151/151/224 124/134/224 156/157/224 +f 139/155/225 151/151/225 156/157/225 +f 135/133/226 154/154/226 156/157/226 +f 154/154/227 139/155/227 156/157/227 +f 137/136/228 132/131/228 157/158/228 +f 145/142/196 137/136/196 157/158/196 +f 132/131/229 148/145/229 157/158/229 +f 148/145/230 145/142/230 157/158/230 +f 149/147/231 140/146/231 158/159/231 +f 131/138/232 149/147/232 158/159/232 +f 150/148/233 131/138/233 158/159/233 +f 140/146/234 150/148/234 158/159/234 +f 143/150/235 133/149/235 159/160/235 +f 133/149/236 151/151/236 159/160/236 +f 154/154/237 143/150/237 159/160/237 +f 151/151/238 154/154/238 159/160/238 +f 124/134/239 133/149/239 160/125/239 +f 140/146/240 130/123/240 160/125/240 +f 133/149/241 140/146/241 160/125/241 +f 141/124/190 124/134/190 160/125/190 +o Bowl_hull_3 +v 0.071125 -0.028888 0.037727 +v 0.040084 -0.026731 -0.010980 +v 0.040517 -0.026731 -0.010980 +v 0.040084 -0.043972 0.007990 +v 0.074570 -0.026731 0.049801 +v 0.070263 -0.043972 0.048507 +v 0.040084 -0.043540 0.014887 +v 0.040517 -0.026731 -0.003652 +v 0.065948 -0.043972 0.049801 +v 0.078884 -0.026731 0.049801 +v 0.050000 -0.042678 0.018332 +v 0.042241 -0.027163 -0.008823 +v 0.074141 -0.036644 0.048075 +v 0.040950 -0.032766 -0.004946 +v 0.071550 -0.043110 0.050232 +v 0.052158 -0.027163 0.006264 +v 0.065086 -0.043972 0.040747 +v 0.065948 -0.043540 0.049801 +v 0.074570 -0.027163 0.050232 +v 0.071983 -0.042247 0.049369 +v 0.042674 -0.043972 0.010572 +v 0.040084 -0.043972 0.014887 +v 0.076727 -0.032766 0.049369 +v 0.072846 -0.026731 0.047212 +v 0.040084 -0.026731 -0.004515 +v 0.077156 -0.027593 0.046781 +v 0.055606 -0.043972 0.027380 +v 0.040517 -0.036644 -0.001064 +v 0.066381 -0.043972 0.050232 +v 0.058193 -0.027163 0.015749 +v 0.078884 -0.027163 0.050232 +v 0.040084 -0.043110 0.014455 +v 0.064657 -0.026731 0.026091 +v 0.041379 -0.029749 -0.007529 +v 0.051296 -0.029318 0.006696 +v 0.056036 -0.042247 0.026091 +v 0.068968 -0.034921 0.038590 +v 0.040084 -0.034059 -0.004083 +vt 0.098571 0.022318 +vt 0.162001 0.011159 +vt 0.112666 0.000000 +vt 0.000000 0.011159 +vt 0.000000 0.000000 +vt 0.992952 0.888802 +vt 0.309906 0.000000 +vt 0.422572 0.000000 +vt 0.119714 0.011159 +vt 0.971809 0.777800 +vt 0.992952 0.666601 +vt 0.992952 1.000000 +vt 0.035239 0.055599 +vt 0.281715 0.311179 +vt 0.845047 0.644381 +vt 0.992952 0.666601 +vt 1.000000 0.888802 +vt 1.000000 0.810983 +vt 0.985904 0.822142 +vt 0.352095 0.066758 +vt 0.422572 0.000000 +vt 0.964761 0.877741 +vt 0.985904 0.944401 +vt 0.950666 0.844362 +vt 0.105619 0.000000 +vt 0.795713 0.800020 +vt 0.943618 0.955462 +vt 0.478857 0.255579 +vt 0.626664 0.400059 +vt 1.000000 0.677760 +vt 0.436668 0.466719 +vt 1.000000 1.000000 +vt 0.415525 0.000000 +vt 0.605619 0.633320 +vt 0.056382 0.033379 +vt 0.288763 0.288959 +vt 0.605619 0.411120 +vt 0.809808 0.744420 +vn 0.3783 -0.6757 -0.6327 +vn 0.0000 1.0000 0.0000 +vn -1.0000 -0.0000 0.0000 +vn 0.0000 -1.0000 -0.0000 +vn 0.7188 0.5100 -0.4725 +vn -0.8035 0.0000 0.5953 +vn -0.7277 0.4847 0.4854 +vn 0.0000 0.7066 0.7076 +vn -0.7442 0.3772 0.5513 +vn 0.7450 -0.6201 -0.2460 +vn 0.7282 -0.4834 -0.4858 +vn 0.7352 -0.4624 -0.4956 +vn 0.8166 -0.4086 -0.4077 +vn 0.8943 -0.4474 0.0016 +vn 0.8101 -0.3147 -0.4947 +vn 0.8656 -0.2797 -0.4154 +vn 0.6729 -0.5493 -0.4955 +vn 0.6098 -0.6387 -0.4692 +vn 0.6536 -0.5707 -0.4971 +vn 0.5205 -0.6757 -0.5220 +vn 0.6294 -0.5996 -0.4943 +vn 0.1543 -0.9250 0.3471 +vn -0.7058 0.0000 0.7084 +vn 0.0000 -0.0000 1.0000 +vn -0.5375 0.2618 0.8016 +vn 0.7997 -0.3367 -0.4970 +vn 0.7898 -0.3613 -0.4956 +vn 0.8158 -0.2864 -0.5025 +vn 0.9043 -0.3017 -0.3021 +vn 0.8310 -0.3822 0.4041 +vn -0.7274 0.4858 0.4846 +vn -0.7274 0.4859 0.4846 +vn -0.7188 0.5241 0.4568 +vn -0.7931 0.4610 0.3980 +vn 0.6549 0.6240 -0.4264 +vn 0.8545 0.0833 -0.5128 +vn 0.8229 0.2209 -0.5236 +vn 0.8332 -0.2089 -0.5120 +vn 0.6212 -0.5065 -0.5980 +vn 0.4381 -0.6196 -0.6512 +vn 0.7180 -0.4879 -0.4964 +vn 0.7637 -0.4060 -0.5020 +vn 0.7441 -0.4473 -0.4962 +vn 0.6806 -0.5395 -0.4956 +vn 0.6886 -0.5361 -0.4883 +vn 0.6925 -0.5234 -0.4965 +vn 0.7066 -0.5050 -0.4958 +vn 0.7676 -0.4094 -0.4930 +vn 0.7810 -0.3783 -0.4969 +vn 0.7871 -0.3668 -0.4959 +vn 0.7671 -0.4063 -0.4964 +vn 0.7628 -0.4152 -0.4956 +vn 0.0000 -0.6853 -0.7282 +vn 0.3066 -0.6619 -0.6840 +vn -0.1858 -0.7594 -0.6235 +usemtl None +s off +f 174/161/242 188/162/242 198/163/242 +f 163/164/243 162/165/243 165/166/243 +f 162/165/244 164/167/244 167/168/244 +f 165/166/243 162/165/243 168/169/243 +f 164/167/245 166/170/245 169/171/245 +f 163/164/243 165/166/243 170/172/243 +f 172/173/246 163/164/246 176/174/246 +f 166/170/245 164/167/245 177/175/245 +f 167/168/247 169/171/247 178/176/247 +f 165/166/248 167/168/248 179/177/248 +f 170/172/249 165/166/249 179/177/249 +f 167/168/250 178/176/250 179/177/250 +f 175/178/251 166/170/251 180/179/251 +f 166/170/252 177/175/252 180/179/252 +f 177/175/253 172/173/253 180/179/253 +f 177/175/245 164/167/245 181/180/245 +f 167/168/244 164/167/244 182/181/244 +f 164/167/245 169/171/245 182/181/245 +f 169/171/247 167/168/247 182/181/247 +f 180/179/254 173/182/254 183/183/254 +f 175/178/255 180/179/255 183/183/255 +f 165/166/243 168/169/243 184/184/243 +f 162/165/244 167/168/244 185/185/244 +f 168/169/243 162/165/243 185/185/243 +f 183/183/256 161/186/256 186/187/256 +f 170/172/257 183/183/257 186/187/257 +f 171/188/258 174/161/258 187/189/258 +f 181/180/259 171/188/259 187/189/259 +f 177/175/245 181/180/245 187/189/245 +f 174/161/260 171/188/260 188/162/260 +f 181/180/261 164/167/261 188/162/261 +f 171/188/262 181/180/262 188/162/262 +f 169/171/245 166/170/245 189/190/245 +f 166/170/263 175/178/263 189/190/263 +f 178/176/264 169/171/264 189/190/264 +f 175/178/265 179/177/265 189/190/265 +f 179/177/266 178/176/266 189/190/266 +f 161/186/267 183/183/267 190/191/267 +f 183/183/268 173/182/268 190/191/268 +f 186/187/269 161/186/269 190/191/269 +f 179/177/265 175/178/265 191/192/265 +f 170/172/249 179/177/249 191/192/249 +f 183/183/270 170/172/270 191/192/270 +f 175/178/271 183/183/271 191/192/271 +f 167/168/272 165/166/272 192/193/272 +f 165/166/273 184/184/273 192/193/273 +f 184/184/274 168/169/274 192/193/274 +f 185/185/244 167/168/244 192/193/244 +f 168/169/275 185/185/275 192/193/275 +f 163/164/243 170/172/243 193/194/243 +f 176/174/276 163/164/276 193/194/276 +f 170/172/277 186/187/277 193/194/277 +f 190/191/278 176/174/278 193/194/278 +f 186/187/279 190/191/279 193/194/279 +f 163/164/280 172/173/280 194/195/280 +f 174/161/281 163/164/281 194/195/281 +f 172/173/282 177/175/282 194/195/282 +f 172/173/283 176/174/283 195/196/283 +f 180/179/284 172/173/284 195/196/284 +f 187/189/285 174/161/285 196/197/285 +f 177/175/286 187/189/286 196/197/286 +f 174/161/287 194/195/287 196/197/287 +f 194/195/288 177/175/288 196/197/288 +f 173/182/289 180/179/289 197/198/289 +f 176/174/290 190/191/290 197/198/290 +f 190/191/291 173/182/291 197/198/291 +f 195/196/292 176/174/292 197/198/292 +f 180/179/293 195/196/293 197/198/293 +f 162/165/294 163/164/294 198/163/294 +f 164/167/244 162/165/244 198/163/244 +f 163/164/295 174/161/295 198/163/295 +f 188/162/296 164/167/296 198/163/296 +o Bowl_hull_4 +v -0.022432 -0.027589 -0.050212 +v -0.014237 -0.034487 -0.033402 +v -0.014669 -0.034487 -0.033402 +v -0.030618 -0.011640 -0.033404 +v -0.014237 -0.029314 -0.050212 +v -0.029756 -0.022850 -0.033404 +v -0.033205 -0.011640 -0.050212 +v -0.014237 -0.029314 -0.033402 +v -0.035362 -0.012074 -0.033404 +v -0.030618 -0.011640 -0.050212 +v -0.030618 -0.018108 -0.050212 +v -0.014669 -0.032333 -0.050212 +v -0.022860 -0.029746 -0.033835 +v -0.025874 -0.024570 -0.049352 +v -0.033637 -0.016386 -0.034266 +v -0.018118 -0.030607 -0.050212 +v -0.032775 -0.013799 -0.050212 +v -0.025444 -0.027589 -0.033835 +v -0.018980 -0.032333 -0.033835 +v -0.035362 -0.011640 -0.034266 +v -0.028029 -0.021991 -0.049783 +v -0.031480 -0.020265 -0.034266 +v -0.027601 -0.025433 -0.033835 +v -0.014237 -0.032333 -0.050212 +v -0.030186 -0.012074 -0.033404 +v -0.020273 -0.029314 -0.049783 +v -0.034499 -0.014662 -0.033835 +v -0.022860 -0.029746 -0.033404 +vt 0.603720 0.367365 +vt 0.698091 0.469460 +vt 0.792462 0.591817 +vt 0.773568 1.000000 +vt 0.698091 0.612079 +vt 0.000000 0.102095 +vt 1.000000 0.979542 +vt 1.000000 1.000000 +vt 0.773568 1.000000 +vt 0.490651 0.265368 +vt 0.018992 0.000000 +vt 0.000000 0.224550 +vt 0.000000 0.224550 +vt 0.283113 0.224550 +vt 0.905727 0.979542 +vt 0.830152 0.816269 +vt 0.094469 0.122455 +vt 0.207734 0.081637 +vt 0.792462 0.591817 +vt 0.565932 0.449099 +vt 0.905727 0.775450 +vt 0.000000 0.000000 +vt 0.453059 0.347103 +vt 0.377484 0.183731 +vt 0.905727 1.000000 +vt 0.018992 0.245008 +vt 0.773568 0.714272 +vt 0.132256 0.040818 +vn -0.5787 -0.5789 0.5745 +vn 0.0000 -0.0000 -1.0000 +vn 0.0000 0.0000 1.0000 +vn 1.0000 0.0000 0.0000 +vn -0.0002 -0.0001 1.0000 +vn -0.0001 0.0000 1.0000 +vn -0.0000 0.0001 1.0000 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -0.9919 -0.1271 +vn -0.8878 -0.4443 -0.1201 +vn -0.6362 -0.7626 -0.1170 +vn -0.6716 -0.7306 -0.1235 +vn -0.4348 -0.8932 -0.1144 +vn -0.4446 -0.8881 -0.1170 +vn -0.0814 0.8903 0.4480 +vn -0.9722 -0.1937 -0.1315 +vn -0.9619 -0.2444 -0.1230 +vn -0.4514 -0.3898 -0.8027 +vn -0.6519 -0.6181 -0.4393 +vn -0.8684 -0.4829 -0.1123 +vn -0.8198 -0.5599 -0.1200 +vn -0.8081 -0.5776 -0.1155 +vn -0.7021 -0.7023 -0.1172 +vn -0.7722 -0.6250 -0.1142 +vn -0.7519 -0.6483 -0.1197 +vn 0.0013 0.0013 1.0000 +vn 0.7341 0.6791 0.0000 +vn 0.7085 0.7057 0.0000 +vn 0.7334 0.6798 -0.0013 +vn -0.6050 -0.7872 -0.1194 +vn -0.5305 -0.7584 -0.3786 +vn -0.5515 -0.8267 -0.1118 +vn -0.5280 -0.8412 -0.1165 +vn -0.6287 -0.3270 0.7056 +vn -0.9480 -0.2966 -0.1155 +vn -0.8997 -0.4206 -0.1169 +vn -0.8409 -0.4733 0.2625 +vn -0.8576 -0.4769 0.1923 +vn -0.0005 -0.0005 1.0000 +vn -0.6405 -0.7679 0.0000 +vn -0.4134 -0.7138 0.5653 +vn -0.5549 -0.8319 0.0000 +vn -0.5783 -0.5784 0.5753 +usemtl None +s off +f 221/199/297 216/200/297 226/201/297 +f 203/202/298 199/203/298 205/204/298 +f 201/205/299 200/206/299 206/207/299 +f 200/206/300 203/202/300 206/207/300 +f 204/208/301 201/205/301 207/209/301 +f 201/205/302 206/207/302 207/209/302 +f 206/207/303 202/210/303 207/209/303 +f 205/204/304 202/210/304 208/211/304 +f 203/202/298 205/204/298 208/211/298 +f 205/204/298 199/203/298 209/212/298 +f 200/206/305 201/205/305 210/213/305 +f 199/203/298 203/202/298 210/213/298 +f 199/203/298 210/213/298 214/214/298 +f 205/204/298 209/212/298 215/215/298 +f 209/212/306 213/216/306 215/215/306 +f 199/203/307 211/217/307 216/200/307 +f 212/218/308 199/203/308 216/200/308 +f 210/213/309 201/205/309 217/219/309 +f 214/214/310 210/213/310 217/219/310 +f 202/210/304 205/204/304 218/220/304 +f 207/209/311 202/210/311 218/220/311 +f 205/204/312 215/215/312 218/220/312 +f 215/215/313 207/209/313 218/220/313 +f 209/212/314 199/203/314 219/221/314 +f 199/203/315 212/218/315 219/221/315 +f 213/216/316 209/212/316 220/222/316 +f 209/212/317 219/221/317 220/222/317 +f 219/221/318 204/208/318 220/222/318 +f 212/218/319 216/200/319 221/199/319 +f 204/208/320 219/221/320 221/199/320 +f 219/221/321 212/218/321 221/199/321 +f 203/202/300 200/206/300 222/223/300 +f 200/206/305 210/213/305 222/223/305 +f 210/213/298 203/202/298 222/223/298 +f 202/210/322 206/207/322 223/224/322 +f 206/207/323 203/202/323 223/224/323 +f 208/211/324 202/210/324 223/224/324 +f 203/202/325 208/211/325 223/224/325 +f 211/217/326 199/203/326 224/225/326 +f 199/203/327 214/214/327 224/225/327 +f 217/219/328 211/217/328 224/225/328 +f 214/214/329 217/219/329 224/225/329 +f 204/208/330 207/209/330 225/226/330 +f 207/209/331 215/215/331 225/226/331 +f 215/215/332 213/216/332 225/226/332 +f 220/222/333 204/208/333 225/226/333 +f 213/216/334 220/222/334 225/226/334 +f 201/205/335 204/208/335 226/201/335 +f 216/200/336 211/217/336 226/201/336 +f 217/219/337 201/205/337 226/201/337 +f 211/217/338 217/219/338 226/201/338 +f 204/208/339 221/199/339 226/201/339 +o Bowl_hull_5 +v -0.012940 -0.033197 -0.049352 +v 0.005163 -0.036644 -0.033404 +v 0.005163 -0.032335 -0.033404 +v -0.014237 -0.029748 -0.033404 +v 0.005163 -0.032335 -0.050214 +v -0.013373 -0.034920 -0.033404 +v -0.002598 -0.035351 -0.050214 +v -0.014237 -0.029748 -0.050214 +v -0.004749 -0.037075 -0.033835 +v 0.005163 -0.035351 -0.048058 +v -0.014237 -0.032335 -0.050214 +v -0.012940 -0.029748 -0.050214 +v 0.002575 -0.037075 -0.035128 +v -0.008629 -0.034489 -0.049783 +v -0.014237 -0.034489 -0.034697 +v -0.009491 -0.036213 -0.033835 +v -0.012940 -0.029748 -0.033404 +v 0.002575 -0.035351 -0.050214 +v 0.004729 -0.037075 -0.033404 +v -0.000011 -0.037075 -0.035559 +v 0.005163 -0.034920 -0.050214 +v -0.006474 -0.034920 -0.049783 +vt 0.244616 0.974354 +vt 0.289056 0.025646 +vt 0.400157 0.025646 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.044538 1.000000 +vt 0.599941 0.000000 +vt 0.000000 0.000000 +vt 1.000000 0.128230 +vt 0.000000 0.000000 +vt 0.066856 0.000000 +vt 0.066856 0.051292 +vt 0.000000 0.923062 +vt 0.489037 0.974354 +vt 0.066856 1.000000 +vt 0.866582 0.000000 +vt 0.866582 0.897416 +vt 0.977584 1.000000 +vt 0.733262 0.871770 +vt 1.000000 0.000000 +vn -0.1948 -0.9740 -0.1158 +vn 0.0000 0.0000 1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn 0.1414 0.9899 0.0000 +vn 0.0000 1.0000 0.0000 +vn -0.2992 -0.8611 -0.4111 +vn -0.1346 -0.5192 -0.8440 +vn -0.8443 -0.1410 0.5170 +vn -0.4933 -0.8616 -0.1196 +vn -0.1068 -0.5878 0.8019 +vn -0.2959 -0.9478 -0.1185 +vn -0.3215 -0.9403 -0.1114 +vn -0.3243 -0.9410 -0.0970 +vn 0.0905 -0.9895 -0.1131 +vn -0.0425 -0.3566 0.9333 +vn 0.7021 -0.7094 -0.0626 +vn 0.0000 -1.0000 0.0000 +vn 0.0945 -0.9890 -0.1135 +vn -0.0400 -0.9932 -0.1098 +vn 0.0000 -0.9932 -0.1168 +vn 0.0189 -0.9934 -0.1135 +vn 0.1612 -0.9678 -0.1936 +vn -0.1229 -0.9852 -0.1198 +vn -0.1544 -0.7721 -0.6164 +vn -0.1776 -0.9776 -0.1129 +usemtl None +s off +f 242/227/340 240/228/340 248/229/340 +f 228/230/341 229/231/341 230/232/341 +f 229/231/342 228/230/342 231/233/342 +f 228/230/341 230/232/341 232/234/341 +f 231/233/343 233/235/343 234/236/343 +f 231/233/342 228/230/342 236/237/342 +f 230/232/344 234/236/344 237/238/344 +f 234/236/343 233/235/343 237/238/343 +f 229/231/345 231/233/345 238/239/345 +f 234/236/346 230/232/346 238/239/346 +f 231/233/343 234/236/343 238/239/343 +f 227/240/347 237/238/347 240/228/347 +f 237/238/348 233/235/348 240/228/348 +f 232/234/349 230/232/349 241/241/349 +f 237/238/350 227/240/350 241/241/350 +f 230/232/344 237/238/344 241/241/344 +f 235/242/351 232/234/351 242/227/351 +f 227/240/352 240/228/352 242/227/352 +f 241/241/353 227/240/353 242/227/353 +f 232/234/354 241/241/354 242/227/354 +f 230/232/341 229/231/341 243/243/341 +f 229/231/345 238/239/345 243/243/345 +f 238/239/346 230/232/346 243/243/346 +f 233/235/343 231/233/343 244/244/343 +f 239/245/355 244/244/355 245/246/355 +f 228/230/341 232/234/341 245/246/341 +f 232/234/356 235/242/356 245/246/356 +f 236/237/357 228/230/357 245/246/357 +f 235/242/358 239/245/358 245/246/358 +f 244/244/359 236/237/359 245/246/359 +f 235/242/360 233/235/360 246/247/360 +f 239/245/358 235/242/358 246/247/358 +f 233/235/361 244/244/361 246/247/361 +f 244/244/362 239/245/362 246/247/362 +f 231/233/342 236/237/342 247/248/342 +f 244/244/343 231/233/343 247/248/343 +f 236/237/363 244/244/363 247/248/363 +f 233/235/364 235/242/364 248/229/364 +f 240/228/365 233/235/365 248/229/365 +f 235/242/366 242/227/366 248/229/366 +o Bowl_hull_6 +v 0.014650 0.032333 -0.050214 +v 0.029737 0.022419 -0.033404 +v 0.029737 0.022419 -0.033835 +v 0.005163 0.032333 -0.050214 +v 0.005163 0.036644 -0.033404 +v 0.005163 0.032333 -0.033404 +v 0.023697 0.022419 -0.050214 +v 0.018958 0.032333 -0.033404 +v 0.025855 0.024575 -0.049783 +v 0.023697 0.022419 -0.033404 +v 0.005163 0.034918 -0.050214 +v 0.009479 0.036212 -0.033835 +v 0.025422 0.027592 -0.033835 +v 0.020250 0.029317 -0.049783 +v 0.027146 0.022419 -0.050214 +v 0.008613 0.034488 -0.049783 +v 0.014650 0.034488 -0.033835 +v 0.029737 0.022851 -0.033835 +v 0.011632 0.033625 -0.049783 +v 0.022838 0.029746 -0.033835 +v 0.022408 0.027592 -0.050214 +v 0.007321 0.036644 -0.033835 +v 0.017662 0.031039 -0.048921 +v 0.027579 0.025438 -0.033404 +v 0.027579 0.022851 -0.048058 +vt 0.842013 0.025646 +vt 1.000000 0.974354 +vt 0.912197 0.128230 +vt 1.000000 1.000000 +vt 0.000000 1.000000 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 0.754209 0.000000 +vt 1.000000 0.974354 +vt 0.386061 0.000000 +vt 0.561374 1.000000 +vt 0.754209 1.000000 +vt 0.000000 0.000000 +vt 0.175607 0.974354 +vt 0.894577 0.000000 +vt 0.140368 0.025646 +vt 0.386061 0.974354 +vt 0.263215 0.025646 +vt 0.613939 0.025646 +vt 0.719264 0.974354 +vt 0.701742 0.000000 +vt 0.824393 0.974354 +vt 0.087803 0.974354 +vt 0.508614 0.076938 +vt 0.912197 1.000000 +vn 0.7573 0.6428 -0.1149 +vn 0.0000 0.0000 1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.4717 -0.8818 -0.0000 +vn -0.0000 -1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.1318 0.4218 0.8970 +vn 0.1733 0.6359 -0.7521 +vn 0.1689 0.5066 0.8455 +vn 1.0000 0.0000 0.0000 +vn 0.1987 0.6949 -0.6912 +vn 0.2730 0.9547 -0.1180 +vn 0.3143 0.9429 -0.1105 +vn 0.3760 0.9187 -0.1209 +vn 0.5428 0.8325 -0.1105 +vn 0.6053 0.7870 -0.1194 +vn 0.6623 0.7392 -0.1219 +vn 0.4063 0.6648 -0.6268 +vn 0.4796 0.4393 -0.7596 +vn 0.6360 0.7628 -0.1170 +vn -0.0204 0.9946 -0.1021 +vn 0.1400 0.6997 0.7006 +vn 0.1378 0.9830 -0.1217 +vn 0.1948 0.9740 -0.1158 +vn 0.4733 0.8416 -0.2604 +vn 0.5237 0.8442 -0.1141 +vn 0.4341 0.8932 -0.1175 +vn 0.4535 0.8842 -0.1116 +vn 0.7132 0.6921 -0.1116 +vn 0.7031 0.5025 0.5031 +vn 0.7536 0.6475 -0.1135 +vn 0.4563 0.5705 0.6829 +vn 0.5412 0.6491 0.5345 +vn 0.9665 -0.2061 -0.1529 +vn 0.8018 0.5341 -0.2680 +vn 0.9887 0.0000 -0.1500 +usemtl None +s off +f 257/249/367 266/250/367 273/251/367 +f 250/252/368 253/253/368 254/254/368 +f 253/253/369 252/255/369 254/254/369 +f 254/254/370 252/255/370 255/256/370 +f 251/257/371 250/252/371 255/256/371 +f 252/255/372 249/258/372 255/256/372 +f 253/253/368 250/252/368 256/259/368 +f 250/252/368 254/254/368 258/260/368 +f 254/254/370 255/256/370 258/260/370 +f 255/256/371 250/252/371 258/260/371 +f 249/258/372 252/255/372 259/261/372 +f 252/255/369 253/253/369 259/261/369 +f 253/253/373 256/259/373 260/262/373 +f 255/256/372 249/258/372 263/263/372 +f 251/257/371 255/256/371 263/263/371 +f 249/258/374 259/261/374 264/264/374 +f 260/262/375 256/259/375 265/265/375 +f 250/252/376 251/257/376 266/250/376 +f 249/258/377 264/264/377 267/266/377 +f 264/264/378 260/262/378 267/266/378 +f 260/262/379 265/265/379 267/266/379 +f 265/265/380 249/258/380 267/266/380 +f 262/267/381 256/259/381 268/268/381 +f 262/267/382 268/268/382 269/269/382 +f 261/270/383 257/249/383 269/269/383 +f 249/258/384 262/267/384 269/269/384 +f 263/263/372 249/258/372 269/269/372 +f 257/249/385 263/263/385 269/269/385 +f 268/268/386 261/270/386 269/269/386 +f 259/261/387 253/253/387 270/271/387 +f 253/253/388 260/262/388 270/271/388 +f 264/264/389 259/261/389 270/271/389 +f 260/262/390 264/264/390 270/271/390 +f 262/267/391 249/258/391 271/272/391 +f 256/259/392 262/267/392 271/272/392 +f 249/258/393 265/265/393 271/272/393 +f 265/265/394 256/259/394 271/272/394 +f 256/259/368 250/252/368 272/273/368 +f 257/249/395 261/270/395 272/273/395 +f 250/252/396 266/250/396 272/273/396 +f 266/250/397 257/249/397 272/273/397 +f 268/268/398 256/259/398 272/273/398 +f 261/270/399 268/268/399 272/273/399 +f 251/257/400 263/263/400 273/251/400 +f 263/263/401 257/249/401 273/251/401 +f 266/250/402 251/257/402 273/251/402 +o Bowl_hull_7 +v 0.034477 0.009055 -0.048921 +v 0.024133 0.022418 -0.050214 +v 0.027583 0.022418 -0.050214 +v 0.024133 0.022418 -0.033404 +v 0.032323 0.003453 -0.050214 +v 0.036201 0.009488 -0.033404 +v 0.032323 0.003453 -0.033404 +v 0.030599 0.021554 -0.033404 +v 0.037065 0.003018 -0.034697 +v 0.032753 0.013793 -0.050214 +v 0.035339 0.003018 -0.049783 +v 0.032753 0.018104 -0.034266 +v 0.024133 0.021983 -0.033404 +v 0.029738 0.022418 -0.033404 +v 0.030170 0.018968 -0.049783 +v 0.024133 0.021983 -0.050214 +v 0.034477 0.014657 -0.033835 +v 0.032753 0.003018 -0.033404 +v 0.037065 0.004744 -0.033404 +v 0.034909 0.006037 -0.050214 +v 0.032753 0.003018 -0.050214 +v 0.034047 0.010350 -0.049783 +v 0.030599 0.021554 -0.034266 +v 0.031461 0.016812 -0.049352 +v 0.036633 0.006899 -0.034697 +vt 0.911022 1.000000 +vt 0.844362 0.000000 +vt 0.799922 0.923062 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 0.977584 0.000000 +vt 0.666503 1.000000 +vt 0.977584 1.000000 +vt 0.044538 1.000000 +vt 0.444597 0.000000 +vt 0.022416 1.000000 +vt 0.000000 1.000000 +vt 0.177858 0.025646 +vt 0.022416 0.000000 +vt 0.400059 0.974354 +vt 0.222396 0.948708 +vt 1.000000 1.000000 +vt 1.000000 0.025646 +vt 1.000000 0.923062 +vt 1.000000 0.000000 +vt 0.688821 0.076938 +vt 0.622064 0.025646 +vt 0.044538 0.948708 +vt 0.288958 0.051292 +vn 0.9850 0.1273 -0.1165 +vn 0.0000 1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -0.0000 1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.9146 -0.4043 0.0000 +vn 0.5973 0.3580 -0.7177 +vn 0.5217 0.2422 0.8180 +vn 0.8442 0.4573 0.2796 +vn -0.7108 -0.7034 0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.9899 0.0848 -0.1132 +vn 0.2334 -0.5830 0.7782 +vn 0.9854 0.1238 -0.1168 +vn 0.1633 -0.1166 -0.9797 +vn 0.9630 0.2443 -0.1138 +vn 0.9457 0.3064 -0.1083 +vn 0.9345 0.3366 -0.1161 +vn 0.9636 0.2093 -0.1666 +vn 0.7699 0.2140 -0.6013 +vn 0.8482 0.5296 0.0000 +vn 0.6623 0.7445 -0.0849 +vn 0.7084 0.7058 0.0000 +vn 0.8015 0.5858 -0.1198 +vn 0.8430 0.5264 -0.1111 +vn 0.8441 0.4462 -0.2973 +vn 0.8621 0.4932 -0.1161 +vn 0.9005 0.4188 -0.1169 +vn 0.8942 0.4331 -0.1137 +vn 0.9692 0.2185 -0.1138 +vn 0.9834 0.1790 -0.0300 +vn 0.9745 0.1903 -0.1189 +usemtl None +s off +f 292/274/403 293/275/403 298/276/403 +f 276/277/404 275/278/404 277/279/404 +f 275/278/405 276/277/405 278/280/405 +f 279/281/406 277/279/406 280/282/406 +f 277/279/406 279/281/406 281/283/406 +f 278/280/405 276/277/405 283/284/405 +f 277/279/407 275/278/407 286/285/407 +f 278/280/408 280/282/408 286/285/408 +f 280/282/406 277/279/406 286/285/406 +f 276/277/404 277/279/404 287/286/404 +f 277/279/406 281/283/406 287/286/406 +f 283/284/409 276/277/409 288/287/409 +f 275/278/405 278/280/405 289/288/405 +f 286/285/407 275/278/407 289/288/407 +f 278/280/408 286/285/408 289/288/408 +f 281/283/410 279/281/410 290/289/410 +f 285/290/411 281/283/411 290/289/411 +f 280/282/412 278/280/412 291/291/412 +f 279/281/406 280/282/406 291/291/406 +f 284/292/413 282/293/413 291/291/413 +f 282/293/414 284/292/414 292/274/414 +f 279/281/406 291/291/406 292/274/406 +f 291/291/415 282/293/415 292/274/415 +f 278/280/405 283/284/405 293/275/405 +f 292/274/416 284/292/416 293/275/416 +f 291/291/412 278/280/412 294/294/412 +f 284/292/413 291/291/413 294/294/413 +f 278/280/405 293/275/405 294/294/405 +f 293/275/417 284/292/417 294/294/417 +f 279/281/418 274/295/418 295/296/418 +f 290/289/419 279/281/419 295/296/419 +f 283/284/420 290/289/420 295/296/420 +f 274/295/421 293/275/421 295/296/421 +f 293/275/422 283/284/422 295/296/422 +f 281/283/423 285/290/423 296/297/423 +f 276/277/424 287/286/424 296/297/424 +f 287/286/425 281/283/425 296/297/425 +f 288/287/426 276/277/426 296/297/426 +f 285/290/427 288/287/427 296/297/427 +f 283/284/428 288/287/428 297/298/428 +f 288/287/429 285/290/429 297/298/429 +f 290/289/430 283/284/430 297/298/430 +f 285/290/431 290/289/431 297/298/431 +f 274/295/432 279/281/432 298/276/432 +f 279/281/433 292/274/433 298/276/433 +f 293/275/434 274/295/434 298/276/434 +o Bowl_hull_8 +v -0.030178 0.002587 -0.050214 +v 0.037056 -0.003018 -0.033404 +v 0.037056 -0.003018 -0.034697 +v 0.037056 0.003017 -0.033404 +v -0.030178 -0.002587 -0.033404 +v 0.034904 -0.003018 -0.050214 +v 0.034904 0.003017 -0.050214 +v -0.030178 0.002587 -0.033404 +v -0.030178 -0.002587 -0.050214 +v 0.035332 0.002586 -0.050214 +v 0.032745 -0.003018 -0.033404 +v 0.032745 0.003017 -0.033404 +v 0.035332 -0.002586 -0.050214 +v 0.037056 0.002586 -0.035130 +v 0.032745 -0.003018 -0.050214 +v 0.032745 0.003017 -0.050214 +vt 0.935872 1.000000 +vt 0.967985 0.000000 +vt 0.935872 0.000000 +vt 1.000000 1.000000 +vt 1.000000 0.923062 +vt 1.000000 1.000000 +vt 0.000000 1.000000 +vt 0.967985 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 0.974349 0.000000 +vt 0.935872 1.000000 +vt 0.974349 0.000000 +vt 1.000000 0.897318 +vt 0.935872 0.000000 +vn 0.0000 1.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn -0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn 0.7070 0.7014 -0.0905 +vn -0.0069 -1.0000 0.0000 +vn -0.0068 1.0000 0.0000 +vn 0.7069 -0.7004 -0.0981 +vn 0.9935 0.0000 -0.1136 +vn 0.9044 0.4139 -0.1034 +vn 0.9938 -0.0085 -0.1107 +usemtl None +s off +f 310/299/435 305/300/435 314/301/435 +f 300/302/436 301/303/436 302/304/436 +f 300/302/437 302/304/437 303/305/437 +f 301/303/438 300/302/438 304/306/438 +f 304/306/439 299/307/439 305/300/439 +f 299/307/440 303/305/440 306/308/440 +f 303/305/437 302/304/437 306/308/437 +f 303/305/440 299/307/440 307/309/440 +f 299/307/439 304/306/439 307/309/439 +f 304/306/439 305/300/439 308/310/439 +f 305/300/441 302/304/441 308/310/441 +f 300/302/437 303/305/437 309/311/437 +f 304/306/438 300/302/438 309/311/438 +f 303/305/442 307/309/442 309/311/442 +f 302/304/435 305/300/435 310/299/435 +f 306/308/437 302/304/437 310/299/437 +f 299/307/443 306/308/443 310/299/443 +f 301/303/444 304/306/444 311/312/444 +f 304/306/439 308/310/439 311/312/439 +f 311/312/445 308/310/445 312/313/445 +f 302/304/436 301/303/436 312/313/436 +f 308/310/446 302/304/446 312/313/446 +f 301/303/447 311/312/447 312/313/447 +f 307/309/439 304/306/439 313/314/439 +f 304/306/438 309/311/438 313/314/438 +f 309/311/442 307/309/442 313/314/442 +f 305/300/439 299/307/439 314/301/439 +f 299/307/443 310/299/443 314/301/443 +o Bowl_hull_9 +v 0.080174 -0.023279 0.050233 +v 0.040084 -0.012505 -0.021762 +v 0.040518 -0.012505 -0.021762 +v 0.040084 -0.026726 -0.011409 +v 0.078450 -0.012505 0.050233 +v 0.040518 -0.026296 -0.004080 +v 0.075005 -0.026726 0.050233 +v 0.040084 -0.012505 -0.015293 +v 0.082333 -0.012505 0.049366 +v 0.073280 -0.026726 0.039887 +v 0.040518 -0.020692 -0.017019 +v 0.046556 -0.013367 -0.011839 +v 0.081039 -0.018540 0.048936 +v 0.051296 -0.026726 0.004538 +v 0.078450 -0.026726 0.048506 +v 0.075005 -0.025865 0.050233 +v 0.040948 -0.016814 -0.019168 +v 0.040084 -0.026726 -0.004940 +v 0.079314 -0.023279 0.048076 +v 0.040518 -0.012505 -0.014426 +v 0.059058 -0.012935 0.009281 +v 0.061639 -0.026726 0.020916 +v 0.040948 -0.026726 -0.010980 +v 0.082333 -0.012505 0.050233 +v 0.041378 -0.014229 -0.020028 +v 0.077156 -0.012505 0.048076 +v 0.081039 -0.013367 0.047216 +v 0.078880 -0.026726 0.050233 +v 0.048707 -0.012505 -0.008393 +v 0.040948 -0.024573 -0.013136 +vt 0.365309 0.265368 +vt 0.149765 0.020458 +vt 0.119812 0.020458 +vt 0.000000 0.010278 +vt 0.000000 0.000000 +vt 1.000000 0.908085 +vt 1.000000 0.948904 +vt 1.000000 0.826547 +vt 0.143794 0.000000 +vt 0.089859 0.000000 +vt 0.987960 1.000000 +vt 0.856304 0.785728 +vt 0.065877 0.010278 +vt 0.981989 0.969362 +vt 0.976018 0.908085 +vt 0.245595 0.010278 +vt 1.000000 0.826547 +vt 0.036022 0.020458 +vt 0.233653 0.000000 +vt 0.970047 0.928544 +vt 0.137823 0.153191 +vt 0.101899 0.010278 +vt 0.431186 0.449099 +vt 0.592796 0.510180 +vt 1.000000 1.000000 +vt 0.024080 0.030638 +vt 0.970047 0.877447 +vt 0.958105 0.969362 +vt 1.000000 0.918265 +vt 0.185689 0.204092 +vn 0.7273 -0.4856 -0.4850 +vn 0.0000 1.0000 0.0000 +vn -0.0000 0.0000 1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.0000 -1.0000 0.0000 +vn 0.0000 -0.5013 -0.8653 +vn -0.9148 -0.2376 -0.3265 +vn 0.9750 -0.2027 -0.0909 +vn -0.8256 0.2129 0.5225 +vn -0.8442 0.0000 0.5360 +vn 0.1915 -0.4920 -0.8493 +vn -0.8259 -0.2111 0.5228 +vn -0.9092 0.2450 0.3366 +vn 0.8965 -0.2613 -0.3576 +vn 0.8412 -0.2162 -0.4957 +vn 0.8946 -0.2688 -0.3569 +vn 0.8260 -0.2689 -0.4954 +vn -0.8475 0.3185 0.4246 +vn 0.8455 -0.1967 -0.4965 +vn 0.7857 -0.3694 -0.4962 +vn 0.7885 -0.3628 -0.4967 +vn 0.8079 -0.3185 -0.4958 +vn 0.9805 -0.1965 0.0000 +vn 0.8455 -0.1047 -0.5236 +vn 0.6709 -0.3321 -0.6631 +vn 0.8145 -0.3005 -0.4963 +vn 0.8260 -0.2682 -0.4958 +vn 0.8280 -0.2617 -0.4960 +vn -0.8139 0.3145 0.4885 +vn -0.8066 0.3547 0.4728 +vn 0.8725 -0.1541 -0.4637 +vn 0.8640 -0.0478 -0.5012 +vn 0.8526 -0.1649 -0.4959 +vn 0.9117 -0.3423 -0.2271 +vn 0.8521 -0.0393 -0.5219 +vn 0.8577 0.1228 -0.4993 +vn 0.8554 -0.1196 -0.5039 +vn 0.2703 -0.6659 -0.6954 +vn 0.7632 -0.4129 -0.4971 +vn 0.3316 -0.6675 -0.6667 +usemtl None +s off +f 328/315/448 337/316/448 344/317/448 +f 317/318/449 316/319/449 319/320/449 +f 315/321/450 319/320/450 321/322/450 +f 316/319/451 318/323/451 322/324/451 +f 319/320/449 316/319/449 322/324/449 +f 317/318/449 319/320/449 323/325/449 +f 321/322/452 318/323/452 324/326/452 +f 316/319/453 317/318/453 325/327/453 +f 318/323/454 316/319/454 325/327/454 +f 323/325/455 315/321/455 327/328/455 +f 324/326/452 318/323/452 328/315/452 +f 321/322/452 324/326/452 329/329/452 +f 319/320/456 320/330/456 330/331/456 +f 321/322/450 319/320/450 330/331/450 +f 320/330/457 321/322/457 330/331/457 +f 325/327/458 317/318/458 331/332/458 +f 318/323/452 321/322/452 332/333/452 +f 321/322/459 320/330/459 332/333/459 +f 322/324/451 318/323/451 332/333/451 +f 320/330/460 322/324/460 332/333/460 +f 327/328/461 315/321/461 333/334/461 +f 326/335/462 327/328/462 333/334/462 +f 315/321/463 329/329/463 333/334/463 +f 329/329/464 324/326/464 333/334/464 +f 319/320/449 322/324/449 334/336/449 +f 322/324/465 320/330/465 334/336/465 +f 327/328/466 326/335/466 335/337/466 +f 324/326/452 328/315/452 336/338/452 +f 328/315/467 325/327/467 336/338/467 +f 325/327/468 331/332/468 336/338/468 +f 331/332/469 324/326/469 336/338/469 +f 328/315/452 318/323/452 337/316/452 +f 319/320/450 315/321/450 338/339/450 +f 315/321/470 323/325/470 338/339/470 +f 323/325/449 319/320/449 338/339/449 +f 317/318/471 326/335/471 339/340/471 +f 331/332/472 317/318/472 339/340/472 +f 324/326/473 331/332/473 339/340/473 +f 333/334/474 324/326/474 339/340/474 +f 326/335/475 333/334/475 339/340/475 +f 320/330/476 319/320/476 340/341/476 +f 319/320/449 334/336/449 340/341/449 +f 334/336/477 320/330/477 340/341/477 +f 323/325/478 327/328/478 341/342/478 +f 335/337/479 323/325/479 341/342/479 +f 327/328/480 335/337/480 341/342/480 +f 315/321/450 321/322/450 342/343/450 +f 329/329/481 315/321/481 342/343/481 +f 321/322/452 329/329/452 342/343/452 +f 317/318/449 323/325/449 343/344/449 +f 326/335/482 317/318/482 343/344/482 +f 323/325/483 335/337/483 343/344/483 +f 335/337/484 326/335/484 343/344/484 +f 318/323/485 325/327/485 344/317/485 +f 325/327/486 328/315/486 344/317/486 +f 337/316/487 318/323/487 344/317/487 +o Bowl_hull_10 +v 0.082330 -0.012501 0.050235 +v 0.040088 0.000431 -0.025211 +v 0.040519 0.000431 -0.025211 +v 0.079743 0.000431 0.050235 +v 0.040949 -0.012501 -0.013993 +v 0.041379 -0.012501 -0.020898 +v 0.082760 0.000431 0.048507 +v 0.040088 0.000431 -0.018742 +v 0.078021 -0.012501 0.049371 +v 0.081899 -0.008621 0.047642 +v 0.042240 -0.004312 -0.022190 +v 0.078452 0.000431 0.048507 +v 0.080173 -0.012501 0.045486 +v 0.040519 -0.007759 -0.024339 +v 0.040088 -0.012501 -0.022190 +v 0.083191 -0.004312 0.049371 +v 0.040949 -0.000434 -0.024775 +v 0.040519 -0.011638 -0.014857 +v 0.083191 0.000431 0.050235 +v 0.076726 -0.012069 0.047214 +v 0.056900 -0.012501 0.005400 +v 0.040088 -0.012501 -0.015721 +v 0.078882 -0.012501 0.050235 +v 0.040949 -0.012069 -0.013993 +v 0.057761 0.000431 0.012298 +v 0.077591 -0.003020 0.039453 +v 0.043536 -0.006035 -0.019598 +v 0.082330 -0.012501 0.049371 +v 0.053879 -0.003882 -0.001933 +vt 0.005775 0.019973 +vt 0.857087 0.870080 +vt 0.308536 0.319953 +vt 0.000000 0.009986 +vt 0.000000 0.000000 +vt 1.000000 0.920012 +vt 1.000000 0.980027 +vt 0.148688 0.019973 +vt 0.057165 0.029959 +vt 0.977095 0.990014 +vt 0.085748 0.000000 +vt 0.988547 0.880067 +vt 0.977095 0.890053 +vt 0.937060 0.929998 +vt 0.011551 0.009986 +vt 0.040035 0.000000 +vt 0.040035 0.049931 +vt 1.000000 1.000000 +vt 0.988547 1.000000 +vt 0.959965 0.850010 +vt 0.405736 0.390053 +vt 0.125783 0.000000 +vt 0.137236 0.009986 +vt 1.000000 0.900039 +vt 0.148688 0.019973 +vt 0.497161 0.410026 +vt 0.965642 0.970041 +vt 0.074393 0.079988 +vt 0.988547 0.980027 +vn 0.8675 -0.0348 -0.4963 +vn 0.0000 1.0000 0.0000 +vn -0.0000 -1.0000 -0.0000 +vn -0.7993 0.0665 0.5973 +vn 0.0000 -0.1058 -0.9944 +vn -1.0000 0.0000 0.0000 +vn -0.9205 -0.0889 -0.3804 +vn 0.6603 -0.3589 -0.6597 +vn 0.8537 0.1785 -0.4892 +vn 0.8374 -0.0813 -0.5404 +vn 0.6219 -0.0829 -0.7787 +vn 0.0000 -0.0000 1.0000 +vn 0.9374 -0.0624 0.3426 +vn 0.9694 0.0440 -0.2415 +vn -0.8612 -0.0675 0.5038 +vn -0.8498 0.0632 0.5232 +vn 0.8538 -0.1592 -0.4957 +vn 0.8424 -0.2079 -0.4972 +vn -0.9237 0.0871 0.3731 +vn -0.8951 0.0000 0.4459 +vn -0.7076 0.0471 0.7050 +vn -0.8633 0.0000 0.5046 +vn -0.8614 0.0669 0.5035 +vn 0.0001 1.0000 -0.0001 +vn -0.8619 0.1272 0.4908 +vn -0.8616 0.1233 0.4923 +vn -0.8618 0.1249 0.4917 +vn 0.8701 -0.0108 -0.4927 +vn 0.8686 -0.0009 -0.4956 +vn 0.8628 -0.0975 -0.4960 +vn 0.8617 -0.1078 -0.4958 +vn 0.8564 -0.1138 -0.5036 +vn 0.8575 -0.1361 -0.4962 +vn 0.8682 -0.1183 -0.4819 +vn 0.9945 -0.1045 0.0000 +vn 0.8957 -0.0942 -0.4345 +vn 0.8656 -0.0692 -0.4959 +vn 0.8664 -0.0609 -0.4955 +vn 0.8667 -0.0427 -0.4970 +vn 0.8671 -0.0478 -0.4958 +usemtl None +s off +f 361/345/488 370/346/488 373/347/488 +f 347/348/489 346/349/489 348/350/489 +f 345/351/490 349/352/490 350/353/490 +f 347/348/489 348/350/489 351/354/489 +f 348/350/489 346/349/489 352/355/489 +f 349/352/490 345/351/490 353/356/490 +f 348/350/489 352/355/489 356/357/489 +f 353/356/491 348/350/491 356/357/491 +f 345/351/490 350/353/490 357/358/490 +f 346/349/492 347/348/492 358/359/492 +f 350/353/490 349/352/490 359/360/490 +f 352/355/493 346/349/493 359/360/493 +f 346/349/494 358/359/494 359/360/494 +f 358/359/495 350/353/495 359/360/495 +f 347/348/496 351/354/496 361/345/496 +f 355/361/497 358/359/497 361/345/497 +f 358/359/498 347/348/498 361/345/498 +f 348/350/499 345/351/499 363/362/499 +f 351/354/489 348/350/489 363/362/489 +f 345/351/500 360/363/500 363/362/500 +f 360/363/501 351/354/501 363/362/501 +f 349/352/502 353/356/502 364/364/502 +f 353/356/503 356/357/503 364/364/503 +f 357/358/490 350/353/490 365/365/490 +f 358/359/504 357/358/504 365/365/504 +f 350/353/505 358/359/505 365/365/505 +f 359/360/490 349/352/490 366/366/490 +f 352/355/493 359/360/493 366/366/493 +f 362/367/506 352/355/506 366/366/506 +f 349/352/507 362/367/507 366/366/507 +f 345/351/499 348/350/499 367/368/499 +f 353/356/490 345/351/490 367/368/490 +f 348/350/508 353/356/508 367/368/508 +f 362/367/507 349/352/507 368/369/507 +f 349/352/509 364/364/509 368/369/509 +f 364/364/510 356/357/510 368/369/510 +f 356/357/511 352/355/511 369/370/511 +f 352/355/512 362/367/512 369/370/512 +f 368/369/513 356/357/513 369/370/513 +f 362/367/514 368/369/514 369/370/514 +f 351/354/515 360/363/515 370/346/515 +f 361/345/516 351/354/516 370/346/516 +f 355/361/517 354/371/517 371/372/517 +f 354/371/518 357/358/518 371/372/518 +f 358/359/519 355/361/519 371/372/519 +f 357/358/520 358/359/520 371/372/520 +f 345/351/490 357/358/490 372/373/490 +f 357/358/521 354/371/521 372/373/521 +f 360/363/522 345/351/522 372/373/522 +f 354/371/523 360/363/523 372/373/523 +f 354/371/524 355/361/524 373/347/524 +f 360/363/525 354/371/525 373/347/525 +f 355/361/526 361/345/526 373/347/526 +f 370/346/527 360/363/527 373/347/527 +o Bowl_hull_11 +v -0.015099 0.032335 -0.048921 +v 0.005163 0.032335 -0.033404 +v 0.005163 0.032335 -0.050214 +v 0.002145 0.037076 -0.035128 +v -0.024153 0.028023 -0.033404 +v -0.016390 0.028023 -0.050214 +v -0.009495 0.036214 -0.033404 +v -0.002599 0.035351 -0.050214 +v -0.016390 0.028023 -0.033404 +v 0.005163 0.035351 -0.048058 +v -0.021134 0.028454 -0.050214 +v -0.018979 0.032335 -0.033835 +v 0.005163 0.036644 -0.033404 +v -0.009925 0.034057 -0.050214 +v -0.004754 0.037076 -0.033835 +v -0.014666 0.034489 -0.033835 +v -0.022858 0.029748 -0.033404 +v 0.002575 0.035351 -0.050214 +v -0.018115 0.030609 -0.050214 +v -0.006479 0.034920 -0.049783 +v -0.021134 0.028023 -0.050214 +v 0.004730 0.037076 -0.033404 +v -0.011650 0.033626 -0.049783 +v -0.024153 0.028454 -0.034697 +v -0.020270 0.029317 -0.049783 +v 0.005163 0.034920 -0.050214 +v -0.000011 0.037076 -0.035559 +v -0.009495 0.036214 -0.033835 +vt 0.426488 0.025646 +vt 0.323610 0.974354 +vt 0.500000 0.974354 +vt 1.000000 0.000000 +vt 1.000000 1.000000 +vt 0.264781 0.000000 +vt 0.000000 1.000000 +vt 0.500000 1.000000 +vt 0.735219 0.000000 +vt 0.264781 1.000000 +vt 1.000000 0.128230 +vt 0.102976 0.000000 +vt 1.000000 1.000000 +vt 0.485317 0.000000 +vt 0.308829 0.076938 +vt 0.176488 0.974354 +vt 0.044146 1.000000 +vt 0.911707 0.000000 +vt 0.205951 0.000000 +vt 0.602878 0.025646 +vt 0.661707 0.974354 +vt 0.102976 0.000000 +vt 0.985219 1.000000 +vt 0.897024 0.897416 +vt 0.000000 0.923062 +vt 0.132439 0.025646 +vt 1.000000 0.000000 +vt 0.823512 0.871770 +vn -0.3144 0.9428 -0.1105 +vn 0.1962 -0.9806 -0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 -0.0000 +vn 1.0000 -0.0000 0.0000 +vn -0.4439 0.8888 -0.1142 +vn -0.2664 0.5334 0.8028 +vn -0.2285 0.4722 0.8514 +vn -0.4549 0.8828 -0.1170 +vn -0.1504 0.8514 -0.5026 +vn -0.1227 0.9852 -0.1199 +vn 0.7043 0.7071 -0.0624 +vn 0.0000 1.0000 0.0000 +vn -0.0363 0.5995 0.7995 +vn 0.0742 0.9910 -0.1112 +vn 0.0946 0.9890 -0.1136 +vn -0.3743 0.9194 -0.1206 +vn -0.3945 0.8822 -0.2570 +vn -0.3281 0.7794 -0.5338 +vn -0.7844 0.5884 0.1963 +vn -0.8698 -0.4681 -0.1562 +vn -0.9816 0.0000 -0.1910 +vn -0.5598 0.8213 -0.1101 +vn -0.5278 0.8414 -0.1165 +vn -0.5268 0.7379 -0.4219 +vn -0.6388 0.7598 -0.1209 +vn -0.6677 0.7330 -0.1299 +vn 0.1610 0.9678 -0.1934 +vn -0.0399 0.9931 -0.1099 +vn 0.0000 0.9931 -0.1169 +vn 0.0226 0.9933 -0.1130 +vn -0.1790 0.9839 0.0000 +vn -0.3164 0.9486 0.0000 +vn -0.2269 0.9663 -0.1213 +vn -0.1778 0.9776 -0.1129 +vn -0.2684 0.9559 -0.1188 +usemtl None +s off +f 396/374/528 389/375/528 401/376/528 +f 376/377/529 375/378/529 379/379/529 +f 378/380/530 375/378/530 380/381/530 +f 376/377/531 379/379/531 381/382/531 +f 375/378/530 378/380/530 382/383/530 +f 379/379/529 375/378/529 382/383/529 +f 378/380/532 379/379/532 382/383/532 +f 375/378/533 376/377/533 383/384/533 +f 381/382/531 379/379/531 384/385/531 +f 380/381/530 375/378/530 386/386/530 +f 375/378/533 383/384/533 386/386/533 +f 381/382/531 384/385/531 387/387/531 +f 374/388/534 385/389/534 389/375/534 +f 378/380/530 380/381/530 390/390/530 +f 389/375/535 385/389/535 390/390/535 +f 380/381/536 389/375/536 390/390/536 +f 376/377/531 381/382/531 391/391/531 +f 385/389/537 374/388/537 392/392/537 +f 387/387/531 384/385/531 392/392/531 +f 381/382/538 387/387/538 393/393/538 +f 388/394/539 381/382/539 393/393/539 +f 379/379/532 378/380/532 394/395/532 +f 384/385/531 379/379/531 394/395/531 +f 380/381/530 386/386/530 395/396/530 +f 386/386/540 383/384/540 395/396/540 +f 377/397/541 388/394/541 395/396/541 +f 388/394/542 380/381/542 395/396/542 +f 391/391/543 377/397/543 395/396/543 +f 383/384/544 391/391/544 395/396/544 +f 374/388/545 389/375/545 396/374/545 +f 392/392/546 374/388/546 396/374/546 +f 387/387/547 392/392/547 396/374/547 +f 378/380/548 390/390/548 397/398/548 +f 394/395/549 378/380/549 397/398/549 +f 384/385/550 394/395/550 397/398/550 +f 390/390/551 385/389/551 398/399/551 +f 385/389/552 392/392/552 398/399/552 +f 392/392/553 384/385/553 398/399/553 +f 397/398/554 390/390/554 398/399/554 +f 384/385/555 397/398/555 398/399/555 +f 383/384/533 376/377/533 399/400/533 +f 376/377/531 391/391/531 399/400/531 +f 391/391/556 383/384/556 399/400/556 +f 388/394/541 377/397/541 400/401/541 +f 381/382/557 388/394/557 400/401/557 +f 391/391/558 381/382/558 400/401/558 +f 377/397/559 391/391/559 400/401/559 +f 380/381/560 388/394/560 401/376/560 +f 389/375/561 380/381/561 401/376/561 +f 393/393/562 387/387/562 401/376/562 +f 388/394/563 393/393/563 401/376/563 +f 387/387/564 396/374/564 401/376/564 +o Bowl_hull_12 +v -0.034927 0.013366 -0.034266 +v -0.024585 0.028023 -0.035128 +v -0.024585 0.028023 -0.033404 +v -0.017255 0.027590 -0.033404 +v -0.030619 0.011211 -0.050214 +v -0.022428 0.027590 -0.050214 +v -0.030619 0.011211 -0.033404 +v -0.017255 0.027590 -0.050214 +v -0.030619 0.018109 -0.050214 +v -0.029754 0.022847 -0.033404 +v -0.033635 0.011211 -0.049352 +v -0.035362 0.011211 -0.033404 +v -0.025879 0.024572 -0.049352 +v -0.017255 0.028023 -0.050214 +v -0.032341 0.018972 -0.033835 +v -0.032772 0.013798 -0.050214 +v -0.017255 0.028023 -0.033404 +v -0.027598 0.025434 -0.033835 +v -0.028031 0.021985 -0.049783 +v -0.021998 0.028023 -0.049783 +v -0.025449 0.027590 -0.033835 +v -0.033635 0.016385 -0.034266 +vt 0.143011 0.846124 +vt 0.023982 0.871770 +vt 0.095341 0.692248 +vt 1.000000 0.025744 +vt 0.595145 0.000000 +vt 0.261942 1.000000 +vt 0.261942 1.000000 +vt 1.000000 0.025744 +vt 0.714272 0.025744 +vt 0.261942 0.589663 +vt 0.309710 0.307850 +vt 0.095341 1.000000 +vt 0.000000 1.000000 +vt 0.595145 0.000000 +vt 1.000000 0.000000 +vt 0.166797 0.538371 +vt 1.000000 0.000000 +vt 0.428739 0.153974 +vt 0.523688 0.205266 +vt 0.404855 0.359142 +vt 0.738058 0.000000 +vt 0.547475 0.025744 +vn -0.9134 0.3910 -0.1129 +vn 0.0000 -0.0000 1.0000 +vn 0.7748 -0.6322 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.9821 0.1553 -0.1063 +vn -0.0000 1.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn -0.8201 0.5604 -0.1158 +vn -0.8239 0.3456 0.4491 +vn -0.4987 0.2403 0.8328 +vn -0.9530 0.2776 -0.1213 +vn -0.2679 -0.2230 -0.9373 +vn -0.7534 0.6466 -0.1194 +vn -0.4538 0.3920 -0.8003 +vn -0.6495 0.6148 -0.4475 +vn -0.7726 0.6246 -0.1141 +vn -0.0614 0.7344 -0.6759 +vn -0.4482 0.8939 0.0000 +vn -0.5777 0.5769 0.5775 +vn -0.6706 0.7314 -0.1237 +vn -0.5807 0.5792 0.5721 +vn -0.7032 0.7013 -0.1169 +vn -0.5606 0.8222 -0.0990 +vn -0.6424 0.7572 -0.1184 +vn -0.8543 0.3657 0.3693 +vn -0.8803 0.4598 -0.1168 +vn -0.8882 0.4436 -0.1200 +usemtl None +s off +f 417/402/565 402/403/565 423/404/565 +f 405/405/566 404/406/566 408/407/566 +f 406/408/567 405/405/567 408/407/567 +f 405/405/567 406/408/567 409/409/567 +f 406/408/568 407/410/568 409/409/568 +f 407/410/568 406/408/568 410/411/568 +f 408/407/566 404/406/566 411/412/566 +f 406/408/569 408/407/569 412/413/569 +f 408/407/566 411/412/566 413/414/566 +f 402/403/570 412/413/570 413/414/570 +f 412/413/569 408/407/569 413/414/569 +f 403/415/571 404/406/571 415/416/571 +f 405/405/572 409/409/572 415/416/572 +f 409/409/568 407/410/568 415/416/568 +f 411/412/573 410/411/573 416/417/573 +f 402/403/574 413/414/574 416/417/574 +f 413/414/575 411/412/575 416/417/575 +f 410/411/568 406/408/568 417/402/568 +f 412/413/576 402/403/576 417/402/576 +f 406/408/577 412/413/577 417/402/577 +f 404/406/566 405/405/566 418/418/566 +f 415/416/571 404/406/571 418/418/571 +f 405/405/572 415/416/572 418/418/572 +f 419/419/578 414/420/578 420/421/578 +f 407/410/579 410/411/579 420/421/579 +f 410/411/573 411/412/573 420/421/573 +f 414/420/580 407/410/580 420/421/580 +f 411/412/581 419/419/581 420/421/581 +f 403/415/571 415/416/571 421/422/571 +f 415/416/582 407/410/582 421/422/582 +f 404/406/583 403/415/583 422/423/583 +f 411/412/584 404/406/584 422/423/584 +f 407/410/585 414/420/585 422/423/585 +f 419/419/586 411/412/586 422/423/586 +f 414/420/587 419/419/587 422/423/587 +f 403/415/588 421/422/588 422/423/588 +f 421/422/589 407/410/589 422/423/589 +f 402/403/590 416/417/590 423/404/590 +f 416/417/591 410/411/591 423/404/591 +f 410/411/592 417/402/592 423/404/592 +o Bowl_hull_13 +v -0.034930 -0.007758 -0.047627 +v -0.033637 0.011205 -0.050214 +v -0.030620 0.011205 -0.050214 +v -0.035361 0.011205 -0.033404 +v -0.030620 -0.011640 -0.033404 +v -0.037085 -0.004739 -0.033404 +v -0.030620 -0.011640 -0.050214 +v -0.030620 0.011205 -0.033404 +v -0.035361 -0.011640 -0.033404 +v -0.035361 0.002154 -0.050214 +v -0.037085 0.004739 -0.033835 +v -0.030189 0.002583 -0.033404 +v -0.033637 -0.011206 -0.050214 +v -0.030189 -0.002585 -0.050214 +v -0.035361 -0.002153 -0.050214 +v -0.034930 0.006895 -0.049352 +v -0.036223 0.009480 -0.033835 +v -0.036223 -0.009482 -0.033835 +v -0.030189 -0.002585 -0.033404 +v -0.030189 0.002583 -0.050214 +v -0.037085 -0.002153 -0.035128 +v -0.033637 -0.011640 -0.049352 +v -0.034930 -0.006895 -0.049352 +vt 0.981008 0.000000 +vt 1.000000 0.051292 +vt 0.792266 0.051292 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 0.697895 1.000000 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 0.396182 0.000000 +vt 0.283015 0.974354 +vt 0.377386 1.000000 +vt 0.603622 0.000000 +vt 0.584728 0.000000 +vt 0.188644 0.051292 +vt 0.075477 0.974354 +vt 0.905531 0.974354 +vt 0.603622 1.000000 +vt 0.377386 0.000000 +vt 0.584728 0.897416 +vt 0.830054 0.153876 +vn -0.9565 -0.2606 -0.1311 +vn 0.0000 1.0000 -0.0000 +vn 0.0000 -0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.3873 0.0419 0.9210 +vn 0.9988 0.0500 0.0000 +vn 0.9989 -0.0476 0.0000 +vn -0.8652 0.1648 -0.4735 +vn -0.9863 0.1118 -0.1215 +vn -0.9778 0.1778 -0.1111 +vn -0.8815 0.4634 -0.0904 +vn -0.6140 0.1117 0.7813 +vn -0.9570 0.2624 -0.1235 +vn -0.7848 -0.1961 0.5879 +vn 1.0000 0.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.9940 0.0202 -0.1078 +vn -0.9907 -0.0755 -0.1132 +vn -0.9935 0.0000 -0.1136 +vn -0.1274 -0.8860 -0.4458 +vn -0.9567 -0.2641 -0.1227 +vn -0.9171 -0.3862 -0.0992 +vn -0.9867 -0.1113 -0.1183 +vn -0.8653 -0.1648 -0.4733 +vn -0.9632 -0.2405 -0.1204 +vn -0.9796 -0.1681 -0.1097 +vn -0.9566 -0.2606 -0.1305 +usemtl None +s off +f 436/424/593 445/425/593 446/426/593 +f 426/427/594 425/428/594 427/429/594 +f 428/430/595 427/429/595 429/431/595 +f 425/428/596 426/427/596 430/432/596 +f 426/427/594 427/429/594 431/433/594 +f 427/429/595 428/430/595 431/433/595 +f 428/430/595 429/431/595 432/434/595 +f 430/432/597 428/430/597 432/434/597 +f 425/428/596 430/432/596 433/435/596 +f 429/431/598 427/429/598 434/436/598 +f 426/427/599 431/433/599 435/437/599 +f 431/433/595 428/430/595 435/437/595 +f 433/435/596 430/432/596 436/424/596 +f 430/432/596 426/427/596 437/438/596 +f 428/430/600 430/432/600 437/438/600 +f 433/435/596 436/424/596 438/439/596 +f 425/428/601 433/435/601 439/440/601 +f 433/435/602 434/436/602 439/440/602 +f 439/440/603 434/436/603 440/441/603 +f 427/429/604 425/428/604 440/441/604 +f 434/436/605 427/429/605 440/441/605 +f 425/428/606 439/440/606 440/441/606 +f 432/434/607 429/431/607 441/442/607 +f 435/437/595 428/430/595 442/443/595 +f 428/430/600 437/438/600 442/443/600 +f 437/438/608 435/437/608 442/443/608 +f 426/427/599 435/437/599 443/444/599 +f 437/438/596 426/427/596 443/444/596 +f 435/437/608 437/438/608 443/444/608 +f 429/431/609 434/436/609 444/445/609 +f 434/436/610 433/435/610 444/445/610 +f 438/439/611 429/431/611 444/445/611 +f 433/435/612 438/439/612 444/445/612 +f 430/432/597 432/434/597 445/425/597 +f 436/424/613 430/432/613 445/425/613 +f 441/442/614 424/446/614 445/425/614 +f 432/434/615 441/442/615 445/425/615 +f 429/431/616 438/439/616 446/426/616 +f 438/439/617 436/424/617 446/426/617 +f 424/446/618 441/442/618 446/426/618 +f 441/442/619 429/431/619 446/426/619 +f 445/425/620 424/446/620 446/426/620 +o Bowl_hull_14 +v 0.065950 -0.047426 0.045491 +v 0.040084 -0.043974 0.008851 +v 0.040515 -0.043974 0.008851 +v 0.040084 -0.072859 0.049372 +v 0.065950 -0.043974 0.050231 +v 0.040084 -0.068112 0.049801 +v 0.040084 -0.044407 0.016180 +v 0.056896 -0.061216 0.049801 +v 0.070693 -0.043974 0.049801 +v 0.040515 -0.046994 0.011866 +v 0.047413 -0.068112 0.048509 +v 0.049138 -0.044407 0.019198 +v 0.063364 -0.054322 0.049368 +v 0.047844 -0.068547 0.050235 +v 0.040515 -0.058201 0.027386 +v 0.051727 -0.065527 0.049372 +v 0.058621 -0.059061 0.048938 +v 0.067242 -0.049581 0.050231 +v 0.040084 -0.068547 0.050235 +v 0.057758 -0.044407 0.030833 +v 0.040084 -0.043974 0.015317 +v 0.042241 -0.070269 0.046779 +v 0.044395 -0.044407 0.013162 +v 0.054313 -0.060786 0.045920 +v 0.069830 -0.045702 0.049368 +v 0.040084 -0.072859 0.050235 +v 0.054313 -0.043977 0.026097 +v 0.040084 -0.051738 0.018335 +v 0.041810 -0.053890 0.022646 +v 0.040515 -0.072859 0.049372 +v 0.060344 -0.057769 0.050235 +v 0.065087 -0.044407 0.041180 +v 0.066813 -0.050010 0.049368 +v 0.058621 -0.057339 0.046783 +v 0.070693 -0.044407 0.050231 +v 0.041810 -0.044836 0.010573 +vt 0.895742 0.464859 +vt 0.072834 0.014096 +vt 0.041605 0.056382 +vt 0.000000 0.014096 +vt 0.000000 0.000000 +vt 0.999902 0.845047 +vt 0.979148 0.000000 +vt 0.989525 0.000000 +vt 0.177092 0.000000 +vt 0.989525 1.000000 +vt 0.989525 0.549237 +vt 1.000000 0.253524 +vt 0.979148 0.380384 +vt 0.958297 0.239428 +vt 0.979050 0.760572 +vt 0.968673 0.605619 +vt 1.000000 0.000000 +vt 0.250024 0.295811 +vt 0.531180 0.577428 +vt 0.156241 0.000000 +vt 0.447871 0.014096 +vt 0.916495 0.070478 +vt 1.000000 0.000000 +vt 0.416740 0.464859 +vt 0.104161 0.140857 +vt 0.229173 0.000000 +vt 0.333333 0.056382 +vt 0.979148 0.014096 +vt 1.000000 0.661903 +vt 0.999902 0.887236 +vt 0.885365 0.845047 +vt 0.781204 0.816856 +vt 0.979050 0.971809 +vt 0.979050 0.873238 +vt 0.916593 0.605619 +vt 0.999902 1.000000 +vn 0.5802 -0.6456 -0.4965 +vn 0.0000 1.0000 0.0000 +vn -1.0000 -0.0000 0.0000 +vn -0.6112 0.6469 0.4561 +vn 0.0000 -0.7065 -0.7078 +vn 0.6271 -0.7659 0.1420 +vn 0.5328 -0.7793 -0.3298 +vn 0.6909 -0.6660 -0.2812 +vn -0.5567 0.5861 0.5887 +vn 0.6711 -0.5499 -0.4972 +vn -0.5176 0.7649 0.3835 +vn 0.4704 -0.7299 -0.4960 +vn 0.5895 -0.6602 -0.4654 +vn 0.5583 -0.6653 -0.4957 +vn 0.5902 -0.6593 -0.4658 +vn 0.0000 0.0000 1.0000 +vn 0.0026 1.0000 -0.0019 +vn 0.7980 -0.1170 -0.5912 +vn 0.6157 0.6151 -0.4925 +vn 0.7167 0.4112 -0.5632 +vn -0.7036 -0.5498 -0.4501 +vn -0.5039 -0.7141 -0.4859 +vn 0.1346 -0.8033 -0.5801 +vn 0.4864 -0.7083 -0.5115 +vn 0.5141 -0.6997 -0.4961 +vn 0.5171 -0.6978 -0.4957 +vn 0.5479 -0.6733 -0.4965 +vn 0.5074 -0.7969 -0.3279 +vn 0.0000 -0.8320 -0.5547 +vn 0.4678 -0.7613 -0.4491 +vn 0.3835 -0.7684 -0.5123 +vn 0.0000 -1.0000 0.0000 +vn 0.4720 -0.8494 0.2360 +vn 0.7021 -0.6734 -0.2313 +vn 0.5033 -0.5838 0.6371 +vn 0.7608 -0.6408 0.1028 +vn -0.0002 0.0004 1.0000 +vn 0.7022 -0.5094 -0.4974 +vn 0.7135 -0.4987 -0.4922 +vn 0.8119 -0.2766 -0.5141 +vn 0.6834 0.5567 -0.4723 +vn 0.8041 0.1706 -0.5695 +vn 0.7787 -0.6228 -0.0764 +vn 0.7008 -0.5117 -0.4971 +vn 0.6784 -0.5426 -0.4954 +vn 0.7133 -0.4995 -0.4917 +vn 0.8132 -0.5694 -0.1202 +vn 0.6421 -0.5853 -0.4951 +vn 0.6419 -0.5991 -0.4786 +vn 0.6317 -0.5955 -0.4963 +vn 0.6076 -0.6205 -0.4958 +vn 0.0641 0.7031 0.7082 +vn 0.8703 -0.3470 -0.3496 +vn 0.8319 -0.5549 0.0009 +vn 0.0000 0.0003 1.0000 +vn 0.0028 -0.0019 1.0000 +vn 0.4259 -0.6392 -0.6403 +vn 0.7043 -0.2609 -0.6602 +vn 0.6006 -0.6273 -0.4958 +vn 0.5990 -0.6289 -0.4957 +usemtl None +s off +f 470/447/621 456/448/621 482/449/621 +f 449/450/622 448/451/622 451/452/622 +f 448/451/623 450/453/623 452/454/623 +f 448/451/623 452/454/623 453/455/623 +f 452/454/624 451/452/624 453/455/624 +f 449/450/622 451/452/622 455/456/622 +f 448/451/625 449/450/625 456/448/625 +f 454/457/626 460/458/626 462/459/626 +f 460/458/627 457/460/627 462/459/627 +f 459/461/628 454/457/628 463/462/628 +f 451/452/629 452/454/629 465/463/629 +f 452/454/623 450/453/623 465/463/623 +f 459/461/630 458/464/630 466/465/630 +f 451/452/622 448/451/622 467/466/622 +f 448/451/623 453/455/623 467/466/623 +f 453/455/631 451/452/631 467/466/631 +f 461/467/632 457/460/632 468/468/632 +f 454/457/633 462/459/633 470/447/633 +f 462/459/634 456/448/634 470/447/634 +f 463/462/635 454/457/635 470/447/635 +f 465/463/623 450/453/623 472/469/623 +f 460/458/636 465/463/636 472/469/636 +f 449/450/637 455/456/637 473/470/637 +f 466/465/638 458/464/638 473/470/638 +f 469/471/639 449/450/639 473/470/639 +f 458/464/640 469/471/640 473/470/640 +f 450/453/623 448/451/623 474/472/623 +f 448/451/641 456/448/641 474/472/641 +f 461/467/642 450/453/642 474/472/642 +f 456/448/643 461/467/643 474/472/643 +f 461/467/644 456/448/644 475/473/644 +f 457/460/645 461/467/645 475/473/645 +f 462/459/646 457/460/646 475/473/646 +f 456/448/647 462/459/647 475/473/647 +f 457/460/648 460/458/648 476/474/648 +f 450/453/649 461/467/649 476/474/649 +f 468/468/650 457/460/650 476/474/650 +f 461/467/651 468/468/651 476/474/651 +f 472/469/652 450/453/652 476/474/652 +f 460/458/653 472/469/653 476/474/653 +f 454/457/654 459/461/654 477/475/654 +f 460/458/655 454/457/655 477/475/655 +f 459/461/656 464/476/656 477/475/656 +f 451/452/657 465/463/657 477/475/657 +f 465/463/636 460/458/636 477/475/636 +f 447/477/658 466/465/658 478/478/658 +f 471/479/659 447/477/659 478/478/659 +f 455/456/660 471/479/660 478/478/660 +f 473/470/661 455/456/661 478/478/661 +f 466/465/662 473/470/662 478/478/662 +f 464/476/663 459/461/663 479/480/663 +f 466/465/664 447/477/664 479/480/664 +f 459/461/665 466/465/665 479/480/665 +f 447/477/666 471/479/666 479/480/666 +f 471/479/667 464/476/667 479/480/667 +f 458/464/668 459/461/668 480/481/668 +f 459/461/669 463/462/669 480/481/669 +f 469/471/670 458/464/670 480/481/670 +f 463/462/671 469/471/671 480/481/671 +f 455/456/672 451/452/672 481/482/672 +f 471/479/673 455/456/673 481/482/673 +f 464/476/674 471/479/674 481/482/674 +f 451/452/675 477/475/675 481/482/675 +f 477/475/676 464/476/676 481/482/676 +f 456/448/677 449/450/677 482/449/677 +f 449/450/678 469/471/678 482/449/678 +f 469/471/679 463/462/679 482/449/679 +f 463/462/680 470/447/680 482/449/680 +o Bowl_hull_15 +v 0.012061 -0.035350 -0.034266 +v 0.024133 -0.028455 -0.033404 +v 0.024133 -0.028455 -0.035128 +v 0.005163 -0.032333 -0.033404 +v 0.023700 -0.022419 -0.050214 +v 0.006027 -0.034918 -0.050214 +v 0.023700 -0.022419 -0.033404 +v 0.018096 -0.030608 -0.050214 +v 0.005163 -0.032333 -0.050214 +v 0.005163 -0.036644 -0.033404 +v 0.024133 -0.026300 -0.049352 +v 0.018956 -0.032333 -0.033404 +v 0.013786 -0.032763 -0.050214 +v 0.024133 -0.022419 -0.033404 +v 0.009475 -0.036212 -0.033835 +v 0.005163 -0.034918 -0.050214 +v 0.014648 -0.034488 -0.033835 +v 0.021113 -0.028885 -0.048489 +v 0.011633 -0.033625 -0.049783 +v 0.024133 -0.022419 -0.050214 +v 0.021544 -0.030608 -0.034266 +v 0.005596 -0.036644 -0.035559 +v 0.024133 -0.025868 -0.050214 +v 0.008615 -0.034488 -0.049783 +v 0.015079 -0.032333 -0.049352 +vt 0.500000 0.974354 +vt 0.454581 0.000000 +vt 0.522709 0.051292 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 0.977193 1.000000 +vt 0.977193 0.000000 +vt 0.045517 0.000000 +vt 0.681774 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 0.897416 +vt 1.000000 0.051292 +vt 0.727095 1.000000 +vt 1.000000 1.000000 +vt 0.227291 0.974354 +vt 0.000000 0.000000 +vt 0.363645 0.948708 +vt 0.840838 0.102584 +vt 0.341034 0.025646 +vt 1.000000 0.000000 +vt 0.863547 0.948708 +vt 0.022807 0.871770 +vt 1.000000 0.000000 +vt 0.181969 0.025646 +vn 0.3829 -0.9164 -0.1167 +vn 0.0000 -0.0000 1.0000 +vn -0.4716 0.8818 0.0000 +vn 0.0000 0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.1319 -0.4222 0.8969 +vn 0.3161 -0.9487 0.0000 +vn 0.1687 -0.5064 0.8456 +vn 0.6266 -0.7706 -0.1168 +vn 0.5855 -0.7691 -0.2563 +vn 0.2970 -0.9481 -0.1136 +vn 0.3310 -0.9368 -0.1133 +vn 0.3488 -0.9299 -0.1163 +vn 0.6394 -0.7689 0.0000 +vn 0.5880 -0.7851 0.1946 +vn 0.5246 -0.8438 -0.1134 +vn 0.6127 -0.7821 -0.1133 +vn 0.5420 -0.8322 -0.1172 +vn 0.1585 -0.9811 -0.1108 +vn 0.1016 -0.9946 0.0204 +vn 0.0000 -0.9931 -0.1169 +vn -0.4534 -0.8867 -0.0910 +vn 0.5746 -0.7318 -0.3664 +vn 0.2249 -0.8096 -0.5422 +vn 0.1815 -0.9766 -0.1153 +vn 0.2412 -0.8432 -0.4804 +vn 0.2731 -0.9547 -0.1179 +vn 0.4684 -0.8762 -0.1139 +vn 0.4365 -0.8727 -0.2187 +vn 0.4535 -0.8844 -0.1103 +usemtl None +s off +f 499/483/681 495/484/681 507/485/681 +f 486/486/682 484/487/682 489/488/682 +f 487/489/683 486/486/683 489/488/683 +f 488/490/684 487/489/684 490/491/684 +f 486/486/683 487/489/683 491/492/683 +f 487/489/684 488/490/684 491/492/684 +f 484/487/682 486/486/682 492/493/682 +f 486/486/685 491/492/685 492/493/685 +f 484/487/686 485/494/686 493/495/686 +f 484/487/682 492/493/682 494/496/682 +f 488/490/684 490/491/684 495/484/684 +f 489/488/682 484/487/682 496/497/682 +f 487/489/687 489/488/687 496/497/687 +f 484/487/686 493/495/686 496/497/686 +f 494/496/688 492/493/688 497/498/688 +f 491/492/684 488/490/684 498/499/684 +f 492/493/685 491/492/685 498/499/685 +f 497/498/689 483/500/689 499/483/689 +f 494/496/690 497/498/690 499/483/690 +f 493/495/691 485/494/691 500/501/691 +f 490/491/692 493/495/692 500/501/692 +f 483/500/693 497/498/693 501/502/693 +f 499/483/694 483/500/694 501/502/694 +f 495/484/695 499/483/695 501/502/695 +f 490/491/684 487/489/684 502/503/684 +f 487/489/687 496/497/687 502/503/687 +f 496/497/686 493/495/686 502/503/686 +f 485/494/696 484/487/696 503/504/696 +f 484/487/697 494/496/697 503/504/697 +f 494/496/698 490/491/698 503/504/698 +f 500/501/699 485/494/699 503/504/699 +f 490/491/700 500/501/700 503/504/700 +f 488/490/701 497/498/701 504/505/701 +f 497/498/702 492/493/702 504/505/702 +f 498/499/703 488/490/703 504/505/703 +f 492/493/704 498/499/704 504/505/704 +f 493/495/705 490/491/705 505/506/705 +f 490/491/684 502/503/684 505/506/684 +f 502/503/686 493/495/686 505/506/686 +f 488/490/706 495/484/706 506/507/706 +f 497/498/707 488/490/707 506/507/707 +f 495/484/708 501/502/708 506/507/708 +f 501/502/709 497/498/709 506/507/709 +f 490/491/710 494/496/710 507/485/710 +f 495/484/711 490/491/711 507/485/711 +f 494/496/712 499/483/712 507/485/712 +o Bowl_hull_16 +v 0.032323 -0.018968 -0.033404 +v 0.032753 -0.003020 -0.050214 +v 0.034909 -0.003020 -0.050214 +v 0.024133 -0.025434 -0.050214 +v 0.032323 -0.003453 -0.033404 +v 0.024133 -0.021986 -0.033404 +v 0.037065 -0.003020 -0.033404 +v 0.032753 -0.013797 -0.050214 +v 0.024565 -0.028020 -0.033404 +v 0.024133 -0.021986 -0.050214 +v 0.028014 -0.021986 -0.050214 +v 0.036201 -0.009488 -0.033835 +v 0.034909 -0.006901 -0.049352 +v 0.027583 -0.025434 -0.033835 +v 0.032323 -0.003453 -0.050214 +v 0.024565 -0.025864 -0.049352 +v 0.034477 -0.014659 -0.033835 +v 0.031461 -0.016812 -0.049352 +v 0.024133 -0.028020 -0.033404 +v 0.037065 -0.004315 -0.034266 +v 0.034047 -0.010349 -0.049783 +v 0.030599 -0.021552 -0.034266 +v 0.035339 -0.003453 -0.049783 +v 0.032753 -0.003020 -0.033404 +v 0.030170 -0.018968 -0.049783 +v 0.025428 -0.027587 -0.033835 +v 0.025859 -0.024570 -0.049783 +vt 0.896535 0.974354 +vt 0.982674 0.974354 +vt 0.861981 0.025646 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.896535 0.000000 +vt 0.637921 1.000000 +vt 0.017326 1.000000 +vt 0.758614 1.000000 +vt 0.000000 1.000000 +vt 0.431089 0.000000 +vt 1.000000 1.000000 +vt 0.758614 0.000000 +vt 0.758614 0.000000 +vt 0.258712 0.974354 +vt 0.017326 0.000000 +vt 0.465544 0.974354 +vt 0.551684 0.051292 +vt 1.000000 1.000000 +vt 0.913763 0.051292 +vt 0.051782 0.948708 +vt 0.155247 0.051292 +vt 0.293168 0.025646 +vt 0.741288 0.948708 +vt 0.017326 0.025646 +vt 0.000000 1.000000 +vt 0.637921 0.025646 +vn 0.7021 -0.7029 -0.1140 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 1.0000 0.0000 +vn -0.9147 0.4042 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.3745 -0.1113 0.9205 +vn 0.4390 -0.3762 0.8159 +vn -0.7094 0.7049 0.0000 +vn 0.5075 -0.1692 0.8448 +vn 0.8847 -0.4532 -0.1091 +vn 0.9003 -0.4194 -0.1168 +vn -0.5625 -0.8172 -0.1257 +vn 0.0000 -0.9910 -0.1340 +vn 0.9660 -0.1433 0.2151 +vn 0.9788 -0.1725 -0.1103 +vn 0.5771 -0.1154 -0.8085 +vn 0.9667 -0.2269 -0.1183 +vn 0.9346 -0.3362 -0.1161 +vn 0.9429 -0.3144 -0.1104 +vn 0.7850 -0.5884 0.1937 +vn 0.7790 -0.6174 -0.1095 +vn 0.7524 0.6516 -0.0965 +vn 0.9918 0.0708 -0.1064 +vn 0.9836 -0.1374 -0.1170 +vn 0.6398 -0.1199 -0.7592 +vn 0.8819 -0.1653 -0.4415 +vn -0.7093 0.7049 0.0000 +vn 0.6687 -0.3871 -0.6349 +vn 0.8444 -0.4466 -0.2958 +vn 0.8622 -0.4937 -0.1133 +vn 0.8434 -0.5257 -0.1109 +vn 0.8159 -0.5662 -0.1169 +vn 0.5783 -0.5790 0.5748 +vn 0.3957 -0.9101 -0.1230 +vn 0.6825 -0.7213 -0.1180 +vn 0.4332 -0.4876 -0.7580 +vn 0.7532 -0.6474 -0.1165 +vn 0.4767 -0.6671 -0.5725 +usemtl None +s off +f 521/508/713 533/509/713 534/510/713 +f 509/511/714 510/512/714 511/513/714 +f 508/514/715 512/515/715 513/516/715 +f 510/512/716 509/511/716 514/517/716 +f 512/515/715 508/514/715 514/517/715 +f 511/513/714 510/512/714 515/518/714 +f 508/514/715 513/516/715 516/519/715 +f 509/511/714 511/513/714 517/520/714 +f 513/516/717 512/515/717 517/520/717 +f 511/513/718 513/516/718 517/520/718 +f 511/513/714 515/518/714 518/521/714 +f 514/517/719 508/514/719 519/522/719 +f 508/514/720 516/519/720 521/508/720 +f 512/515/721 509/511/721 522/523/721 +f 509/511/714 517/520/714 522/523/714 +f 517/520/717 512/515/717 522/523/717 +f 519/522/722 508/514/722 524/524/722 +f 524/524/723 508/514/723 525/525/723 +f 515/518/724 524/524/724 525/525/724 +f 513/516/718 511/513/718 526/526/718 +f 516/519/715 513/516/715 526/526/715 +f 511/513/725 523/527/725 526/526/725 +f 523/527/726 516/519/726 526/526/726 +f 514/517/727 519/522/727 527/528/727 +f 519/522/728 520/529/728 527/528/728 +f 515/518/729 510/512/729 528/530/729 +f 520/529/730 519/522/730 528/530/730 +f 524/524/731 515/518/731 528/530/731 +f 519/522/732 524/524/732 528/530/732 +f 508/514/733 521/508/733 529/531/733 +f 521/508/734 518/521/734 529/531/734 +f 510/512/735 514/517/735 530/532/735 +f 514/517/736 527/528/736 530/532/736 +f 527/528/737 520/529/737 530/532/737 +f 528/530/738 510/512/738 530/532/738 +f 520/529/739 528/530/739 530/532/739 +f 509/511/740 512/515/740 531/533/740 +f 514/517/716 509/511/716 531/533/716 +f 512/515/715 514/517/715 531/533/715 +f 518/521/741 515/518/741 532/534/741 +f 515/518/742 525/525/742 532/534/742 +f 525/525/743 508/514/743 532/534/743 +f 508/514/744 529/531/744 532/534/744 +f 529/531/745 518/521/745 532/534/745 +f 521/508/746 516/519/746 533/509/746 +f 516/519/747 523/527/747 533/509/747 +f 533/509/748 523/527/748 534/510/748 +f 511/513/749 518/521/749 534/510/749 +f 518/521/750 521/508/750 534/510/750 +f 523/527/751 511/513/751 534/510/751 +o Bowl_hull_17 +v -0.040537 0.051736 0.018334 +v -0.069415 0.046132 0.049371 +v -0.068554 0.046132 0.048076 +v -0.045711 0.069838 0.049371 +v -0.040107 0.068115 0.049801 +v -0.040104 0.045698 0.017904 +v -0.065105 0.045698 0.050235 +v -0.057349 0.060785 0.049801 +v -0.046141 0.046132 0.017470 +v -0.040107 0.072858 0.050235 +v -0.040104 0.045698 0.011003 +v -0.063814 0.053031 0.048507 +v -0.054333 0.063372 0.049371 +v -0.069415 0.045698 0.050235 +v -0.040968 0.072427 0.048941 +v -0.064244 0.045698 0.049371 +v -0.057349 0.046132 0.032124 +v -0.059932 0.055617 0.046352 +v -0.061226 0.056909 0.050235 +v -0.040968 0.046562 0.011867 +v -0.050023 0.066820 0.049371 +v -0.040537 0.059065 0.028680 +v -0.040107 0.068546 0.050235 +v -0.053900 0.056479 0.039885 +v -0.057349 0.045698 0.032124 +v -0.049590 0.067251 0.050235 +v -0.040104 0.059065 0.028680 +v -0.066830 0.049580 0.048937 +v -0.051745 0.047426 0.026095 +vt 0.901038 0.323544 +vt 0.164839 0.794028 +vt 0.384691 0.602839 +vt 0.175901 1.000000 +vt 1.000000 0.147039 +vt 0.000000 1.000000 +vt 0.977976 0.000000 +vt 0.944988 0.029369 +vt 1.000000 0.000000 +vt 1.000000 0.999902 +vt 0.977976 0.808713 +vt 0.967013 0.970534 +vt 0.988939 0.999902 +vt 0.977976 0.176407 +vt 0.955951 0.191092 +vt 0.988939 0.411650 +vt 1.000000 0.279393 +vt 0.186864 0.985218 +vt 0.022024 0.970534 +vt 0.977976 0.514538 +vt 0.977976 0.661576 +vt 0.450568 0.985218 +vt 1.000000 0.999902 +vt 0.736198 0.529320 +vt 0.538371 0.411650 +vt 0.538371 0.411650 +vt 1.000000 0.676358 +vt 0.450568 1.000000 +vt 0.966915 0.088204 +vn -0.6244 0.6032 -0.4962 +vn -0.0000 -1.0000 0.0000 +vn -0.5589 -0.7413 -0.3717 +vn 0.0000 -0.0000 1.0000 +vn -0.4773 0.8784 0.0251 +vn 0.5998 -0.6546 0.4601 +vn 0.5596 -0.6132 0.5575 +vn -0.6539 0.6180 -0.4364 +vn -0.6700 0.6253 -0.4000 +vn -0.7743 0.5656 0.2837 +vn 0.1441 0.7680 -0.6240 +vn -0.7317 -0.0518 -0.6796 +vn -0.5549 0.6672 -0.4968 +vn -0.5426 0.6783 -0.4955 +vn -0.4498 0.7412 -0.4983 +vn -0.5106 0.7016 -0.4971 +vn -0.4981 0.7119 -0.4952 +vn 1.0000 -0.0003 0.0003 +vn 0.5442 -0.5955 0.5910 +vn -0.6083 0.6286 -0.4846 +vn -0.6092 0.6277 -0.4846 +vn -0.6185 0.6099 -0.4956 +vn -0.5917 0.6343 -0.4976 +vn -0.5795 0.6464 -0.4963 +vn -0.4603 -0.8043 -0.3759 +vn -0.5575 -0.7424 -0.3715 +vn -0.7943 0.0000 -0.6075 +vn -0.8183 0.0000 -0.5748 +vn -0.4885 0.8263 0.2803 +vn -0.6404 0.7623 0.0938 +vn -0.5336 0.6003 0.5957 +vn -0.5691 0.8134 -0.1201 +vn -0.6229 0.7786 -0.0757 +vn 1.0000 0.0000 0.0000 +vn 0.6726 0.5902 -0.4463 +vn 0.3624 0.7851 -0.5023 +vn 0.0000 0.8160 -0.5781 +vn 0.0000 0.8348 -0.5505 +vn 1.0000 -0.0002 0.0002 +vn 1.0000 -0.0000 0.0001 +vn -0.7281 0.4850 -0.4843 +vn -0.7162 0.4837 -0.5031 +vn -0.6837 0.5358 -0.4954 +vn -0.7971 0.6026 0.0389 +vn -0.7416 0.6146 -0.2688 +vn -0.6784 0.5202 -0.5189 +vn -0.6640 0.5585 -0.4972 +vn -0.6550 0.5705 -0.4954 +usemtl None +s off +f 552/535/752 543/536/752 563/537/752 +f 540/538/753 541/539/753 545/540/753 +f 536/541/754 537/542/754 548/543/754 +f 541/539/755 544/544/755 548/543/755 +f 545/540/753 541/539/753 548/543/753 +f 538/545/756 544/544/756 549/546/756 +f 540/538/757 539/547/757 550/548/757 +f 541/539/753 540/538/753 550/548/753 +f 539/547/758 541/539/758 550/548/758 +f 546/549/759 542/550/759 552/535/759 +f 542/550/760 546/549/760 553/551/760 +f 536/541/761 548/543/761 553/551/761 +f 548/543/755 544/544/755 553/551/755 +f 535/552/762 545/540/762 554/553/762 +f 545/540/763 543/536/763 554/553/763 +f 547/554/764 535/552/764 554/553/764 +f 535/552/765 547/554/765 555/555/765 +f 538/545/766 549/546/766 556/556/766 +f 535/552/767 555/555/767 556/556/767 +f 555/555/768 538/545/768 556/556/768 +f 539/547/769 540/538/769 557/557/769 +f 541/539/770 539/547/770 557/557/770 +f 544/544/755 541/539/755 557/557/755 +f 542/550/771 547/554/771 558/558/771 +f 552/535/772 542/550/772 558/558/772 +f 543/536/773 552/535/773 558/558/773 +f 554/553/774 543/536/774 558/558/774 +f 547/554/775 554/553/775 558/558/775 +f 543/536/776 545/540/776 559/559/776 +f 548/543/777 537/542/777 559/559/777 +f 545/540/753 548/543/753 559/559/753 +f 551/560/778 543/536/778 559/559/778 +f 537/542/779 551/560/779 559/559/779 +f 544/544/780 538/545/780 560/561/780 +f 547/554/781 542/550/781 560/561/781 +f 542/550/782 553/551/782 560/561/782 +f 553/551/755 544/544/755 560/561/755 +f 538/545/783 555/555/783 560/561/783 +f 555/555/784 547/554/784 560/561/784 +f 540/538/785 545/540/785 561/562/785 +f 545/540/786 535/552/786 561/562/786 +f 549/546/787 544/544/787 561/562/787 +f 535/552/788 556/556/788 561/562/788 +f 556/556/789 549/546/789 561/562/789 +f 557/557/790 540/538/790 561/562/790 +f 544/544/791 557/557/791 561/562/791 +f 537/542/792 536/541/792 562/563/792 +f 551/560/793 537/542/793 562/563/793 +f 546/549/794 551/560/794 562/563/794 +f 536/541/795 553/551/795 562/563/795 +f 553/551/796 546/549/796 562/563/796 +f 543/536/797 551/560/797 563/537/797 +f 551/560/798 546/549/798 563/537/798 +f 546/549/799 552/535/799 563/537/799 +o Bowl_hull_18 +v -0.047003 0.043110 0.014881 +v -0.078037 0.029318 0.049367 +v -0.078037 0.028886 0.049367 +v -0.040969 0.028886 -0.008389 +v -0.040104 0.045266 0.017038 +v -0.069418 0.045697 0.048940 +v -0.073729 0.028886 0.049801 +v -0.040538 0.028886 -0.001492 +v -0.065106 0.045266 0.050235 +v -0.040104 0.045697 0.010574 +v -0.055195 0.029318 0.012731 +v -0.072868 0.039660 0.048506 +v -0.042261 0.031473 -0.004510 +v -0.055195 0.045697 0.028676 +v -0.040104 0.033629 -0.004510 +v -0.073298 0.040092 0.050235 +v -0.065106 0.045697 0.050235 +v -0.047865 0.029318 0.001520 +v -0.073729 0.029318 0.050235 +v -0.040969 0.045266 0.010140 +v -0.075883 0.034060 0.048940 +v -0.040104 0.044403 0.016176 +v -0.062091 0.044834 0.037296 +v -0.040538 0.036647 -0.001064 +v -0.040969 0.045697 0.018333 +v -0.040104 0.028886 -0.002359 +v -0.067695 0.042679 0.043332 +v -0.040969 0.045266 0.018333 +v -0.062091 0.029318 0.023501 +v -0.078037 0.028886 0.050235 +v -0.069849 0.045697 0.050235 +v -0.040104 0.028886 -0.008828 +v -0.055195 0.028886 0.012731 +v -0.042261 0.029318 -0.006666 +v -0.072868 0.028886 0.048506 +v -0.040969 0.032336 -0.005377 +v -0.042692 0.045697 0.012731 +v -0.074160 0.029318 0.042904 +vt 0.978074 0.056779 +vt 0.547377 0.420362 +vt 0.875881 0.102203 +vt 0.985317 0.000000 +vt 0.007439 0.977190 +vt 0.992659 0.113559 +vt 0.124217 0.988546 +vt 0.978074 0.227215 +vt 0.328504 1.000000 +vt 0.634984 0.602154 +vt 0.437940 1.000000 +vt 0.073121 1.000000 +vt 0.970732 0.136270 +vt 1.000000 0.124915 +vt 1.000000 0.340871 +vt 1.000000 0.340871 +vt 0.365016 0.602154 +vt 0.175215 0.795399 +vt 1.000000 0.113559 +vt 0.985317 0.000000 +vt 0.423355 1.000000 +vt 0.780932 0.420362 +vt 0.401429 0.818111 +vt 0.131460 0.988546 +vt 0.321163 0.977190 +vt 0.459867 0.977190 +vt 0.109534 1.000000 +vt 0.883124 0.272638 +vt 0.459867 0.977190 +vt 1.000000 0.000000 +vt 1.000000 0.215859 +vt 0.000000 1.000000 +vt 0.365016 0.602154 +vt 0.036609 0.943123 +vt 0.073121 0.943123 +vt 0.970732 0.136270 +vt 0.058438 0.977190 +vt 0.365016 0.931767 +vn -0.7980 0.3418 -0.4964 +vn 0.0000 -1.0000 -0.0000 +vn -0.0000 1.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn -0.8113 0.4869 -0.3236 +vn 0.0000 0.0000 1.0000 +vn -0.7595 0.4201 -0.4966 +vn -0.9104 0.4066 -0.0764 +vn -0.8449 0.4303 -0.3179 +vn -0.6383 0.6260 -0.4480 +vn -0.6565 0.5680 -0.4964 +vn 0.4252 0.7067 -0.5654 +vn -0.0872 0.7880 -0.6095 +vn 0.5125 0.8568 0.0572 +vn 0.7975 0.0000 0.6034 +vn 0.7883 -0.4718 0.3949 +vn -0.7474 0.4615 -0.4780 +vn -0.7507 0.4369 -0.4956 +vn -0.7171 0.4975 -0.4881 +vn 0.7181 -0.4935 0.4907 +vn 0.7323 -0.3959 0.5541 +vn 0.7171 -0.4985 0.4871 +vn 0.7270 -0.4852 0.4857 +vn 0.8315 0.0000 0.5555 +vn -0.7748 0.3920 -0.4960 +vn -0.7807 0.3821 -0.4945 +vn -1.0000 0.0000 0.0000 +vn -0.9042 0.3824 0.1901 +vn 0.0708 -0.7073 0.7033 +vn -0.8194 0.5043 -0.2725 +vn -0.7633 -0.3910 -0.5142 +vn -0.8369 0.0000 -0.5473 +vn -0.7995 -0.3352 -0.4984 +vn -0.8422 0.0000 -0.5392 +vn -0.8066 -0.2114 -0.5521 +vn -0.7120 0.4966 -0.4964 +vn -0.7252 0.4771 -0.4964 +vn -0.7206 0.4844 -0.4960 +vn 0.7127 -0.5170 0.4741 +vn 0.7067 -0.5401 0.4570 +vn -0.6861 0.5326 -0.4956 +vn -0.6871 0.5312 -0.4957 +vn -0.6605 0.5630 -0.4968 +vn -0.3699 0.6753 -0.6381 +vn -0.3573 0.6143 -0.7035 +vn -0.2566 0.6507 -0.7146 +vn -0.6173 0.5175 -0.5926 +vn -0.6874 0.5137 -0.5135 +vn -0.6149 0.6240 -0.4822 +vn -0.2798 0.8994 -0.3359 +vn -0.6152 0.6117 -0.4974 +vn -0.5993 0.6232 -0.5024 +vn -0.8576 0.0000 -0.5144 +vn -0.8112 0.3245 -0.4865 +vn -0.8171 -0.2722 -0.5082 +usemtl None +s off +f 584/564/800 592/565/800 601/566/800 +f 566/567/801 567/568/801 570/569/801 +f 570/569/801 567/568/801 571/570/801 +f 569/571/802 573/572/802 577/573/802 +f 573/572/803 568/574/803 578/575/803 +f 569/571/804 575/576/804 579/577/804 +f 573/572/802 569/571/802 580/578/802 +f 579/577/805 572/579/805 580/578/805 +f 574/580/806 575/576/806 581/581/806 +f 572/579/805 579/577/805 582/582/805 +f 565/583/807 579/577/807 584/564/807 +f 579/577/808 575/576/808 584/564/808 +f 578/575/803 568/574/803 585/584/803 +f 569/571/809 577/573/809 586/585/809 +f 577/573/810 564/586/810 587/587/810 +f 573/572/811 578/575/811 587/587/811 +f 583/588/812 573/572/812 587/587/812 +f 568/574/813 573/572/813 588/589/813 +f 580/578/814 572/579/814 588/589/814 +f 573/572/802 580/578/802 588/589/802 +f 571/570/801 567/568/801 589/590/801 +f 585/584/815 571/570/815 589/590/815 +f 578/575/803 585/584/803 589/590/803 +f 575/576/816 569/571/816 590/591/816 +f 581/581/817 575/576/817 590/591/817 +f 569/571/818 586/585/818 590/591/818 +f 582/582/819 570/569/819 591/592/819 +f 572/579/820 582/582/820 591/592/820 +f 570/569/821 585/584/821 591/592/821 +f 585/584/822 568/574/822 591/592/822 +f 568/574/823 588/589/823 591/592/823 +f 588/589/814 572/579/814 591/592/814 +f 575/576/824 574/580/824 592/565/824 +f 584/564/825 575/576/825 592/565/825 +f 565/583/826 566/567/826 593/593/826 +f 566/567/801 570/569/801 593/593/801 +f 579/577/827 565/583/827 593/593/827 +f 570/569/828 582/582/828 593/593/828 +f 582/582/805 579/577/805 593/593/805 +f 569/571/829 579/577/829 594/594/829 +f 580/578/802 569/571/802 594/594/802 +f 579/577/805 580/578/805 594/594/805 +f 589/590/801 567/568/801 595/595/801 +f 578/575/803 589/590/803 595/595/803 +f 567/568/801 566/567/801 596/596/801 +f 581/581/830 567/568/830 596/596/830 +f 574/580/831 581/581/831 596/596/831 +f 566/567/832 592/565/832 596/596/832 +f 592/565/833 574/580/833 596/596/833 +f 567/568/834 581/581/834 597/597/834 +f 586/585/835 576/598/835 597/597/835 +f 581/581/836 590/591/836 597/597/836 +f 590/591/837 586/585/837 597/597/837 +f 570/569/801 571/570/801 598/599/801 +f 585/584/838 570/569/838 598/599/838 +f 571/570/839 585/584/839 598/599/839 +f 586/585/840 577/573/840 599/600/840 +f 576/598/841 586/585/841 599/600/841 +f 577/573/842 587/587/842 599/600/842 +f 587/587/843 578/575/843 599/600/843 +f 595/595/844 567/568/844 599/600/844 +f 578/575/845 595/595/845 599/600/845 +f 567/568/846 597/597/846 599/600/846 +f 597/597/847 576/598/847 599/600/847 +f 564/586/848 577/573/848 600/601/848 +f 577/573/802 573/572/802 600/601/802 +f 573/572/849 583/588/849 600/601/849 +f 587/587/850 564/586/850 600/601/850 +f 583/588/851 587/587/851 600/601/851 +f 566/567/852 565/583/852 601/566/852 +f 565/583/853 584/564/853 601/566/853 +f 592/565/854 566/567/854 601/566/854 +o Bowl_hull_19 +v -0.044848 0.027158 -0.004945 +v -0.081920 0.015521 0.049370 +v -0.081920 0.015089 0.049370 +v -0.074160 0.028453 0.050235 +v -0.040968 0.015089 -0.012274 +v -0.040538 0.028453 -0.001928 +v -0.077176 0.015089 0.048934 +v -0.040538 0.015521 -0.020469 +v -0.077176 0.028885 0.047639 +v -0.040538 0.028885 -0.009257 +v -0.079763 0.024142 0.049370 +v -0.040108 0.028885 -0.002793 +v -0.060369 0.028885 0.020482 +v -0.050022 0.015521 -0.004945 +v -0.040108 0.015089 -0.020469 +v -0.041401 0.017678 -0.017873 +v -0.074160 0.028885 0.050235 +v -0.081920 0.015089 0.050235 +v -0.078470 0.028453 0.050235 +v -0.040108 0.015089 -0.013998 +v -0.040538 0.020695 -0.017015 +v -0.079763 0.020695 0.047639 +v -0.078040 0.015089 0.050235 +v -0.040108 0.028885 -0.009257 +v -0.076746 0.025002 0.044629 +v -0.068556 0.026727 0.032123 +v -0.044848 0.015521 -0.013568 +v -0.062518 0.015521 0.016170 +v -0.054332 0.028885 0.011007 +v -0.050022 0.015089 -0.004945 +v -0.073296 0.028453 0.048934 +v -0.042261 0.028885 -0.007097 +v -0.060799 0.028022 0.020482 +vt 0.445184 0.659814 +vt 0.048845 0.989721 +vt 0.579189 0.505140 +vt 0.115897 0.979442 +vt 0.262236 0.989721 +vt 0.981597 0.113461 +vt 0.987764 0.000000 +vt 0.158575 0.989721 +vt 0.963293 0.113461 +vt 0.250000 1.000000 +vt 0.579189 0.515418 +vt 0.000000 1.000000 +vt 1.000000 0.185609 +vt 0.987764 0.000000 +vt 1.000000 0.000000 +vt 0.987764 0.051591 +vt 1.000000 0.185609 +vt 1.000000 0.082526 +vt 0.091523 1.000000 +vt 0.000000 0.989721 +vt 0.036707 0.969065 +vt 0.963293 0.051591 +vt 1.000000 0.092805 +vt 0.158575 1.000000 +vt 0.920713 0.123740 +vt 0.219558 0.762898 +vt 0.743833 0.319628 +vt 0.097592 0.886637 +vt 0.518207 0.464023 +vt 0.219558 0.886637 +vt 0.219558 0.762898 +vt 0.981597 0.206265 +vt 0.189115 0.948507 +vn -0.7778 0.3862 -0.4958 +vn 0.7930 -0.3887 0.4691 +vn -0.0000 -1.0000 0.0000 +vn -0.0000 1.0000 0.0000 +vn 0.8173 0.2378 0.5248 +vn -1.0000 0.0000 0.0000 +vn -0.9630 0.2410 0.1204 +vn 0.0000 0.0000 1.0000 +vn -0.8645 0.3347 -0.3751 +vn -0.0991 0.9884 0.1152 +vn -0.9491 0.2451 0.1980 +vn 0.8381 -0.3506 0.4180 +vn 0.9101 -0.2612 0.3217 +vn 1.0000 0.0000 0.0000 +vn 0.4874 0.4848 -0.7262 +vn -0.7438 0.3711 -0.5559 +vn -0.8733 0.2185 -0.4354 +vn 0.8098 -0.2351 0.5375 +vn 0.0000 0.6877 -0.7260 +vn 0.8935 0.2832 -0.3485 +vn -0.8323 0.2792 -0.4789 +vn -0.8375 0.2451 -0.4884 +vn -0.8351 0.2383 -0.4958 +vn -0.8178 0.2934 -0.4951 +vn -0.8183 0.2906 -0.4959 +vn -0.8128 0.2855 -0.5077 +vn -0.8272 0.2634 -0.4963 +vn -0.8121 0.3066 -0.4965 +vn -0.8634 0.0000 -0.5046 +vn -0.8480 0.1878 -0.4956 +vn -0.8388 0.2236 -0.4964 +vn -0.7586 0.4216 -0.4967 +vn -0.6459 -0.6424 -0.4125 +vn -0.7826 -0.3854 -0.4889 +vn -0.8575 0.0000 -0.5145 +vn -0.8470 -0.1876 -0.4974 +vn -0.8606 0.0000 -0.5093 +vn 0.8167 -0.2372 0.5260 +vn 0.8332 0.0000 0.5530 +vn 0.8397 0.0499 0.5408 +vn -0.7289 0.4603 -0.5068 +vn -0.6729 0.5087 -0.5370 +vn -0.7275 0.4852 -0.4851 +vn -0.7830 0.3900 -0.4846 +vn -0.7867 0.3665 -0.4967 +vn -0.7964 0.3524 -0.4915 +vn -0.8003 0.3374 -0.4957 +vn -0.7775 0.3873 -0.4955 +usemtl None +s off +f 630/602/855 622/603/855 634/604/855 +f 606/605/856 607/606/856 608/607/856 +f 604/608/857 606/605/857 608/607/857 +f 611/609/858 610/610/858 613/611/858 +f 610/610/858 611/609/858 614/612/858 +f 606/605/857 604/608/857 616/613/857 +f 607/606/859 613/611/859 618/614/859 +f 613/611/858 610/610/858 618/614/858 +f 603/615/860 604/608/860 619/616/860 +f 604/608/857 608/607/857 619/616/857 +f 612/617/861 603/615/861 619/616/861 +f 605/618/862 618/614/862 619/616/862 +f 619/616/862 618/614/862 620/619/862 +f 610/610/863 612/617/863 620/619/863 +f 618/614/864 610/610/864 620/619/864 +f 612/617/865 619/616/865 620/619/865 +f 607/606/866 606/605/866 621/620/866 +f 613/611/867 607/606/867 621/620/867 +f 606/605/857 616/613/857 621/620/857 +f 616/613/868 613/611/868 621/620/868 +f 616/613/869 609/621/869 622/603/869 +f 609/621/870 617/622/870 622/603/870 +f 603/615/871 612/617/871 623/623/871 +f 608/607/872 605/618/872 624/624/872 +f 619/616/857 608/607/857 624/624/857 +f 605/618/862 619/616/862 624/624/862 +f 611/609/858 613/611/858 625/625/858 +f 613/611/868 616/613/868 625/625/868 +f 622/603/873 611/609/873 625/625/873 +f 616/613/874 622/603/874 625/625/874 +f 612/617/875 610/610/875 626/626/875 +f 623/623/876 612/617/876 626/626/876 +f 615/627/877 623/623/877 626/626/877 +f 626/626/878 610/610/878 627/628/878 +f 626/626/879 627/628/879 628/629/879 +f 617/622/880 609/621/880 628/629/880 +f 615/627/881 626/626/881 628/629/881 +f 627/628/882 617/622/882 628/629/882 +f 604/608/883 603/615/883 629/630/883 +f 603/615/884 623/623/884 629/630/884 +f 623/623/885 615/627/885 629/630/885 +f 614/612/858 611/609/858 630/602/858 +f 602/631/886 622/603/886 630/602/886 +f 616/613/857 604/608/857 631/632/857 +f 609/621/887 616/613/887 631/632/887 +f 628/629/888 609/621/888 631/632/888 +f 615/627/889 628/629/889 631/632/889 +f 604/608/890 629/630/890 631/632/890 +f 629/630/891 615/627/891 631/632/891 +f 608/607/892 607/606/892 632/633/892 +f 605/618/872 608/607/872 632/633/872 +f 618/614/893 605/618/893 632/633/893 +f 607/606/894 618/614/894 632/633/894 +f 622/603/895 602/631/895 633/634/895 +f 611/609/896 622/603/896 633/634/896 +f 602/631/897 630/602/897 633/634/897 +f 630/602/858 611/609/858 633/634/858 +f 610/610/898 614/612/898 634/604/898 +f 622/603/899 617/622/899 634/604/899 +f 627/628/900 610/610/900 634/604/900 +f 617/622/901 627/628/901 634/604/901 +f 614/612/902 630/602/902 634/604/902 +o Bowl_hull_20 +v -0.040969 0.014656 -0.020462 +v -0.083210 0.003451 0.049363 +v -0.082779 0.006900 0.048935 +v -0.078040 0.014656 0.050235 +v -0.040539 0.000433 -0.017877 +v -0.041399 0.000433 -0.023911 +v -0.079332 0.000433 0.049799 +v -0.040104 0.015086 -0.014000 +v -0.081488 0.015086 0.048507 +v -0.083210 0.000433 0.049363 +v -0.040539 0.007330 -0.024347 +v -0.078471 0.000433 0.048507 +v -0.054764 0.015086 0.002815 +v -0.040539 0.003881 -0.025211 +v -0.081918 0.015086 0.050235 +v -0.040104 0.014656 -0.014000 +v -0.040104 0.015086 -0.020898 +v -0.040104 0.000433 -0.025211 +v -0.078040 0.015086 0.050235 +v -0.076314 0.009914 0.038160 +v -0.083210 0.000433 0.050235 +v -0.042695 0.009482 -0.020034 +v -0.040104 0.000433 -0.018742 +v -0.046573 0.007330 -0.014000 +v -0.048299 0.002157 -0.011844 +v -0.079766 0.000433 0.050235 +v -0.082779 0.000433 0.048507 +v -0.082779 0.009482 0.049363 +v -0.071575 0.005176 0.029106 +v -0.041399 0.011639 -0.021326 +v -0.063381 0.015086 0.017460 +vt 0.371476 0.659912 +vt 0.068618 0.939892 +vt 0.565583 0.460010 +vt 0.017228 0.969946 +vt 0.097200 0.989917 +vt 0.994225 0.089966 +vt 0.988450 0.000000 +vt 1.000000 0.119922 +vt 0.977095 0.109936 +vt 0.977095 0.039941 +vt 0.148590 1.000000 +vt 1.000000 0.029956 +vt 0.148590 1.000000 +vt 0.011453 0.989917 +vt 0.062940 0.979932 +vt 0.057165 1.000000 +vt 0.000000 1.000000 +vt 0.000000 0.989917 +vt 1.000000 0.119922 +vt 0.988450 0.000000 +vt 1.000000 0.000000 +vt 0.085748 1.000000 +vt 0.148590 0.849927 +vt 0.839957 0.159961 +vt 0.177173 0.809887 +vt 1.000000 0.079882 +vt 0.977095 0.009985 +vt 0.982772 0.009985 +vt 0.988450 0.009985 +vt 0.719949 0.269897 +vt 0.051488 0.969946 +vn -0.8432 0.2070 -0.4961 +vn 0.0000 -1.0000 -0.0000 +vn 0.8287 -0.0921 0.5520 +vn 0.0000 1.0000 0.0000 +vn 0.8610 0.0000 0.5085 +vn 0.8577 -0.0875 0.5066 +vn 0.8571 -0.1597 0.4898 +vn -0.5569 0.3633 -0.7469 +vn -0.5507 0.7622 -0.3404 +vn 1.0000 0.0000 0.0000 +vn -0.7055 -0.0889 -0.7031 +vn 0.8877 0.1119 -0.4466 +vn 0.9321 0.1023 -0.3474 +vn 0.0000 0.0000 1.0000 +vn -1.0000 0.0000 0.0000 +vn 0.8835 -0.1481 0.4444 +vn -0.8570 0.1252 -0.4998 +vn -0.8580 0.1337 -0.4959 +vn -0.8615 0.1065 -0.4965 +vn -0.8550 0.1427 -0.4987 +vn -0.8552 0.1497 -0.4963 +vn -0.8660 0.0280 -0.4992 +vn 0.7054 -0.0856 0.7036 +vn -0.8936 0.0000 -0.4490 +vn -0.8684 0.0168 -0.4956 +vn -0.8682 -0.0021 -0.4961 +vn -0.9166 0.0654 -0.3944 +vn -0.9539 0.1835 -0.2376 +vn -0.8616 0.1233 -0.4924 +vn -0.9685 0.0691 0.2394 +vn -0.9186 0.0809 0.3869 +vn -0.8679 0.0469 -0.4945 +vn -0.8644 0.0831 -0.4959 +vn -0.8679 0.0323 -0.4957 +vn -0.8665 0.0519 -0.4964 +vn -0.8646 0.0822 -0.4957 +vn -0.8646 0.0826 -0.4957 +vn -0.7401 0.2806 -0.6112 +vn -0.8285 0.2602 -0.4958 +vn -0.8354 0.1937 -0.5143 +vn -0.8427 0.2088 -0.4963 +vn -0.8498 0.1792 -0.4956 +usemtl None +s off +f 647/635/903 656/636/903 665/637/903 +f 640/638/904 639/639/904 641/640/904 +f 640/638/904 641/640/904 644/641/904 +f 638/642/905 641/640/905 646/643/905 +f 641/640/904 639/639/904 646/643/904 +f 643/644/906 642/645/906 647/635/906 +f 642/645/906 643/644/906 649/646/906 +f 642/645/907 638/642/907 650/647/907 +f 638/642/908 646/643/908 650/647/908 +f 646/643/909 639/639/909 650/647/909 +f 645/648/910 635/649/910 651/650/910 +f 635/649/911 647/635/911 651/650/911 +f 647/635/906 642/645/906 651/650/906 +f 642/645/912 650/647/912 651/650/912 +f 651/650/912 650/647/912 652/651/912 +f 639/639/904 640/638/904 652/651/904 +f 640/638/913 648/652/913 652/651/913 +f 648/652/914 645/648/914 652/651/914 +f 645/648/915 651/650/915 652/651/915 +f 638/642/907 642/645/907 653/653/907 +f 649/646/916 638/642/916 653/653/916 +f 642/645/906 649/646/906 653/653/906 +f 636/654/917 644/641/917 655/655/917 +f 644/641/904 641/640/904 655/655/904 +f 638/642/916 649/646/916 655/655/916 +f 650/647/918 639/639/918 657/656/918 +f 652/651/912 650/647/912 657/656/912 +f 639/639/904 652/651/904 657/656/904 +f 645/648/919 648/652/919 658/657/919 +f 654/658/920 643/644/920 658/657/920 +f 648/652/921 654/658/921 658/657/921 +f 656/636/922 645/648/922 658/657/922 +f 643/644/923 656/636/923 658/657/923 +f 648/652/924 640/638/924 659/659/924 +f 641/640/925 638/642/925 660/660/925 +f 638/642/916 655/655/916 660/660/916 +f 655/655/904 641/640/904 660/660/904 +f 644/641/926 636/654/926 661/661/926 +f 640/638/904 644/641/904 661/661/904 +f 636/654/927 659/659/927 661/661/927 +f 659/659/928 640/638/928 661/661/928 +f 637/662/929 636/654/929 662/663/929 +f 649/646/930 643/644/930 662/663/930 +f 643/644/931 654/658/931 662/663/931 +f 636/654/932 655/655/932 662/663/932 +f 655/655/933 649/646/933 662/663/933 +f 636/654/934 637/662/934 663/664/934 +f 654/658/935 648/652/935 663/664/935 +f 659/659/936 636/654/936 663/664/936 +f 648/652/937 659/659/937 663/664/937 +f 637/662/938 662/663/938 663/664/938 +f 662/663/939 654/658/939 663/664/939 +f 635/649/940 645/648/940 664/665/940 +f 647/635/941 635/649/941 664/665/941 +f 645/648/942 656/636/942 664/665/942 +f 656/636/943 647/635/943 664/665/943 +f 643/644/906 647/635/906 665/637/906 +f 656/636/944 643/644/944 665/637/944 +o Bowl_hull_21 +v -0.030189 0.064663 0.028240 +v -0.039671 0.039663 0.009287 +v -0.039240 0.040096 0.009715 +v -0.020704 0.040096 -0.017020 +v -0.020704 0.076738 0.050235 +v -0.040102 0.072853 0.048931 +v -0.020704 0.040096 -0.009679 +v -0.040102 0.040958 0.003678 +v -0.021137 0.080619 0.049366 +v -0.040102 0.068111 0.049366 +v -0.025016 0.040096 -0.013998 +v -0.040102 0.053033 0.019623 +v -0.021137 0.050872 -0.000193 +v -0.029327 0.078029 0.049366 +v -0.040102 0.073286 0.050235 +v -0.020704 0.080619 0.050235 +v -0.034931 0.040096 -0.003649 +v -0.039240 0.068977 0.050235 +v -0.021566 0.040096 -0.017020 +v -0.021566 0.039663 -0.017020 +v -0.040102 0.039663 0.002816 +v -0.039671 0.040096 0.010143 +v -0.038809 0.059928 0.028240 +v -0.040102 0.040096 0.010143 +v -0.021137 0.059070 0.013171 +v -0.031480 0.076734 0.048503 +v -0.020704 0.075876 0.048938 +v -0.020704 0.039663 -0.010542 +v -0.039671 0.068111 0.049366 +v -0.026309 0.078887 0.048938 +v -0.036224 0.072424 0.045054 +v -0.031049 0.042257 -0.004939 +v -0.038378 0.066820 0.038154 +v -0.020704 0.059070 0.013171 +v -0.020704 0.041391 -0.007527 +v -0.021566 0.076738 0.042901 +v -0.029758 0.078029 0.050235 +v -0.021566 0.046133 -0.007527 +v -0.040102 0.045700 0.009715 +v -0.040102 0.059062 0.028240 +v -0.033636 0.076305 0.049366 +v -0.031049 0.040096 -0.007961 +vt 0.544832 0.673551 +vt 0.179620 0.936668 +vt 0.134691 0.989428 +vt 0.000000 0.989428 +vt 1.000000 0.094753 +vt 0.109143 0.989428 +vt 0.980619 0.189605 +vt 0.307753 0.968383 +vt 0.987079 0.305403 +vt 1.000000 0.179033 +vt 1.000000 0.000000 +vt 1.000000 0.284260 +vt 0.250196 0.726312 +vt 0.000000 0.989428 +vt 0.000000 1.000000 +vt 0.044930 0.989428 +vt 0.294930 1.000000 +vt 0.198806 0.989428 +vt 0.391151 1.000000 +vt 0.397514 0.989428 +vt 0.403876 0.989428 +vt 0.403876 0.989428 +vt 0.448904 0.526136 +vt 0.974256 0.094851 +vt 0.980717 0.115799 +vt 0.096319 1.000000 +vt 0.987079 0.305403 +vt 0.987079 0.063234 +vt 0.987079 0.000000 +vt 0.980717 0.042287 +vt 0.820380 0.336922 +vt 0.672964 0.505188 +vt 0.922964 0.200078 +vt 0.448904 0.526136 +vt 0.141151 0.957811 +vt 0.890955 0.094753 +vt 1.000000 0.063234 +vt 0.141151 0.842013 +vt 0.672964 0.389585 +vt 0.397514 0.852584 +vt 0.672964 0.526331 +vt 0.987079 0.105325 +vn -0.5207 0.6944 -0.4966 +vn 1.0000 0.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn -0.6376 -0.1276 0.7597 +vn 0.0000 0.8421 -0.5393 +vn 0.0000 0.0000 -1.0000 +vn -0.6588 0.0000 -0.7523 +vn -0.7359 0.3753 -0.5635 +vn 0.0000 -1.0000 0.0000 +vn 0.4089 -0.8143 0.4120 +vn -0.6630 -0.7474 0.0442 +vn 0.0000 -0.8923 0.4514 +vn 0.0000 -0.8137 0.5812 +vn -0.3139 0.8093 -0.4965 +vn 0.4639 -0.7526 0.4673 +vn 0.4019 -0.7626 0.5068 +vn 0.4195 -0.8142 0.4013 +vn 0.4250 -0.8090 0.4062 +vn 0.4480 -0.8920 -0.0596 +vn 0.3123 -0.7459 0.5883 +vn 0.0000 -0.7083 0.7059 +vn 0.3249 -0.7696 0.5497 +vn -0.2948 0.9323 -0.2096 +vn -0.3022 0.8230 -0.4811 +vn -0.2981 0.8160 -0.4952 +vn -0.4347 0.7514 -0.4964 +vn -0.4840 0.7283 -0.4852 +vn -0.4520 0.7415 -0.4958 +vn -0.4078 0.7668 -0.4957 +vn -0.4098 0.7664 -0.4947 +vn 0.3654 0.7881 -0.4953 +vn 0.7102 0.6086 -0.3539 +vn 0.0000 0.8524 -0.5229 +vn 0.0000 0.8593 -0.5116 +vn 0.4747 -0.7542 0.4537 +vn 0.4782 -0.7495 0.4578 +vn 1.0000 -0.0002 0.0000 +vn -0.0638 0.8575 -0.5105 +vn -0.2406 0.8392 -0.4878 +vn -0.2562 0.8293 -0.4965 +vn -0.2982 0.9430 -0.1479 +vn -0.2725 0.9525 0.1357 +vn -0.1447 0.8349 -0.5310 +vn -0.3482 0.7954 -0.4960 +vn -0.3393 0.7990 -0.4964 +vn -0.3751 0.7830 -0.4961 +vn -0.3806 0.7803 -0.4963 +vn -0.5971 0.6308 -0.4956 +vn -0.5544 0.6690 -0.4951 +vn -0.4867 0.7269 -0.4845 +vn -0.4830 0.7213 -0.4964 +vn -0.4888 0.7172 -0.4966 +vn -0.5018 0.7087 -0.4959 +vn -0.4367 0.8537 -0.2836 +vn -0.3558 0.7927 -0.4949 +vn -0.3366 0.8414 -0.4228 +vn -0.3613 0.7905 -0.4946 +vn -0.3890 0.7886 -0.4762 +vn -0.3653 0.9131 -0.1812 +vn -0.4161 0.9076 0.0565 +vn -0.5507 0.6716 -0.4957 +vn -0.5785 -0.5754 -0.5782 +vn -0.4967 -0.7439 -0.4472 +vn -0.3675 -0.8643 -0.3434 +vn -0.5030 0.7030 -0.5027 +usemtl None +s off +f 677/666/945 697/667/945 707/668/945 +f 669/669/946 670/670/946 672/671/946 +f 671/672/947 673/673/947 675/674/947 +f 673/673/947 671/672/947 677/666/947 +f 671/672/947 675/674/947 680/675/947 +f 670/670/946 669/669/946 681/676/946 +f 680/675/948 670/670/948 681/676/948 +f 670/670/948 680/675/948 683/677/948 +f 680/675/949 675/674/949 683/677/949 +f 678/678/950 669/669/950 684/679/950 +f 684/679/951 669/669/951 685/680/951 +f 676/681/952 684/679/952 685/680/952 +f 675/674/947 673/673/947 686/682/947 +f 673/673/953 682/683/953 686/682/953 +f 685/680/954 667/684/954 686/682/954 +f 667/684/955 668/685/955 687/686/955 +f 686/682/956 667/684/956 689/687/956 +f 675/674/947 686/682/947 689/687/947 +f 667/684/957 687/686/957 689/687/957 +f 687/686/958 675/674/958 689/687/958 +f 690/688/959 678/678/959 691/689/959 +f 672/671/946 670/670/946 692/690/946 +f 687/686/960 668/685/960 692/690/960 +f 670/670/961 687/686/961 692/690/961 +f 668/685/962 667/684/962 693/691/962 +f 672/671/963 668/685/963 693/691/963 +f 669/669/946 672/671/946 693/691/946 +f 667/684/954 685/680/954 693/691/954 +f 685/680/964 669/669/964 693/691/964 +f 670/670/965 683/677/965 694/692/965 +f 683/677/966 675/674/966 694/692/966 +f 687/686/967 670/670/967 694/692/967 +f 675/674/958 687/686/958 694/692/958 +f 679/693/968 674/694/968 695/695/968 +f 691/689/969 679/693/969 695/695/969 +f 690/688/970 691/689/970 695/695/970 +f 684/679/971 676/681/971 698/696/971 +f 688/697/972 671/672/972 698/696/972 +f 676/681/973 688/697/973 698/696/973 +f 696/698/974 684/679/974 698/696/974 +f 671/672/975 696/698/975 698/696/975 +f 669/669/976 678/678/976 699/699/976 +f 681/676/946 669/669/946 699/699/946 +f 674/694/977 681/676/977 699/699/977 +f 678/678/978 690/688/978 699/699/978 +f 690/688/979 674/694/979 699/699/979 +f 668/685/980 672/671/980 700/700/980 +f 692/690/981 668/685/981 700/700/981 +f 672/671/982 692/690/982 700/700/982 +f 674/694/983 690/688/983 701/701/983 +f 695/695/984 674/694/984 701/701/984 +f 690/688/985 695/695/985 701/701/985 +f 674/694/986 679/693/986 702/702/986 +f 680/675/948 681/676/948 702/702/948 +f 681/676/987 674/694/987 702/702/987 +f 678/678/988 684/679/988 703/703/988 +f 666/704/989 691/689/989 703/703/989 +f 691/689/990 678/678/990 703/703/990 +f 696/698/991 666/704/991 703/703/991 +f 684/679/992 696/698/992 703/703/992 +f 673/673/947 677/666/947 704/705/947 +f 682/683/993 673/673/993 704/705/993 +f 677/666/994 682/683/994 704/705/994 +f 677/666/947 671/672/947 705/706/947 +f 671/672/995 688/697/995 705/706/995 +f 688/697/996 676/681/996 705/706/996 +f 676/681/997 697/667/997 705/706/997 +f 697/667/998 677/666/998 705/706/998 +f 671/672/999 680/675/999 706/707/999 +f 691/689/1000 666/704/1000 706/707/1000 +f 679/693/1001 691/689/1001 706/707/1001 +f 666/704/1002 696/698/1002 706/707/1002 +f 696/698/1003 671/672/1003 706/707/1003 +f 702/702/1004 679/693/1004 706/707/1004 +f 680/675/1005 702/702/1005 706/707/1005 +f 682/683/1006 677/666/1006 707/668/1006 +f 676/681/1007 685/680/1007 707/668/1007 +f 686/682/1008 682/683/1008 707/668/1008 +f 685/680/1009 686/682/1009 707/668/1009 +f 697/667/1010 676/681/1010 707/668/1010 +o Bowl_hull_22 +v -0.013373 0.082336 0.050235 +v -0.009065 0.039663 -0.017450 +v -0.009496 0.039663 -0.017450 +v -0.002167 0.041389 -0.023911 +v -0.001305 0.079318 0.049796 +v -0.020704 0.040528 -0.009250 +v -0.020704 0.040528 -0.017011 +v -0.020704 0.076735 0.050235 +v -0.001305 0.082771 0.048504 +v -0.001305 0.040532 -0.017880 +v -0.020704 0.079753 0.047643 +v -0.011649 0.040097 -0.023481 +v -0.011649 0.081045 0.046774 +v -0.001305 0.039663 -0.025642 +v -0.008201 0.042689 -0.020465 +v -0.019840 0.039667 -0.010973 +v -0.001305 0.078462 0.048504 +v -0.020704 0.060791 0.015735 +v -0.006478 0.082340 0.048073 +v -0.020704 0.039667 -0.017450 +v -0.017686 0.081475 0.049366 +v -0.001305 0.083206 0.050235 +v -0.005616 0.040097 -0.025642 +v -0.020271 0.040528 -0.009250 +v -0.020271 0.076735 0.050235 +v -0.015960 0.041824 -0.018311 +v -0.001305 0.039663 -0.019604 +v -0.020704 0.080614 0.050235 +v -0.001305 0.041389 -0.023911 +v -0.001305 0.079753 0.050235 +v -0.003892 0.083206 0.049366 +v -0.009496 0.042689 -0.020034 +v -0.009496 0.039663 -0.024342 +v -0.020704 0.050011 -0.001919 +v -0.012942 0.082336 0.049366 +v -0.005616 0.046568 -0.014427 +v -0.020704 0.075444 0.040312 +v -0.018115 0.040097 -0.019596 +v -0.001305 0.042250 -0.014858 +vt 0.977193 0.108947 +vt 0.216034 0.980129 +vt 0.142130 0.940583 +vt 0.113743 0.980129 +vt 0.216034 0.980129 +vt 1.000000 0.148590 +vt 0.977193 0.009984 +vt 0.994225 0.089272 +vt 0.102291 0.980031 +vt 0.965838 0.079287 +vt 0.107968 1.000000 +vt 0.107968 1.000000 +vt 0.000000 1.000000 +vt 0.193324 0.999902 +vt 0.545321 0.514781 +vt 0.107968 0.999902 +vt 1.000000 0.019969 +vt 1.000000 0.000000 +vt 0.068226 0.930501 +vt 0.954385 0.049628 +vt 0.000000 0.990016 +vt 1.000000 0.148590 +vt 0.028485 0.990016 +vt 0.096613 0.950372 +vt 0.079581 1.000000 +vt 1.000000 0.059514 +vt 0.988547 0.039742 +vt 0.022807 0.960356 +vt 0.022807 0.960356 +vt 1.000000 0.079287 +vt 0.988547 0.000000 +vt 0.971515 0.019871 +vt 0.073904 0.930501 +vt 0.017130 1.000000 +vt 0.312647 0.762334 +vt 0.988547 0.019969 +vt 0.147807 0.841425 +vt 0.869225 0.178250 +vt 0.079679 0.990016 +vn 0.2200 -0.8469 0.4840 +vn -1.0000 0.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 -1.0000 0.0006 +vn -0.0004 -1.0000 0.0000 +vn -0.6164 -0.7832 0.0822 +vn 0.0000 0.0000 1.0000 +vn -0.1338 0.8578 -0.4962 +vn 0.0000 -0.8542 0.5199 +vn 0.0000 -0.8946 0.4470 +vn 0.2183 -0.8500 0.4793 +vn 0.1242 -0.8476 0.5159 +vn 0.1253 -0.8269 0.5482 +vn -0.2654 0.8261 -0.4972 +vn 0.0003 -1.0000 0.0012 +vn 0.2051 -0.8738 0.4409 +vn -0.2254 0.9597 0.1680 +vn -0.3400 0.8925 -0.2964 +vn 0.0000 0.8682 -0.4962 +vn 0.0000 0.8014 -0.5981 +vn 0.0712 0.7062 -0.7044 +vn 0.1122 -0.7054 0.6998 +vn -0.0193 0.8682 -0.4959 +vn -0.0423 0.8673 -0.4959 +vn -0.0703 0.9754 0.2092 +vn 0.0816 0.9666 -0.2428 +vn -0.1992 0.8452 -0.4959 +vn -0.1650 0.8525 -0.4959 +vn -0.1843 0.8374 -0.5145 +vn -0.1687 0.8451 -0.5073 +vn -0.0848 -0.8409 -0.5344 +vn -0.3310 0.1915 -0.9240 +vn -0.3113 0.8111 -0.4952 +vn -0.1383 0.8572 -0.4961 +vn -0.0970 0.8707 -0.4822 +vn -0.1779 0.9801 -0.0882 +vn -0.1551 0.8545 -0.4957 +vn -0.0864 0.8991 -0.4291 +vn -0.0955 0.9943 -0.0474 +vn -0.0652 0.8657 -0.4964 +vn -0.0918 0.8637 -0.4956 +vn -0.0734 0.8639 -0.4984 +vn -0.1183 0.8601 -0.4962 +vn -0.2471 0.8323 -0.4962 +vn -0.2046 0.8439 -0.4960 +vn -0.2169 0.8405 -0.4965 +vn -0.6315 0.3517 -0.6910 +vn -0.3169 0.7883 -0.5275 +vn -0.3920 -0.6485 -0.6525 +vn -0.3535 -0.7384 -0.5743 +vn -0.3637 0.7887 -0.4956 +vn -0.3421 0.7973 -0.4973 +vn 0.2195 -0.8482 0.4820 +usemtl None +s off +f 724/708/1011 731/709/1011 746/710/1011 +f 714/711/1012 713/712/1012 715/713/1012 +f 716/714/1013 712/715/1013 717/716/1013 +f 714/711/1012 715/713/1012 718/717/1012 +f 709/718/1014 710/719/1014 721/720/1014 +f 716/714/1013 717/716/1013 721/720/1013 +f 710/719/1015 709/718/1015 723/721/1015 +f 717/716/1013 712/715/1013 724/708/1013 +f 714/711/1012 718/717/1012 725/722/1012 +f 713/712/1012 714/711/1012 727/723/1012 +f 710/719/1016 723/721/1016 727/723/1016 +f 723/721/1017 713/712/1017 727/723/1017 +f 708/724/1018 715/713/1018 729/725/1018 +f 712/715/1013 716/714/1013 729/725/1013 +f 722/726/1019 720/727/1019 730/728/1019 +f 715/713/1020 713/712/1020 731/709/1020 +f 713/712/1021 723/721/1021 731/709/1021 +f 723/721/1022 717/716/1022 731/709/1022 +f 731/709/1023 724/708/1023 732/729/1023 +f 724/708/1024 712/715/1024 732/729/1024 +f 729/725/1018 715/713/1018 732/729/1018 +f 715/713/1020 731/709/1020 732/729/1020 +f 725/722/1025 719/730/1025 733/731/1025 +f 709/718/1014 721/720/1014 734/732/1014 +f 721/720/1013 717/716/1013 734/732/1013 +f 723/721/1026 709/718/1026 734/732/1026 +f 717/716/1027 723/721/1027 734/732/1027 +f 715/713/1018 708/724/1018 735/733/1018 +f 718/717/1012 715/713/1012 735/733/1012 +f 708/724/1028 728/734/1028 735/733/1028 +f 728/734/1029 718/717/1029 735/733/1029 +f 711/735/1030 716/714/1030 736/736/1030 +f 716/714/1013 721/720/1013 736/736/1013 +f 730/728/1031 711/735/1031 736/736/1031 +f 721/720/1032 730/728/1032 736/736/1032 +f 712/715/1013 729/725/1013 737/737/1013 +f 732/729/1033 712/715/1033 737/737/1033 +f 729/725/1018 732/729/1018 737/737/1018 +f 716/714/1034 711/735/1034 738/738/1034 +f 711/735/1035 726/739/1035 738/738/1035 +f 708/724/1036 729/725/1036 738/738/1036 +f 729/725/1037 716/714/1037 738/738/1037 +f 718/717/1038 728/734/1038 739/740/1038 +f 728/734/1039 722/726/1039 739/740/1039 +f 730/728/1040 719/730/1040 739/740/1040 +f 722/726/1041 730/728/1041 739/740/1041 +f 721/720/1014 710/719/1014 740/741/1014 +f 710/719/1016 727/723/1016 740/741/1016 +f 730/728/1042 721/720/1042 740/741/1042 +f 719/730/1043 730/728/1043 740/741/1043 +f 714/711/1012 725/722/1012 741/742/1012 +f 725/722/1044 733/731/1044 741/742/1044 +f 720/727/1045 722/726/1045 742/743/1045 +f 726/739/1046 720/727/1046 742/743/1046 +f 728/734/1047 708/724/1047 742/743/1047 +f 722/726/1048 728/734/1048 742/743/1048 +f 738/738/1049 726/739/1049 742/743/1049 +f 708/724/1050 738/738/1050 742/743/1050 +f 726/739/1051 711/735/1051 743/744/1051 +f 720/727/1052 726/739/1052 743/744/1052 +f 711/735/1053 730/728/1053 743/744/1053 +f 730/728/1054 720/727/1054 743/744/1054 +f 725/722/1012 718/717/1012 744/745/1012 +f 719/730/1055 725/722/1055 744/745/1055 +f 718/717/1056 739/740/1056 744/745/1056 +f 739/740/1057 719/730/1057 744/745/1057 +f 727/723/1058 714/711/1058 745/746/1058 +f 733/731/1059 719/730/1059 745/746/1059 +f 719/730/1060 740/741/1060 745/746/1060 +f 740/741/1061 727/723/1061 745/746/1061 +f 714/711/1062 741/742/1062 745/746/1062 +f 741/742/1063 733/731/1063 745/746/1063 +f 717/716/1013 724/708/1013 746/710/1013 +f 731/709/1064 717/716/1064 746/710/1064 +o Bowl_hull_23 +v -0.013374 -0.042685 -0.018306 +v 0.002577 -0.083206 0.050235 +v -0.006045 -0.083206 0.050235 +v -0.012943 -0.077597 0.048935 +v 0.002577 -0.040959 -0.017013 +v 0.002144 -0.041389 -0.023904 +v -0.013374 -0.040098 -0.015293 +v 0.002577 -0.078893 0.049371 +v -0.013374 -0.081475 0.048078 +v -0.006045 -0.040529 -0.024768 +v -0.002598 -0.082771 0.048507 +v -0.012943 -0.042685 -0.010544 +v 0.002577 -0.040098 -0.025211 +v -0.013374 -0.078462 0.050235 +v 0.002577 -0.083206 0.049371 +v -0.013374 -0.040098 -0.021755 +v -0.006476 -0.078893 0.042037 +v -0.002167 -0.041389 -0.023904 +v -0.012512 -0.056911 0.005400 +v -0.012943 -0.082336 0.049371 +v 0.002577 -0.040098 -0.018742 +v 0.002577 -0.079754 0.050235 +v -0.010356 -0.040959 -0.022611 +v 0.002577 -0.067254 0.021337 +v -0.006476 -0.043976 -0.018742 +v -0.013374 -0.082336 0.050235 +v -0.011218 -0.082336 0.048935 +v -0.013374 -0.065528 0.020480 +v 0.002577 -0.040529 -0.025211 +v -0.008200 -0.045702 -0.015293 +v -0.005613 -0.046567 -0.014421 +v -0.012512 -0.040529 -0.014429 +vt 0.085748 0.000000 +vt 0.131460 0.000000 +vt 0.142913 0.009985 +vt 1.000000 1.000000 +vt 0.108653 0.019971 +vt 0.988547 0.899951 +vt 0.091523 0.060010 +vt 0.971417 0.959863 +vt 0.982772 0.869897 +vt 0.194401 0.060010 +vt 0.000000 0.000000 +vt 1.000000 1.000000 +vt 1.000000 0.889966 +vt 0.988547 1.000000 +vt 0.977095 0.989917 +vt 0.045810 0.000000 +vt 0.005873 0.009985 +vt 0.891347 0.899951 +vt 0.017326 0.029956 +vt 1.000000 0.919921 +vt 0.034456 0.019971 +vt 0.405736 0.390015 +vt 0.616973 0.629956 +vt 0.017326 0.029956 +vt 1.000000 0.979834 +vt 0.988547 0.979834 +vt 0.982772 0.979834 +vt 0.085748 0.089966 +vt 0.605619 0.589917 +vt 0.000000 0.009985 +vt 0.131460 0.130005 +vt 0.143011 0.150073 +vn 0.0817 0.9222 0.3779 +vn 1.0000 0.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0577 0.8610 0.5054 +vn 0.1096 0.8630 0.4932 +vn 0.0000 0.0000 1.0000 +vn 0.0528 0.8231 0.5654 +vn -0.2004 0.8449 0.4959 +vn -0.3609 0.8048 0.4712 +vn 0.0000 -1.0000 0.0000 +vn -0.0300 -0.9535 -0.2998 +vn -0.0000 1.0000 0.0000 +vn -0.0625 0.9554 -0.2886 +vn -0.0401 -0.8674 -0.4960 +vn 0.0573 0.7072 0.7046 +vn -0.3702 -0.7431 -0.5574 +vn -0.3611 -0.4568 -0.8130 +vn -0.2266 -0.8388 -0.4951 +vn 0.0096 -0.8691 -0.4945 +vn -0.0017 -0.8682 -0.4962 +vn 0.0000 -0.8681 -0.4963 +vn -0.1176 -0.9913 -0.0586 +vn -0.5966 -0.7453 -0.2976 +vn -0.0649 -0.9294 -0.3633 +vn -0.0680 -0.8732 -0.4827 +vn -0.0797 -0.9456 -0.3154 +vn -0.1252 -0.8593 -0.4959 +vn -0.2553 -0.8331 -0.4907 +vn -0.2235 -0.8439 -0.4877 +vn -0.0513 0.0000 -0.9987 +vn 0.0000 -0.8351 -0.5500 +vn -0.0323 -0.7768 -0.6289 +vn 0.2161 -0.8467 -0.4861 +vn -0.1660 -0.8491 -0.5014 +vn -0.1797 -0.8488 -0.4972 +vn -0.1430 -0.8546 -0.4992 +vn -0.1330 -0.8581 -0.4959 +vn -0.1677 -0.8518 -0.4963 +vn -0.1480 -0.8558 -0.4957 +vn -0.0659 -0.8655 -0.4966 +vn -0.0800 -0.8623 -0.5000 +vn -0.0877 -0.8619 -0.4994 +vn -0.0942 -0.8633 -0.4957 +vn -0.1052 -0.8620 -0.4959 +vn -0.0450 0.8755 0.4810 +vn 0.1089 0.8639 0.4917 +vn 0.1014 0.8905 0.4436 +usemtl None +s off +f 767/747/1065 753/748/1065 778/749/1065 +f 748/750/1066 751/751/1066 754/752/1066 +f 753/748/1067 747/753/1067 755/754/1067 +f 750/755/1068 754/752/1068 758/756/1068 +f 754/752/1069 751/751/1069 758/756/1069 +f 751/751/1066 748/750/1066 759/757/1066 +f 749/758/1070 748/750/1070 760/759/1070 +f 754/752/1071 750/755/1071 760/759/1071 +f 753/748/1067 755/754/1067 760/759/1067 +f 750/755/1072 758/756/1072 760/759/1072 +f 758/756/1073 753/748/1073 760/759/1073 +f 748/750/1074 749/758/1074 761/760/1074 +f 749/758/1075 757/761/1075 761/760/1075 +f 759/757/1066 748/750/1066 761/760/1066 +f 747/753/1067 753/748/1067 762/762/1067 +f 753/748/1076 759/757/1076 762/762/1076 +f 759/757/1077 756/763/1077 762/762/1077 +f 757/761/1078 763/764/1078 764/765/1078 +f 751/751/1066 759/757/1066 767/747/1066 +f 759/757/1076 753/748/1076 767/747/1076 +f 748/750/1066 754/752/1066 768/766/1066 +f 760/759/1070 748/750/1070 768/766/1070 +f 754/752/1079 760/759/1079 768/766/1079 +f 747/753/1080 762/762/1080 769/767/1080 +f 762/762/1081 756/763/1081 769/767/1081 +f 765/768/1082 747/753/1082 769/767/1082 +f 761/760/1083 757/761/1083 770/769/1083 +f 759/757/1066 761/760/1066 770/769/1066 +f 757/761/1084 764/765/1084 770/769/1084 +f 764/765/1085 752/770/1085 770/769/1085 +f 749/758/1070 760/759/1070 772/771/1070 +f 760/759/1067 755/754/1067 772/771/1067 +f 766/772/1086 749/758/1086 772/771/1086 +f 755/754/1087 766/772/1087 772/771/1087 +f 757/761/1088 749/758/1088 773/773/1088 +f 763/764/1089 757/761/1089 773/773/1089 +f 749/758/1090 766/772/1090 773/773/1090 +f 766/772/1091 771/774/1091 773/773/1091 +f 755/754/1067 747/753/1067 774/775/1067 +f 747/753/1092 765/768/1092 774/775/1092 +f 766/772/1093 755/754/1093 774/775/1093 +f 756/763/1094 759/757/1094 775/776/1094 +f 752/770/1095 764/765/1095 775/776/1095 +f 764/765/1096 756/763/1096 775/776/1096 +f 770/769/1097 752/770/1097 775/776/1097 +f 759/757/1066 770/769/1066 775/776/1066 +f 769/767/1098 756/763/1098 776/777/1098 +f 765/768/1099 769/767/1099 776/777/1099 +f 756/763/1100 771/774/1100 776/777/1100 +f 771/774/1101 766/772/1101 776/777/1101 +f 774/775/1102 765/768/1102 776/777/1102 +f 766/772/1103 774/775/1103 776/777/1103 +f 764/765/1104 763/764/1104 777/778/1104 +f 756/763/1105 764/765/1105 777/778/1105 +f 771/774/1106 756/763/1106 777/778/1106 +f 763/764/1107 773/773/1107 777/778/1107 +f 773/773/1108 771/774/1108 777/778/1108 +f 753/748/1109 758/756/1109 778/749/1109 +f 758/756/1110 751/751/1110 778/749/1110 +f 751/751/1111 767/747/1111 778/749/1111 +o Bowl_hull_24 +v -0.038377 0.028020 -0.013569 +v -0.009063 0.039229 -0.018312 +v -0.009063 0.039229 -0.018744 +v -0.039671 0.006898 -0.018312 +v -0.039671 0.039229 0.008847 +v -0.023292 0.037936 -0.018744 +v -0.040103 0.039659 0.002376 +v -0.040103 0.018973 -0.018744 +v -0.030186 0.032763 -0.018744 +v -0.020703 0.039662 -0.018312 +v -0.040103 0.006898 -0.018744 +v -0.040103 0.039659 0.008847 +v -0.009063 0.039662 -0.018312 +v -0.032774 0.039659 -0.006671 +v -0.040103 0.034918 -0.003660 +v -0.034928 0.027590 -0.018744 +v -0.040103 0.025435 -0.013569 +v -0.037945 0.039659 -0.000641 +v -0.032774 0.030175 -0.018744 +v -0.037945 0.023280 -0.018744 +v -0.027597 0.036211 -0.017018 +v -0.025443 0.039229 -0.014863 +vt 0.052663 0.541601 +vt 0.105325 0.402897 +vt 0.013215 0.472298 +vt 0.013215 1.000000 +vt 0.013215 1.000000 +vt 1.000000 0.013900 +vt 0.013215 0.013900 +vt 0.631461 0.000000 +vt 0.210552 0.319499 +vt 0.000000 0.625000 +vt 1.000000 0.000000 +vt 0.000098 0.000000 +vt 0.000098 0.000000 +vt 0.000000 1.000000 +vt 0.144773 0.000000 +vt 0.368442 0.166699 +vt 0.355325 0.055599 +vt 0.434221 0.000000 +vt 0.000098 0.069499 +vt 0.000098 0.236100 +vt 0.289546 0.236100 +vt 0.500000 0.069499 +vn -0.4880 0.7105 -0.5071 +vn 0.7262 -0.6875 0.0000 +vn 0.5620 -0.5320 0.6333 +vn 0.0000 0.0000 -1.0000 +vn -0.0253 0.2784 -0.9601 +vn 0.5854 -0.5620 -0.5844 +vn -1.0000 -0.0000 0.0000 +vn -0.5395 -0.5416 0.6447 +vn -0.0002 1.0000 0.0000 +vn -0.6081 -0.5114 0.6072 +vn 1.0000 0.0000 0.0000 +vn 0.6637 0.0000 0.7480 +vn 0.0000 0.7064 -0.7078 +vn 0.5493 0.5515 0.6278 +vn 0.0000 1.0000 0.0001 +vn -0.6770 0.5435 -0.4963 +vn -0.7344 0.4903 -0.4692 +vn -0.0007 1.0000 -0.0005 +vn -0.5771 0.6497 -0.4948 +vn -0.0015 1.0000 -0.0013 +vn -0.6537 0.5952 -0.4674 +vn -0.6284 0.6008 -0.4942 +vn -0.6661 0.5551 -0.4982 +vn -0.6136 0.6137 -0.4968 +vn -0.7045 0.4931 -0.5104 +vn -0.7804 0.3908 -0.4881 +vn -0.7201 0.4807 -0.5004 +vn -0.4923 0.6560 -0.5721 +vn -0.5542 0.6660 -0.4992 +vn -0.5054 0.7105 -0.4896 +vn -0.4256 0.7611 -0.4894 +vn -0.3275 0.8818 -0.3394 +usemtl None +s off +f 784/779/1112 799/780/1112 800/781/1112 +f 781/782/1113 780/783/1113 782/784/1113 +f 782/784/1114 780/783/1114 783/785/1114 +f 784/779/1115 781/782/1115 786/786/1115 +f 784/779/1115 786/786/1115 787/787/1115 +f 781/782/1116 784/779/1116 788/788/1116 +f 781/782/1117 782/784/1117 789/789/1117 +f 786/786/1115 781/782/1115 789/789/1115 +f 785/790/1118 786/786/1118 789/789/1118 +f 782/784/1119 783/785/1119 790/791/1119 +f 788/788/1120 785/790/1120 790/791/1120 +f 789/789/1121 782/784/1121 790/791/1121 +f 785/790/1118 789/789/1118 790/791/1118 +f 780/783/1122 781/782/1122 791/792/1122 +f 783/785/1123 780/783/1123 791/792/1123 +f 781/782/1124 788/788/1124 791/792/1124 +f 790/791/1125 783/785/1125 791/792/1125 +f 788/788/1126 790/791/1126 791/792/1126 +f 786/786/1118 785/790/1118 793/793/1118 +f 787/787/1115 786/786/1115 794/794/1115 +f 779/795/1127 793/793/1127 794/794/1127 +f 793/793/1128 779/795/1128 795/796/1128 +f 786/786/1118 793/793/1118 795/796/1118 +f 785/790/1129 788/788/1129 796/797/1129 +f 792/798/1130 787/787/1130 796/797/1130 +f 788/788/1131 792/798/1131 796/797/1131 +f 793/793/1132 785/790/1132 796/797/1132 +f 793/793/1133 796/797/1133 797/799/1133 +f 787/787/1115 794/794/1115 797/799/1115 +f 794/794/1134 793/793/1134 797/799/1134 +f 796/797/1135 787/787/1135 797/799/1135 +f 779/795/1136 794/794/1136 798/800/1136 +f 794/794/1115 786/786/1115 798/800/1115 +f 786/786/1137 795/796/1137 798/800/1137 +f 795/796/1138 779/795/1138 798/800/1138 +f 784/779/1139 787/787/1139 799/780/1139 +f 787/787/1140 792/798/1140 799/780/1140 +f 799/780/1141 792/798/1141 800/781/1141 +f 788/788/1142 784/779/1142 800/781/1142 +f 792/798/1143 788/788/1143 800/781/1143 +o Bowl_hull_25 +v 0.012492 0.077167 0.040309 +v 0.013355 0.040094 -0.015285 +v 0.013355 0.040959 -0.013565 +v -0.001301 0.040094 -0.018742 +v -0.001301 0.078462 0.048507 +v -0.001301 0.041394 -0.023904 +v -0.001301 0.082771 0.048507 +v 0.013355 0.078458 0.050235 +v 0.013355 0.040529 -0.021755 +v 0.006026 0.040529 -0.024775 +v 0.013355 0.082336 0.049799 +v 0.004301 0.083201 0.049371 +v -0.001301 0.083201 0.050235 +v 0.012923 0.076302 0.046778 +v 0.012923 0.053032 -0.001062 +v -0.001301 0.040094 -0.025211 +v 0.003439 0.041820 -0.023047 +v 0.009042 0.080619 0.045486 +v 0.012923 0.040959 -0.013565 +v -0.001301 0.079754 0.050235 +v -0.001301 0.042250 -0.014850 +v 0.013355 0.040094 -0.021755 +v 0.002577 0.067254 0.021337 +v 0.008611 0.043115 -0.019598 +v 0.013355 0.076302 0.039017 +v 0.013355 0.082336 0.050235 +v 0.010336 0.040959 -0.022619 +v 0.006456 0.043976 -0.018742 +vt 0.868442 0.139990 +vt 0.851312 0.160059 +vt 0.085748 0.909936 +vt 0.085748 1.000000 +vt 0.977095 0.109936 +vt 0.017326 0.969848 +vt 0.977095 0.009985 +vt 0.154366 0.979931 +vt 0.131558 1.000000 +vt 1.000000 0.110034 +vt 0.045810 0.989917 +vt 0.994225 0.020069 +vt 1.000000 0.000000 +vt 0.988547 0.000000 +vt 0.954190 0.160059 +vt 0.000000 1.000000 +vt 0.005775 0.989917 +vt 0.028681 0.959961 +vt 0.937060 0.059912 +vt 0.154366 0.979931 +vt 1.000000 0.079980 +vt 0.137334 0.949975 +vt 0.045810 1.000000 +vt 0.616973 0.369946 +vt 0.320086 0.699853 +vt 0.074393 0.929907 +vt 1.000000 0.020069 +vt 0.034358 0.979931 +vn 0.1200 0.8602 -0.4957 +vn -1.0000 0.0000 0.0000 +vn 1.0000 -0.0000 0.0000 +vn -0.0372 0.9697 -0.2415 +vn 0.2421 -0.8365 0.4917 +vn -0.0632 -0.8431 0.5340 +vn 0.0000 -1.0000 0.0000 +vn -0.0001 0.7091 -0.7051 +vn 0.0292 0.8212 -0.5700 +vn 0.0657 0.8660 -0.4957 +vn 0.1393 0.8642 -0.4834 +vn 0.1060 0.8828 -0.4576 +vn 0.0000 -0.8934 0.4492 +vn -0.1006 -0.8988 0.4266 +vn 0.0000 -0.8629 0.5054 +vn -0.0695 -0.8608 0.5042 +vn -0.0706 -0.7991 0.5971 +vn 0.0000 0.0000 1.0000 +vn -0.1223 -0.8681 0.4810 +vn -0.1227 -0.8616 0.4925 +vn 0.3810 0.0000 -0.9246 +vn 0.0750 -0.9451 -0.3179 +vn -0.0019 0.8682 -0.4961 +vn 0.0096 0.8689 -0.4949 +vn 0.0118 0.8677 -0.4970 +vn 0.0447 0.8671 -0.4960 +vn 0.1748 0.8507 -0.4958 +vn 0.1420 0.8638 -0.4834 +vn 0.5418 0.7243 -0.4264 +vn 0.0951 0.9955 0.0000 +vn 0.0550 0.9325 0.3569 +vn 0.2952 0.6324 -0.7162 +vn 0.2600 0.8288 -0.4954 +vn 0.1692 0.8453 -0.5069 +vn 0.1886 0.8470 -0.4970 +vn 0.0966 0.8612 -0.4990 +vn 0.0910 0.8634 -0.4962 +vn 0.1172 0.8606 -0.4957 +vn 0.1433 0.8549 -0.4987 +vn 0.1446 0.8560 -0.4963 +usemtl None +s off +f 801/801/1144 825/802/1144 828/803/1144 +f 804/804/1145 805/805/1145 806/806/1145 +f 806/806/1145 805/805/1145 807/807/1145 +f 803/808/1146 802/809/1146 808/810/1146 +f 808/810/1146 802/809/1146 809/811/1146 +f 808/810/1146 809/811/1146 811/812/1146 +f 807/807/1145 805/805/1145 813/813/1145 +f 812/814/1147 807/807/1147 813/813/1147 +f 803/808/1148 808/810/1148 814/815/1148 +f 808/810/1149 805/805/1149 814/815/1149 +f 802/809/1150 804/804/1150 816/816/1150 +f 804/804/1145 806/806/1145 816/816/1145 +f 806/806/1151 810/817/1151 816/816/1151 +f 810/817/1152 806/806/1152 817/818/1152 +f 817/818/1153 812/814/1153 818/819/1153 +f 811/812/1154 801/801/1154 818/819/1154 +f 812/814/1155 811/812/1155 818/819/1155 +f 802/809/1156 803/808/1156 819/820/1156 +f 804/804/1157 802/809/1157 819/820/1157 +f 803/808/1158 814/815/1158 819/820/1158 +f 814/815/1159 805/805/1159 819/820/1159 +f 805/805/1160 808/810/1160 820/821/1160 +f 813/813/1145 805/805/1145 820/821/1145 +f 808/810/1161 813/813/1161 820/821/1161 +f 805/805/1145 804/804/1145 821/822/1145 +f 804/804/1162 819/820/1162 821/822/1162 +f 819/820/1163 805/805/1163 821/822/1163 +f 809/811/1146 802/809/1146 822/823/1146 +f 810/817/1164 809/811/1164 822/823/1164 +f 802/809/1150 816/816/1150 822/823/1150 +f 816/816/1165 810/817/1165 822/823/1165 +f 806/806/1166 807/807/1166 823/824/1166 +f 807/807/1167 812/814/1167 823/824/1167 +f 817/818/1168 806/806/1168 823/824/1168 +f 812/814/1169 817/818/1169 823/824/1169 +f 815/825/1170 824/826/1170 825/802/1170 +f 801/801/1171 811/812/1171 825/802/1171 +f 811/812/1146 809/811/1146 825/802/1146 +f 809/811/1172 815/825/1172 825/802/1172 +f 808/810/1146 811/812/1146 826/827/1146 +f 811/812/1173 812/814/1173 826/827/1173 +f 812/814/1174 813/813/1174 826/827/1174 +f 813/813/1161 808/810/1161 826/827/1161 +f 809/811/1175 810/817/1175 827/828/1175 +f 815/825/1176 809/811/1176 827/828/1176 +f 810/817/1177 824/826/1177 827/828/1177 +f 824/826/1178 815/825/1178 827/828/1178 +f 810/817/1179 817/818/1179 828/803/1179 +f 817/818/1180 818/819/1180 828/803/1180 +f 818/819/1181 801/801/1181 828/803/1181 +f 824/826/1182 810/817/1182 828/803/1182 +f 825/802/1183 824/826/1183 828/803/1183 +o Bowl_hull_26 +v 0.013787 0.064667 0.019187 +v 0.025857 0.040094 -0.005807 +v 0.025857 0.040532 -0.004939 +v 0.025857 0.078461 0.048077 +v 0.013356 0.078032 0.049800 +v 0.013356 0.040528 -0.021331 +v 0.025857 0.040962 -0.011846 +v 0.013356 0.040528 -0.013996 +v 0.025857 0.075011 0.049800 +v 0.013356 0.081912 0.048939 +v 0.016803 0.040958 -0.019173 +v 0.024994 0.040094 -0.005807 +v 0.025857 0.059067 0.016175 +v 0.022838 0.080181 0.049366 +v 0.014217 0.045268 -0.013569 +v 0.024563 0.075440 0.050235 +v 0.015943 0.081912 0.050235 +v 0.022838 0.040528 -0.015292 +v 0.014217 0.040094 -0.021331 +v 0.025857 0.079325 0.050235 +v 0.018961 0.080181 0.047643 +v 0.025857 0.069403 0.032988 +v 0.025857 0.040094 -0.012273 +v 0.013356 0.040094 -0.014858 +v 0.013356 0.078461 0.050235 +v 0.013787 0.054323 0.001520 +v 0.022838 0.074577 0.039881 +v 0.015080 0.081478 0.048504 +v 0.025425 0.050016 0.001527 +v 0.013356 0.076738 0.047643 +v 0.014217 0.041387 -0.020035 +v 0.013356 0.048719 -0.007965 +v 0.019821 0.040962 -0.017009 +vt 0.319401 0.762725 +vt 0.084377 0.989624 +vt 0.060395 0.979248 +vt 0.229052 0.989526 +vt 0.216915 1.000000 +vt 0.969851 0.082518 +vt 0.132537 0.979248 +vt 0.993931 0.092796 +vt 0.000000 0.989624 +vt 0.102486 0.989624 +vt 0.993931 0.165035 +vt 0.981891 0.000000 +vt 0.216915 1.000000 +vt 0.524080 0.546300 +vt 1.000000 0.154757 +vt 0.030149 0.979346 +vt 0.000000 1.000000 +vt 1.000000 0.061864 +vt 0.987862 0.041406 +vt 1.000000 0.000000 +vt 0.759006 0.299139 +vt 0.126566 1.000000 +vt 0.090446 1.000000 +vt 1.000000 0.082518 +vt 0.566171 0.412392 +vt 0.963782 0.041406 +vt 0.319303 0.659749 +vt 0.855325 0.175411 +vt 0.108457 0.876272 +vt 0.975822 0.010376 +vt 0.963782 0.123727 +vt 0.018109 0.969068 +vt 0.186766 0.793755 +vn 0.3939 0.7733 -0.4968 +vn 1.0000 0.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0000 -0.8929 0.4502 +vn -0.1017 -0.8418 0.5302 +vn -0.1063 -0.8414 0.5299 +vn -0.2115 -0.8274 0.5202 +vn 0.3349 0.6650 -0.6676 +vn 0.0000 -1.0000 0.0000 +vn 0.5220 0.3641 -0.7713 +vn 0.3470 0.8707 -0.3485 +vn 0.2880 -0.0959 0.9528 +vn 0.2518 0.9649 0.0752 +vn 0.0000 0.0000 1.0000 +vn 0.3226 0.8064 -0.4957 +vn 0.6928 0.3186 -0.6470 +vn 0.3897 -0.7729 -0.5007 +vn -0.3302 -0.8431 0.4245 +vn -0.4490 -0.8915 -0.0598 +vn -0.1882 -0.6981 0.6908 +vn -0.4246 0.3183 0.8476 +vn 0.1878 0.8476 -0.4963 +vn 0.2203 0.8401 -0.4957 +vn 0.2635 0.8305 -0.4907 +vn 0.2822 0.8225 -0.4938 +vn 0.2283 0.8377 -0.4962 +vn 0.2234 0.8392 -0.4958 +vn 0.0914 0.8621 -0.4984 +vn 0.1911 0.9254 -0.3274 +vn 0.1568 0.9367 -0.3131 +vn 0.1745 0.8508 -0.4956 +vn 0.1955 0.8766 -0.4398 +vn 0.6270 0.6543 -0.4228 +vn 0.4522 0.7452 -0.4900 +vn -1.0000 0.0001 0.0000 +vn -0.3211 -0.8123 0.4870 +vn -0.3622 -0.8037 0.4721 +vn 0.3327 0.6688 -0.6648 +vn 0.3007 0.8144 -0.4963 +vn 0.2781 0.8227 -0.4958 +vn 0.2656 0.8266 -0.4961 +vn -0.2139 0.8438 -0.4922 +vn -0.1005 0.8586 -0.5027 +vn 0.1069 0.8539 -0.5093 +vn -0.0646 0.8509 -0.5214 +vn 0.0866 0.8542 -0.5127 +vn 0.3552 0.7919 -0.4967 +vn 0.4478 0.6390 -0.6255 +vn 0.3721 0.7847 -0.4958 +usemtl None +s off +f 857/829/1184 846/830/1184 861/831/1184 +f 831/832/1185 830/833/1185 832/834/1185 +f 832/834/1185 830/833/1185 835/835/1185 +f 833/836/1186 834/837/1186 836/838/1186 +f 831/832/1185 832/834/1185 837/839/1185 +f 834/837/1186 833/836/1186 838/840/1186 +f 830/833/1187 831/832/1187 840/841/1187 +f 832/834/1185 835/835/1185 841/842/1185 +f 831/832/1188 837/839/1188 844/843/1188 +f 840/841/1189 831/832/1189 844/843/1189 +f 833/836/1190 840/841/1190 844/843/1190 +f 834/837/1191 839/844/1191 847/845/1191 +f 830/833/1192 840/841/1192 847/845/1192 +f 839/844/1193 846/830/1193 847/845/1193 +f 837/839/1185 832/834/1185 848/846/1185 +f 832/834/1194 842/847/1194 848/846/1194 +f 844/843/1195 837/839/1195 848/846/1195 +f 842/847/1196 845/848/1196 848/846/1196 +f 845/848/1197 844/843/1197 848/846/1197 +f 832/834/1185 841/842/1185 850/849/1185 +f 841/842/1198 839/844/1198 850/849/1198 +f 835/835/1185 830/833/1185 851/850/1185 +f 846/830/1199 835/835/1199 851/850/1199 +f 830/833/1192 847/845/1192 851/850/1192 +f 847/845/1200 846/830/1200 851/850/1200 +f 836/838/1186 834/837/1186 852/851/1186 +f 840/841/1201 836/838/1201 852/851/1201 +f 834/837/1202 847/845/1202 852/851/1202 +f 847/845/1192 840/841/1192 852/851/1192 +f 838/840/1186 833/836/1186 853/852/1186 +f 833/836/1203 844/843/1203 853/852/1203 +f 844/843/1197 845/848/1197 853/852/1197 +f 845/848/1204 838/840/1204 853/852/1204 +f 829/853/1205 849/854/1205 854/855/1205 +f 849/854/1206 842/847/1206 854/855/1206 +f 842/847/1207 832/834/1207 855/856/1207 +f 832/834/1208 850/849/1208 855/856/1208 +f 843/857/1209 854/855/1209 855/856/1209 +f 854/855/1210 842/847/1210 855/856/1210 +f 829/853/1211 838/840/1211 856/858/1211 +f 845/848/1212 842/847/1212 856/858/1212 +f 838/840/1213 845/848/1213 856/858/1213 +f 849/854/1214 829/853/1214 856/858/1214 +f 842/847/1215 849/854/1215 856/858/1215 +f 841/842/1216 835/835/1216 857/829/1216 +f 835/835/1217 846/830/1217 857/829/1217 +f 833/836/1218 836/838/1218 858/859/1218 +f 840/841/1219 833/836/1219 858/859/1219 +f 836/838/1220 840/841/1220 858/859/1220 +f 839/844/1221 834/837/1221 859/860/1221 +f 850/849/1222 839/844/1222 859/860/1222 +f 855/856/1223 850/849/1223 859/860/1223 +f 843/857/1224 855/856/1224 859/860/1224 +f 838/840/1225 829/853/1225 860/861/1225 +f 834/837/1186 838/840/1186 860/861/1186 +f 829/853/1226 854/855/1226 860/861/1226 +f 854/855/1227 843/857/1227 860/861/1227 +f 859/860/1228 834/837/1228 860/861/1228 +f 843/857/1229 859/860/1229 860/861/1229 +f 839/844/1230 841/842/1230 861/831/1230 +f 846/830/1231 839/844/1231 861/831/1231 +f 841/842/1232 857/829/1232 861/831/1232 +o Bowl_hull_27 +v 0.027151 0.046562 -0.002360 +v 0.043964 0.040094 0.014886 +v 0.043531 0.040094 0.014886 +v 0.025857 0.078894 0.050235 +v 0.043964 0.070269 0.048503 +v 0.025857 0.075013 0.050235 +v 0.025857 0.040094 -0.005374 +v 0.043964 0.040531 0.007989 +v 0.043531 0.066387 0.050235 +v 0.026289 0.040960 -0.011415 +v 0.030600 0.077599 0.049372 +v 0.043531 0.053463 0.023934 +v 0.025857 0.062077 0.021345 +v 0.038360 0.073288 0.048071 +v 0.034049 0.040527 -0.004080 +v 0.043964 0.070698 0.050235 +v 0.025857 0.040094 -0.011846 +v 0.026289 0.055620 0.011009 +v 0.040945 0.058203 0.027811 +v 0.026720 0.078461 0.048509 +v 0.025857 0.040531 -0.004511 +v 0.042668 0.040094 0.014029 +v 0.043964 0.066387 0.050235 +v 0.043964 0.040094 0.007989 +v 0.042238 0.069407 0.045489 +v 0.028014 0.041389 -0.009257 +v 0.043964 0.047857 0.017043 +v 0.034480 0.075442 0.048509 +v 0.040084 0.073288 0.050235 +v 0.026289 0.062077 0.021345 +v 0.043964 0.062077 0.036434 +v 0.033188 0.043117 -0.001497 +v 0.026289 0.049581 0.001523 +v 0.025857 0.078028 0.047646 +v 0.040084 0.041389 0.004112 +v 0.025857 0.049581 0.001523 +vt 0.368148 0.599843 +vt 0.215348 0.755482 +vt 0.215348 0.755482 +vt 1.000000 0.100039 +vt 1.000000 0.000000 +vt 0.104248 1.000000 +vt 0.430599 1.000000 +vt 0.430599 1.000000 +vt 0.972103 0.222298 +vt 0.319499 0.988743 +vt 1.000000 0.322337 +vt 0.534652 0.433438 +vt 1.000000 0.211237 +vt 0.000000 1.000000 +vt 0.006950 0.977682 +vt 0.125098 0.988841 +vt 0.986100 0.033379 +vt 0.972201 0.011159 +vt 0.118148 0.988743 +vt 0.416797 1.000000 +vt 1.000000 0.322337 +vt 0.319499 1.000000 +vt 0.152800 0.833301 +vt 0.965153 0.144479 +vt 0.923551 0.244518 +vt 0.638802 0.533281 +vt 0.041699 0.966621 +vt 0.465348 0.799922 +vt 0.576351 0.655442 +vt 0.972201 0.088978 +vt 1.000000 0.144479 +vt 0.534652 0.433438 +vt 0.777702 0.433438 +vt 0.166699 0.922083 +vt 0.958301 0.022318 +vt 0.257048 0.966621 +vn 0.0000 0.8436 -0.5370 +vn -1.0000 0.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn 1.0000 -0.0000 0.0000 +vn 0.0000 -0.8024 0.5968 +vn -0.3646 -0.7471 0.5557 +vn 0.0000 0.0000 1.0000 +vn 0.6874 0.0185 -0.7261 +vn 0.2409 0.9630 -0.1211 +vn -0.4622 -0.7912 0.4005 +vn -0.4798 -0.7322 0.4834 +vn -0.5206 -0.7224 0.4550 +vn 0.7727 0.0000 -0.6348 +vn 0.3468 -0.8829 -0.3166 +vn 0.4269 0.7563 -0.4957 +vn 0.4459 0.7600 -0.4728 +vn 0.4752 0.7271 -0.4956 +vn 0.4428 0.7430 -0.5018 +vn 0.5772 0.5784 -0.5765 +vn 0.4568 0.7382 -0.4965 +vn 0.5726 0.6532 -0.4954 +vn 0.3780 0.7818 -0.4958 +vn 0.3118 0.7912 0.5261 +vn 0.4627 0.8061 -0.3689 +vn 0.5438 0.8146 -0.2019 +vn 0.4182 0.8641 -0.2799 +vn 0.4267 0.8380 -0.3402 +vn 0.0000 0.8481 -0.5298 +vn 0.2921 0.8169 -0.4974 +vn 0.3354 0.8013 -0.4954 +vn 0.3495 0.7947 -0.4964 +vn 0.5260 0.6917 -0.4949 +vn 0.4935 0.7196 -0.4885 +vn 0.4822 0.7236 -0.4939 +vn 0.7176 0.5617 -0.4119 +vn 0.5444 0.6761 -0.4965 +vn 0.5256 0.6918 -0.4952 +vn 0.5102 0.7023 -0.4965 +vn 0.5307 0.6804 -0.5054 +vn 0.3850 0.7680 -0.5118 +vn 0.4229 0.7584 -0.4959 +vn 0.3826 0.7794 -0.4962 +vn -0.1566 0.9366 -0.3133 +vn 0.0000 0.8550 -0.5186 +vn 0.0878 0.8524 -0.5155 +vn 0.6553 0.5296 -0.5386 +vn 0.6250 0.6069 -0.4910 +vn 0.5822 0.6438 -0.4967 +vn -0.7260 0.5609 -0.3980 +vn -0.1151 0.8403 -0.5297 +vn 0.0000 0.8322 -0.5545 +usemtl None +s off +f 879/862/1233 894/863/1233 897/864/1233 +f 867/865/1234 865/866/1234 868/867/1234 +f 863/868/1235 864/869/1235 868/867/1235 +f 866/870/1236 863/868/1236 869/871/1236 +f 864/869/1237 863/868/1237 870/872/1237 +f 867/865/1238 864/869/1238 870/872/1238 +f 865/866/1239 867/865/1239 870/872/1239 +f 868/867/1234 865/866/1234 874/873/1234 +f 863/868/1236 866/870/1236 877/874/1236 +f 865/866/1239 870/872/1239 877/874/1239 +f 863/868/1235 868/867/1235 878/875/1235 +f 868/867/1234 874/873/1234 878/875/1234 +f 871/876/1240 876/877/1240 878/875/1240 +f 865/866/1241 872/878/1241 881/879/1241 +f 867/865/1234 868/867/1234 882/880/1234 +f 882/880/1242 868/867/1242 883/881/1242 +f 864/869/1243 867/865/1243 883/881/1243 +f 868/867/1235 864/869/1235 883/881/1235 +f 867/865/1244 882/880/1244 883/881/1244 +f 870/872/1237 863/868/1237 884/882/1237 +f 863/868/1236 877/874/1236 884/882/1236 +f 877/874/1239 870/872/1239 884/882/1239 +f 869/871/1236 863/868/1236 885/883/1236 +f 876/877/1245 869/871/1245 885/883/1245 +f 863/868/1235 878/875/1235 885/883/1235 +f 878/875/1246 876/877/1246 885/883/1246 +f 862/884/1247 875/885/1247 886/886/1247 +f 875/885/1248 866/870/1248 886/886/1248 +f 886/886/1249 880/887/1249 887/888/1249 +f 871/876/1250 862/884/1250 887/888/1250 +f 876/877/1251 871/876/1251 887/888/1251 +f 862/884/1252 886/886/1252 887/888/1252 +f 866/870/1236 869/871/1236 888/889/1236 +f 876/877/1253 873/890/1253 888/889/1253 +f 875/885/1254 879/862/1254 889/891/1254 +f 872/878/1255 865/866/1255 890/892/1255 +f 866/870/1256 875/885/1256 890/892/1256 +f 877/874/1257 866/870/1257 890/892/1257 +f 865/866/1239 877/874/1239 890/892/1239 +f 889/891/1258 872/878/1258 890/892/1258 +f 875/885/1259 889/891/1259 890/892/1259 +f 879/862/1260 874/873/1260 891/893/1260 +f 881/879/1261 872/878/1261 891/893/1261 +f 872/878/1262 889/891/1262 891/893/1262 +f 889/891/1263 879/862/1263 891/893/1263 +f 873/890/1264 880/887/1264 892/894/1264 +f 886/886/1265 866/870/1265 892/894/1265 +f 880/887/1266 886/886/1266 892/894/1266 +f 866/870/1236 888/889/1236 892/894/1236 +f 888/889/1267 873/890/1267 892/894/1267 +f 873/890/1268 876/877/1268 893/895/1268 +f 880/887/1269 873/890/1269 893/895/1269 +f 887/888/1270 880/887/1270 893/895/1270 +f 876/877/1271 887/888/1271 893/895/1271 +f 862/884/1272 871/876/1272 894/863/1272 +f 875/885/1273 862/884/1273 894/863/1273 +f 879/862/1274 875/885/1274 894/863/1274 +f 874/873/1234 865/866/1234 895/896/1234 +f 865/866/1275 881/879/1275 895/896/1275 +f 891/893/1276 874/873/1276 895/896/1276 +f 881/879/1277 891/893/1277 895/896/1277 +f 869/871/1278 876/877/1278 896/897/1278 +f 888/889/1279 869/871/1279 896/897/1279 +f 876/877/1280 888/889/1280 896/897/1280 +f 878/875/1234 874/873/1234 897/864/1234 +f 871/876/1281 878/875/1281 897/864/1281 +f 874/873/1282 879/862/1282 897/864/1282 +f 894/863/1283 871/876/1283 897/864/1283 +o Bowl_hull_28 +v 0.050000 0.056043 0.034706 +v 0.072849 0.040094 0.050235 +v 0.072849 0.040528 0.050235 +v 0.044396 0.040094 0.008851 +v 0.043964 0.065097 0.048934 +v 0.044396 0.040094 0.016180 +v 0.068537 0.040094 0.050235 +v 0.044396 0.070703 0.049801 +v 0.063363 0.054323 0.049372 +v 0.059051 0.040528 0.028682 +v 0.044396 0.042251 0.010573 +v 0.053450 0.064234 0.050235 +v 0.043964 0.055608 0.027823 +v 0.069829 0.045700 0.049372 +v 0.043964 0.066392 0.050235 +v 0.051725 0.065529 0.049372 +v 0.043964 0.040525 0.016180 +v 0.058618 0.059060 0.048938 +v 0.053020 0.040528 0.020057 +v 0.044396 0.055608 0.027823 +v 0.072416 0.040957 0.048938 +v 0.043964 0.070703 0.050235 +v 0.066812 0.050011 0.049372 +v 0.043964 0.040525 0.008851 +v 0.044396 0.065960 0.042468 +v 0.064225 0.053460 0.050235 +v 0.045691 0.040525 0.010148 +v 0.065517 0.040094 0.038162 +v 0.044396 0.049151 0.019198 +v 0.053020 0.052169 0.033422 +v 0.047413 0.068114 0.048509 +v 0.054312 0.060786 0.045920 +vt 0.593735 0.605521 +vt 0.250024 0.704092 +vt 0.895742 0.324002 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 0.177092 1.000000 +vt 1.000000 0.985807 +vt 1.000000 1.000000 +vt 1.000000 0.211335 +vt 0.968576 0.183144 +vt 1.000000 0.140857 +vt 0.458443 0.493148 +vt 0.989525 0.000000 +vt 0.979148 0.169049 +vt 0.177092 0.985905 +vt 0.979148 0.535141 +vt 0.968673 0.380384 +vt 0.624767 0.478955 +vt 0.458443 0.493148 +vt 0.968673 0.971809 +vt 0.979148 0.816856 +vt 0.479197 0.985807 +vt 1.000000 0.000000 +vt 0.979148 0.675998 +vt 0.270778 0.985807 +vt 0.000000 0.985905 +vt 0.812335 0.154953 +vt 1.000000 0.563332 +vt 0.031326 0.985905 +vt 0.041605 0.929522 +vt 0.708272 1.000000 +vt 0.958297 0.084573 +vn 0.5978 0.6298 -0.4960 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn -0.6043 -0.5647 0.5621 +vn -1.0000 -0.0000 0.0000 +vn 0.5781 0.8134 0.0646 +vn -0.7062 -0.7080 -0.0000 +vn -0.6457 -0.6108 0.4582 +vn -0.6315 -0.6331 0.4476 +vn 0.7068 0.7074 -0.0056 +vn 0.6565 0.7156 -0.2388 +vn 0.5577 0.6655 -0.4961 +vn 0.9486 0.0000 -0.3165 +vn 0.8656 0.4839 -0.1289 +vn 0.7411 0.4498 -0.4985 +vn 0.4911 0.7202 0.4901 +vn 0.7118 0.4980 -0.4953 +vn 0.7091 0.5014 -0.4958 +vn 0.6785 0.5429 -0.4949 +vn 0.0000 0.8166 -0.5772 +vn -0.4780 0.7375 -0.4770 +vn -0.6831 0.6057 -0.4080 +vn 0.7071 0.7071 0.0005 +vn 0.7688 0.5127 0.3822 +vn 0.7716 0.6173 -0.1538 +vn 0.8084 0.5656 0.1630 +vn 0.6812 -0.5313 -0.5037 +vn 0.6706 0.5515 -0.4961 +vn 0.5143 0.5156 -0.6853 +vn 0.5038 0.5435 -0.6714 +vn 0.5665 -0.7158 -0.4082 +vn 0.7836 -0.2927 -0.5479 +vn 0.8064 -0.3315 -0.4897 +vn 0.8018 0.2669 -0.5347 +vn 0.5589 0.6638 -0.4969 +vn 0.0000 0.8005 -0.5993 +vn -0.5323 0.6610 -0.5288 +vn -0.5865 0.6340 -0.5040 +vn 0.6369 0.5927 -0.4930 +vn 0.6415 0.5859 -0.4951 +vn 0.6310 0.5959 -0.4968 +vn 0.6037 0.6225 -0.4980 +vn 0.5335 0.7823 -0.3216 +vn 0.5173 0.6969 -0.4968 +vn 0.4385 0.7546 -0.4881 +vn 0.4969 0.7087 -0.5009 +vn 0.5580 0.6653 -0.4960 +vn 0.5902 0.6601 -0.4647 +vn 0.5894 0.6375 -0.4963 +vn 0.5993 0.6288 -0.4955 +usemtl None +s off +f 927/898/1284 926/899/1284 929/900/1284 +f 901/901/1285 899/902/1285 903/903/1285 +f 899/902/1286 900/904/1286 904/905/1286 +f 903/903/1285 899/902/1285 904/905/1285 +f 904/905/1286 900/904/1286 909/906/1286 +f 902/907/1287 904/905/1287 912/908/1287 +f 904/905/1286 909/906/1286 912/908/1286 +f 910/909/1288 902/907/1288 912/908/1288 +f 905/910/1289 909/906/1289 913/911/1289 +f 901/901/1290 903/903/1290 914/912/1290 +f 904/905/1291 902/907/1291 914/912/1291 +f 903/903/1292 904/905/1292 914/912/1292 +f 902/907/1288 910/909/1288 914/912/1288 +f 909/906/1293 906/913/1293 915/914/1293 +f 913/911/1294 909/906/1294 915/914/1294 +f 913/911/1295 898/915/1295 917/916/1295 +f 900/904/1296 899/902/1296 918/917/1296 +f 911/918/1297 900/904/1297 918/917/1297 +f 907/919/1298 911/918/1298 918/917/1298 +f 909/906/1299 905/910/1299 919/920/1299 +f 912/908/1286 909/906/1286 919/920/1286 +f 910/909/1288 912/908/1288 919/920/1288 +f 911/918/1300 907/919/1300 920/921/1300 +f 907/919/1301 916/922/1301 920/921/1301 +f 916/922/1302 906/913/1302 920/921/1302 +f 901/901/1290 914/912/1290 921/923/1290 +f 914/912/1288 910/909/1288 921/923/1288 +f 917/916/1303 910/909/1303 922/924/1303 +f 919/920/1304 905/910/1304 922/924/1304 +f 910/909/1305 919/920/1305 922/924/1305 +f 909/906/1286 900/904/1286 923/925/1286 +f 906/913/1306 909/906/1306 923/925/1306 +f 900/904/1307 911/918/1307 923/925/1307 +f 920/921/1308 906/913/1308 923/925/1308 +f 911/918/1309 920/921/1309 923/925/1309 +f 916/922/1310 901/901/1310 924/926/1310 +f 906/913/1311 916/922/1311 924/926/1311 +f 901/901/1312 921/923/1312 924/926/1312 +f 921/923/1313 908/927/1313 924/926/1313 +f 899/902/1285 901/901/1285 925/928/1285 +f 901/901/1314 916/922/1314 925/928/1314 +f 916/922/1315 907/919/1315 925/928/1315 +f 918/917/1316 899/902/1316 925/928/1316 +f 907/919/1317 918/917/1317 925/928/1317 +f 917/916/1318 898/915/1318 926/899/1318 +f 910/909/1319 917/916/1319 926/899/1319 +f 908/927/1320 921/923/1320 926/899/1320 +f 921/923/1321 910/909/1321 926/899/1321 +f 915/914/1322 906/913/1322 927/898/1322 +f 906/913/1323 924/926/1323 927/898/1323 +f 924/926/1324 908/927/1324 927/898/1324 +f 908/927/1325 926/899/1325 927/898/1325 +f 905/910/1326 913/911/1326 928/929/1326 +f 913/911/1327 917/916/1327 928/929/1327 +f 922/924/1328 905/910/1328 928/929/1328 +f 917/916/1329 922/924/1329 928/929/1329 +f 898/915/1330 913/911/1330 929/900/1330 +f 913/911/1331 915/914/1331 929/900/1331 +f 926/899/1332 898/915/1332 929/900/1332 +f 915/914/1333 927/898/1333 929/900/1333 +o Bowl_hull_29 +v 0.020251 -0.046997 -0.007096 +v 0.006026 -0.083197 0.050235 +v 0.002577 -0.083197 0.050235 +v 0.021115 -0.075875 0.048935 +v 0.002577 -0.039667 -0.019173 +v 0.003440 -0.040532 -0.025204 +v 0.021115 -0.039667 -0.010542 +v 0.002577 -0.078888 0.049366 +v 0.021115 -0.080614 0.049366 +v 0.013354 -0.040097 -0.022612 +v 0.014216 -0.078893 0.043758 +v 0.021115 -0.039667 -0.017011 +v 0.020683 -0.040097 -0.009681 +v 0.004302 -0.083197 0.049366 +v 0.002577 -0.039667 -0.025642 +v 0.009476 -0.042684 -0.020027 +v 0.020251 -0.076732 0.050235 +v 0.009476 -0.082771 0.049366 +v 0.021115 -0.059067 0.013158 +v 0.005594 -0.040102 -0.025642 +v 0.002577 -0.083197 0.049366 +v 0.021115 -0.040528 -0.016588 +v 0.021115 -0.080614 0.050235 +v 0.003440 -0.079319 0.050235 +v 0.002577 -0.041824 -0.023050 +v 0.018095 -0.074580 0.037720 +v 0.020683 -0.067249 0.026512 +v 0.004302 -0.045706 -0.016157 +v 0.010770 -0.040097 -0.023904 +v 0.009044 -0.078888 0.042473 +v 0.010770 -0.039667 -0.023904 +v 0.016371 -0.081475 0.048935 +v 0.016803 -0.040958 -0.019165 +v 0.008182 -0.050445 -0.007104 +vt 0.897709 0.901018 +vt 0.000000 0.009986 +vt 0.244323 0.247601 +vt 0.085258 0.000000 +vt 1.000000 1.000000 +vt 0.988547 0.901018 +vt 0.199002 0.000000 +vt 0.982870 0.831799 +vt 0.988547 0.940670 +vt 0.113743 0.000000 +vt 0.210356 0.009889 +vt 1.000000 1.000000 +vt 0.988547 1.000000 +vt 0.000000 0.000000 +vt 1.000000 0.851478 +vt 0.988547 0.990210 +vt 0.511355 0.445663 +vt 0.005775 0.019875 +vt 0.988547 1.000000 +vt 0.039937 0.009889 +vt 0.119323 0.019777 +vt 0.244420 0.168396 +vt 1.000000 0.940670 +vt 1.000000 0.910907 +vt 0.034162 0.049540 +vt 0.687353 0.633640 +vt 0.835063 0.802036 +vt 0.125000 0.138731 +vt 0.074002 0.069317 +vt 0.022905 0.009889 +vt 0.914644 0.901116 +vt 0.022905 0.000000 +vt 0.982870 0.960446 +vt 0.085356 0.029665 +vn 0.1112 -0.8612 -0.4960 +vn -1.0000 -0.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.1829 0.8398 0.5112 +vn -0.1722 0.9130 0.3698 +vn -0.2331 0.8440 0.4830 +vn 0.0000 -1.0000 -0.0000 +vn 0.0000 -0.0000 1.0000 +vn -0.0617 0.8517 0.5203 +vn -0.1287 0.8465 0.5166 +vn 0.0810 -0.9837 -0.1608 +vn -0.0732 -0.5078 -0.8584 +vn 0.5578 -0.3663 -0.7448 +vn 0.4779 -0.7455 -0.4646 +vn 0.7653 0.1703 0.6208 +vn 0.1659 -0.9690 0.1832 +vn 0.1822 -0.9833 0.0000 +vn -0.6639 0.1479 0.7331 +vn -0.1281 0.8322 0.5395 +vn -0.4070 -0.7022 -0.5842 +vn 0.0000 -0.8683 -0.4961 +vn 0.2725 -0.8243 -0.4963 +vn 0.4242 -0.7782 -0.4631 +vn 0.2322 -0.8377 -0.4943 +vn 0.0707 -0.8630 -0.5003 +vn 0.0481 -0.8651 -0.4993 +vn 0.0308 -0.8675 -0.4964 +vn 0.1709 -0.8450 -0.5068 +vn 0.2009 -0.8445 -0.4964 +vn 0.2264 -0.8383 -0.4960 +vn 0.2484 -0.8316 -0.4967 +vn 0.1218 -0.8615 -0.4929 +vn 0.0714 -0.8671 -0.4929 +vn 0.0667 -0.8660 -0.4955 +vn 0.0990 -0.8626 -0.4962 +vn 0.4267 0.6386 -0.6404 +vn 0.1183 0.8215 -0.5578 +vn 0.4473 0.0000 -0.8944 +vn 0.3184 0.0000 -0.9480 +vn 0.1711 -0.8513 -0.4960 +vn 0.1820 -0.9824 -0.0410 +vn 0.1320 -0.8640 -0.4860 +vn 0.1985 -0.8482 -0.4910 +vn 0.1755 -0.8504 -0.4959 +vn 0.3178 -0.8085 -0.4953 +vn 0.2924 -0.8171 -0.4968 +vn 0.3759 -0.7813 -0.4983 +vn 0.4237 -0.6831 -0.5948 +vn 0.1607 -0.8532 -0.4963 +vn 0.1517 -0.8540 -0.4977 +vn 0.1224 -0.8599 -0.4955 +usemtl None +s off +f 959/930/1334 949/931/1334 963/932/1334 +f 934/933/1335 932/934/1335 937/935/1335 +f 936/936/1336 933/937/1336 938/938/1336 +f 934/933/1337 936/936/1337 941/939/1337 +f 936/936/1336 938/938/1336 941/939/1336 +f 933/937/1338 936/936/1338 942/940/1338 +f 936/936/1339 934/933/1339 942/940/1339 +f 934/933/1340 937/935/1340 942/940/1340 +f 931/941/1341 932/934/1341 943/942/1341 +f 932/934/1335 934/933/1335 944/943/1335 +f 934/933/1337 941/939/1337 944/943/1337 +f 932/934/1342 931/941/1342 946/944/1342 +f 933/937/1343 942/940/1343 946/944/1343 +f 942/940/1344 937/935/1344 946/944/1344 +f 931/941/1345 943/942/1345 947/945/1345 +f 941/939/1336 938/938/1336 948/946/1336 +f 935/947/1346 944/943/1346 949/931/1346 +f 943/942/1341 932/934/1341 950/948/1341 +f 932/934/1335 944/943/1335 950/948/1335 +f 939/949/1347 941/939/1347 951/950/1347 +f 948/946/1348 930/951/1348 951/950/1348 +f 941/939/1336 948/946/1336 951/950/1336 +f 938/938/1336 933/937/1336 952/952/1336 +f 946/944/1342 931/941/1342 952/952/1342 +f 933/937/1349 946/944/1349 952/952/1349 +f 931/941/1350 947/945/1350 952/952/1350 +f 947/945/1351 938/938/1351 952/952/1351 +f 937/935/1352 932/934/1352 953/953/1352 +f 932/934/1342 946/944/1342 953/953/1342 +f 946/944/1353 937/935/1353 953/953/1353 +f 944/943/1354 935/947/1354 954/954/1354 +f 943/942/1355 950/948/1355 954/954/1355 +f 950/948/1335 944/943/1335 954/954/1335 +f 939/949/1356 948/946/1356 956/955/1356 +f 948/946/1357 938/938/1357 956/955/1357 +f 938/938/1358 955/956/1358 956/955/1358 +f 935/947/1359 949/931/1359 957/957/1359 +f 954/954/1360 935/947/1360 957/957/1360 +f 943/942/1361 954/954/1361 957/957/1361 +f 945/958/1362 949/931/1362 958/959/1362 +f 955/956/1363 945/958/1363 958/959/1363 +f 956/955/1364 955/956/1364 958/959/1364 +f 939/949/1365 956/955/1365 958/959/1365 +f 940/960/1366 947/945/1366 959/930/1366 +f 947/945/1367 943/942/1367 959/930/1367 +f 943/942/1368 957/957/1368 959/930/1368 +f 957/957/1369 949/931/1369 959/930/1369 +f 941/939/1370 939/949/1370 960/961/1370 +f 944/943/1337 941/939/1337 960/961/1337 +f 949/931/1371 944/943/1371 960/961/1371 +f 939/949/1372 958/959/1372 960/961/1372 +f 958/959/1373 949/931/1373 960/961/1373 +f 940/960/1374 945/958/1374 961/962/1374 +f 938/938/1375 947/945/1375 961/962/1375 +f 947/945/1376 940/960/1376 961/962/1376 +f 955/956/1377 938/938/1377 961/962/1377 +f 945/958/1378 955/956/1378 961/962/1378 +f 930/951/1379 948/946/1379 962/963/1379 +f 948/946/1380 939/949/1380 962/963/1380 +f 951/950/1381 930/951/1381 962/963/1381 +f 939/949/1382 951/950/1382 962/963/1382 +f 945/958/1383 940/960/1383 963/932/1383 +f 949/931/1384 945/958/1384 963/932/1384 +f 940/960/1385 959/930/1385 963/932/1385 +o Bowl_hull_30 +v 0.036202 0.028019 -0.016586 +v 0.006457 0.040094 -0.018744 +v 0.006457 0.040094 -0.018309 +v 0.039221 0.009053 -0.018312 +v 0.039221 0.039662 0.008847 +v 0.020257 0.039659 -0.018744 +v 0.039653 0.040094 0.001944 +v 0.039653 0.020265 -0.018744 +v 0.030164 0.032762 -0.018744 +v 0.006457 0.039659 -0.018309 +v 0.039653 0.009053 -0.018744 +v 0.024991 0.040094 -0.013999 +v 0.039653 0.040094 0.008847 +v 0.039653 0.032762 -0.006671 +v 0.031458 0.040094 -0.007533 +v 0.033183 0.029745 -0.018744 +v 0.025852 0.036211 -0.018744 +v 0.018964 0.040094 -0.018744 +v 0.039221 0.025002 -0.015295 +v 0.006457 0.039659 -0.018744 +v 0.036202 0.025865 -0.018744 +vt 0.986981 0.486198 +vt 1.000000 0.638802 +vt 0.896045 0.458399 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 0.415720 0.013998 +vt 0.714174 0.236198 +vt 0.000000 0.013998 +vt 0.986981 1.000000 +vt 0.986981 0.013900 +vt 1.000000 1.000000 +vt 0.558340 0.000000 +vt 1.000000 0.000000 +vt 1.000000 0.236198 +vt 0.753132 0.000000 +vt 0.805110 0.333399 +vt 0.896045 0.388998 +vt 0.584280 0.125098 +vt 0.376762 0.000000 +vt 0.000000 0.013998 +vn 0.7255 0.4471 -0.5232 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.5269 -0.5641 0.6357 +vn -0.6381 0.0000 0.7699 +vn 1.0000 0.0000 0.0000 +vn 0.5523 -0.5533 0.6235 +vn -0.5347 0.5356 0.6536 +vn 0.5986 -0.5322 0.5987 +vn 0.5716 0.6550 -0.4943 +vn 0.6129 0.6132 -0.4984 +vn 0.6703 0.5511 -0.4969 +vn 0.6495 0.5791 -0.4928 +vn 0.4496 0.7295 -0.5154 +vn 0.5396 0.6747 -0.5035 +vn 0.4948 0.7144 -0.4948 +vn 0.2952 0.8788 -0.3750 +vn 0.7124 0.5036 -0.4888 +vn 0.8824 0.3269 -0.3384 +vn -0.6826 -0.7308 0.0000 +vn -0.5611 -0.6086 -0.5611 +vn 0.6729 0.5235 -0.5226 +vn 0.7104 0.4981 -0.4972 +usemtl None +s off +f 982/964/1386 971/965/1386 984/966/1386 +f 965/967/1387 966/968/1387 970/969/1387 +f 965/967/1388 969/970/1388 971/965/1388 +f 971/965/1388 969/970/1388 972/971/1388 +f 966/968/1389 965/967/1389 973/972/1389 +f 967/973/1390 968/974/1390 973/972/1390 +f 968/974/1391 966/968/1391 973/972/1391 +f 965/967/1388 971/965/1388 974/975/1388 +f 971/965/1392 970/969/1392 974/975/1392 +f 965/967/1387 970/969/1387 975/976/1387 +f 968/974/1393 967/973/1393 976/977/1393 +f 966/968/1394 968/974/1394 976/977/1394 +f 970/969/1387 966/968/1387 976/977/1387 +f 967/973/1395 974/975/1395 976/977/1395 +f 974/975/1392 970/969/1392 976/977/1392 +f 970/969/1392 971/965/1392 977/978/1392 +f 970/969/1396 972/971/1396 978/979/1396 +f 975/976/1387 970/969/1387 978/979/1387 +f 972/971/1397 970/969/1397 979/980/1397 +f 971/965/1388 972/971/1388 979/980/1388 +f 977/978/1398 964/981/1398 979/980/1398 +f 970/969/1399 977/978/1399 979/980/1399 +f 972/971/1388 969/970/1388 980/982/1388 +f 969/970/1400 975/976/1400 980/982/1400 +f 978/979/1401 972/971/1401 980/982/1401 +f 975/976/1402 978/979/1402 980/982/1402 +f 969/970/1388 965/967/1388 981/983/1388 +f 965/967/1387 975/976/1387 981/983/1387 +f 975/976/1403 969/970/1403 981/983/1403 +f 964/981/1404 977/978/1404 982/964/1404 +f 977/978/1405 971/965/1405 982/964/1405 +f 973/972/1389 965/967/1389 983/984/1389 +f 967/973/1406 973/972/1406 983/984/1406 +f 974/975/1407 967/973/1407 983/984/1407 +f 965/967/1388 974/975/1388 983/984/1388 +f 979/980/1408 964/981/1408 984/966/1408 +f 971/965/1388 979/980/1388 984/966/1388 +f 964/981/1409 982/964/1409 984/966/1409 +o Bowl_hull_31 +v 0.048278 0.040094 0.013159 +v 0.039653 0.019401 -0.018744 +v 0.039653 0.018969 -0.018744 +v 0.081036 0.018969 0.049370 +v 0.040086 0.039662 0.010141 +v 0.073278 0.040094 0.049796 +v 0.077159 0.018969 0.050228 +v 0.040086 0.018969 -0.010979 +v 0.068104 0.040094 0.049364 +v 0.077159 0.027594 0.046784 +v 0.040086 0.040094 0.002815 +v 0.040086 0.019401 -0.018744 +v 0.041379 0.028886 -0.008393 +v 0.076725 0.032761 0.049370 +v 0.068104 0.040094 0.041606 +v 0.055606 0.019831 0.006698 +v 0.039653 0.040094 0.009284 +v 0.068967 0.039232 0.050235 +v 0.080177 0.023280 0.050228 +v 0.073711 0.037507 0.048074 +v 0.076296 0.018969 0.048938 +v 0.058191 0.039662 0.026515 +v 0.040086 0.025005 -0.013997 +v 0.080177 0.021990 0.048938 +v 0.039653 0.037507 -0.000635 +v 0.040086 0.031469 -0.007529 +v 0.039653 0.018969 -0.011843 +v 0.068104 0.039662 0.049364 +v 0.073278 0.040094 0.050228 +v 0.069397 0.018969 0.029540 +v 0.040516 0.022850 -0.015294 +v 0.052588 0.021556 0.002815 +v 0.040086 0.037507 -0.000635 +v 0.067242 0.019831 0.026089 +v 0.053018 0.040094 0.019621 +v 0.051296 0.018969 -0.000635 +v 0.081036 0.018969 0.050228 +v 0.068967 0.034918 0.038587 +vt 0.050020 0.020852 +vt 0.874902 0.687518 +vt 0.831147 0.708370 +vt 0.000000 0.000000 +vt 0.987471 1.000000 +vt 0.999902 0.906314 +vt 0.112569 0.010475 +vt 0.993637 0.812531 +vt 0.462510 0.208419 +vt 0.987373 0.687518 +vt 0.312549 0.010475 +vt 0.000000 0.000000 +vt 0.000000 0.010475 +vt 0.406323 0.000000 +vt 0.418755 0.010475 +vt 0.987471 0.895840 +vt 0.968677 0.823005 +vt 0.981206 0.885463 +vt 0.656128 0.447969 +vt 0.068814 0.010475 +vt 0.150059 0.041703 +vt 0.949980 0.906314 +vt 0.981206 0.979246 +vt 0.999902 0.979246 +vt 0.262529 0.000000 +vt 0.162588 0.010475 +vt 0.100039 0.000000 +vt 0.987373 0.687518 +vt 1.000000 0.708370 +vt 0.999902 0.812531 +vt 0.699980 0.718747 +vt 0.312549 0.312580 +vt 0.368833 0.385511 +vt 0.262529 0.010475 +vt 0.649961 0.666667 +vt 0.556186 0.322956 +vt 0.262529 0.281351 +vt 0.999902 1.000000 +vn 0.7623 0.4162 -0.4957 +vn -0.0000 -1.0000 0.0000 +vn -0.0000 1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.7742 0.3139 0.5496 +vn 0.8173 0.4079 -0.4071 +vn 0.7571 0.4452 -0.4782 +vn -0.7685 -0.3807 0.5142 +vn -0.7569 -0.4668 0.4574 +vn 0.7346 0.4631 -0.4958 +vn 0.0000 0.6463 -0.7630 +vn 0.7265 0.4750 -0.4965 +vn 0.8511 0.2903 -0.4374 +vn 0.9433 0.2346 -0.2347 +vn 0.9042 0.3019 -0.3020 +vn -0.9665 0.2483 -0.0648 +vn -0.8137 0.4111 -0.4110 +vn -0.8115 0.4133 -0.4131 +vn 0.6853 0.5152 -0.5148 +vn -0.8128 -0.4161 0.4077 +vn -0.9032 -0.3036 0.3036 +vn -0.7723 -0.3149 0.5517 +vn -0.8137 0.0000 0.5813 +vn -0.7476 -0.3024 0.5913 +vn -0.7104 0.0000 0.7038 +vn 0.9050 0.4255 0.0000 +vn -0.1267 0.6393 0.7584 +vn 0.8362 0.3431 0.4279 +vn 0.0014 0.0006 1.0000 +vn 0.7442 0.4470 -0.4963 +vn 0.6847 0.4711 -0.5561 +vn 0.8091 0.3159 -0.4955 +vn 0.7957 0.3473 -0.4962 +vn 0.8127 0.3055 -0.4961 +vn 0.8134 0.2952 -0.5012 +vn 0.6038 0.6378 -0.4782 +vn 0.0000 0.8001 -0.5999 +vn 0.0000 0.7523 -0.6589 +vn 0.6572 0.5670 -0.4966 +vn 0.8266 0.2662 -0.4959 +vn 0.8303 0.2572 -0.4944 +vn 0.8505 0.1706 -0.4976 +vn 0.8552 0.1291 -0.5019 +vn 0.7034 0.5092 -0.4959 +vn 0.6300 0.6452 -0.4323 +vn 0.6752 0.5467 -0.4953 +vn 0.6984 0.5156 -0.4964 +vn 0.6429 -0.6448 -0.4134 +vn 0.8376 0.1846 -0.5141 +vn 0.8541 0.0883 -0.5125 +vn 0.8545 0.0848 -0.5126 +vn 0.0000 -0.0003 1.0000 +vn 0.9807 0.1954 0.0000 +vn 0.0008 0.0002 1.0000 +vn 0.7895 0.3619 -0.4957 +vn 0.7886 0.3659 -0.4942 +vn 0.7629 0.4158 -0.4950 +vn 0.7701 0.4007 -0.4964 +usemtl None +s off +f 1015/985/1410 999/986/1410 1022/987/1410 +f 987/988/1411 988/989/1411 991/990/1411 +f 987/988/1411 991/990/1411 992/991/1411 +f 990/992/1412 985/993/1412 993/994/1412 +f 993/994/1412 985/993/1412 995/995/1412 +f 987/988/1413 986/996/1413 996/997/1413 +f 985/993/1412 990/992/1412 999/986/1412 +f 986/996/1414 987/988/1414 1001/998/1414 +f 989/999/1415 993/994/1415 1001/998/1415 +f 993/994/1412 995/995/1412 1001/998/1412 +f 990/992/1416 998/1000/1416 1004/1001/1416 +f 999/986/1417 990/992/1417 1004/1001/1417 +f 991/990/1418 989/999/1418 1005/1002/1418 +f 989/999/1419 992/991/1419 1005/1002/1419 +f 992/991/1411 991/990/1411 1005/1002/1411 +f 1006/1003/1420 999/986/1420 1007/1004/1420 +f 996/997/1421 986/996/1421 1007/1004/1421 +f 997/1005/1422 1006/1003/1422 1007/1004/1422 +f 994/1006/1423 998/1000/1423 1008/1007/1423 +f 1003/1008/1424 988/989/1424 1008/1007/1424 +f 998/1000/1425 1003/1008/1425 1008/1007/1425 +f 986/996/1414 1001/998/1414 1009/1009/1414 +f 1001/998/1426 995/995/1426 1009/1009/1426 +f 1007/1004/1427 986/996/1427 1009/1009/1427 +f 1007/1004/1428 1009/1009/1428 1010/1010/1428 +f 997/1005/1429 1007/1004/1429 1010/1010/1429 +f 987/988/1411 992/991/1411 1011/1011/1411 +f 992/991/1430 989/999/1430 1011/1011/1430 +f 1001/998/1414 987/988/1414 1011/1011/1414 +f 989/999/1431 1001/998/1431 1011/1011/1431 +f 989/999/1432 991/990/1432 1012/1012/1432 +f 993/994/1433 989/999/1433 1012/1012/1433 +f 991/990/1434 1002/1013/1434 1012/1012/1434 +f 1002/1013/1435 993/994/1435 1012/1012/1435 +f 990/992/1412 993/994/1412 1013/1014/1412 +f 998/1000/1436 990/992/1436 1013/1014/1436 +f 993/994/1437 1002/1013/1437 1013/1014/1437 +f 1003/1008/1438 998/1000/1438 1013/1014/1438 +f 1002/1013/1439 1003/1008/1439 1013/1014/1439 +f 988/989/1411 987/988/1411 1014/1015/1411 +f 1007/1004/1440 999/986/1440 1015/985/1440 +f 996/997/1441 1007/1004/1441 1015/985/1441 +f 998/1000/1442 994/1006/1442 1016/1016/1442 +f 996/997/1443 998/1000/1443 1016/1016/1443 +f 994/1006/1444 1000/1017/1444 1016/1016/1444 +f 1000/1017/1445 996/997/1445 1016/1016/1445 +f 995/995/1446 985/993/1446 1017/1018/1446 +f 1009/1009/1447 995/995/1447 1017/1018/1447 +f 1010/1010/1448 1009/1009/1448 1017/1018/1448 +f 985/993/1449 1010/1010/1449 1017/1018/1449 +f 1000/1017/1450 994/1006/1450 1018/1019/1450 +f 994/1006/1451 1008/1007/1451 1018/1019/1451 +f 1008/1007/1452 988/989/1452 1018/1019/1452 +f 988/989/1453 1014/1015/1453 1018/1019/1453 +f 985/993/1412 999/986/1412 1019/1020/1412 +f 1006/1003/1454 997/1005/1454 1019/1020/1454 +f 999/986/1455 1006/1003/1455 1019/1020/1455 +f 1010/1010/1456 985/993/1456 1019/1020/1456 +f 997/1005/1457 1010/1010/1457 1019/1020/1457 +f 987/988/1458 996/997/1458 1020/1021/1458 +f 996/997/1459 1000/1017/1459 1020/1021/1459 +f 1014/1015/1411 987/988/1411 1020/1021/1411 +f 1000/1017/1460 1018/1019/1460 1020/1021/1460 +f 1018/1019/1461 1014/1015/1461 1020/1021/1461 +f 991/990/1411 988/989/1411 1021/1022/1411 +f 1002/1013/1462 991/990/1462 1021/1022/1462 +f 988/989/1463 1003/1008/1463 1021/1022/1463 +f 1003/1008/1464 1002/1013/1464 1021/1022/1464 +f 998/1000/1465 996/997/1465 1022/987/1465 +f 1004/1001/1466 998/1000/1466 1022/987/1466 +f 999/986/1467 1004/1001/1467 1022/987/1467 +f 996/997/1468 1015/985/1468 1022/987/1468 +o Bowl_hull_32 +v 0.043967 0.017242 -0.013996 +v 0.039654 0.005606 -0.025642 +v 0.039654 0.000433 -0.025642 +v 0.083196 0.004314 0.049366 +v 0.040084 0.018535 -0.011411 +v 0.078452 0.000433 0.048504 +v 0.081039 0.018969 0.049366 +v 0.077160 0.018969 0.050235 +v 0.040519 0.000433 -0.017873 +v 0.083196 0.000433 0.049366 +v 0.040084 0.018969 -0.018735 +v 0.040084 0.005606 -0.025642 +v 0.082330 0.012931 0.049366 +v 0.041380 0.000433 -0.023911 +v 0.041380 0.010775 -0.021757 +v 0.039654 0.018969 -0.012273 +v 0.065951 0.018969 0.023504 +v 0.079743 0.000433 0.050235 +v 0.082330 0.013794 0.050235 +v 0.076295 0.017242 0.040312 +v 0.039654 0.000433 -0.019604 +v 0.081900 0.008625 0.047643 +v 0.041811 0.003452 -0.023050 +v 0.077160 0.018535 0.050235 +v 0.040519 0.007761 -0.024342 +v 0.039654 0.018104 -0.012273 +v 0.040084 0.013363 -0.022619 +v 0.039654 0.018104 -0.019604 +v 0.083196 0.000433 0.050235 +v 0.051724 0.018969 -0.000204 +v 0.077591 0.003020 0.039450 +v 0.067673 0.011207 0.023504 +v 0.081039 0.018969 0.050235 +v 0.043537 0.006038 -0.019604 +v 0.081039 0.018535 0.048935 +v 0.082761 0.000433 0.048504 +vt 0.022807 0.039644 +vt 0.857870 0.871280 +vt 0.977193 0.990016 +vt 0.000000 0.000000 +vt 0.977193 0.891053 +vt 0.102388 0.019871 +vt 0.988547 1.000000 +vt 1.000000 0.861394 +vt 0.988547 0.950470 +vt 0.091034 0.009886 +vt 0.000000 0.000000 +vt 0.000000 0.009886 +vt 0.176194 0.000000 +vt 0.187549 0.009886 +vt 0.647709 0.603954 +vt 1.000000 0.920713 +vt 0.988547 0.980129 +vt 1.000000 0.980129 +vt 0.988547 1.000000 +vt 0.051194 0.039644 +vt 0.869225 0.841523 +vt 0.079581 0.000000 +vt 0.965838 0.970243 +vt 0.034162 0.049530 +vt 1.000000 0.861394 +vt 0.017130 0.019871 +vt 0.176194 0.000000 +vt 0.153485 0.099060 +vt 0.039839 0.009886 +vt 0.079581 0.000000 +vt 1.000000 1.000000 +vt 0.335258 0.277212 +vt 0.647709 0.643500 +vt 1.000000 0.950470 +vt 0.079581 0.089174 +vt 0.982870 0.950470 +vn 0.8682 -0.0013 -0.4961 +vn 0.0000 -1.0000 -0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.7068 -0.0588 -0.7050 +vn -1.0000 0.0000 0.0000 +vn -0.8452 0.1685 0.5072 +vn 0.9574 0.2048 -0.2035 +vn 0.9901 0.0994 -0.0988 +vn -0.0000 0.0000 1.0000 +vn 0.8414 0.2151 -0.4957 +vn 0.8906 0.0894 -0.4459 +vn 0.8441 0.0324 -0.5352 +vn 0.8662 0.0622 -0.4958 +vn -0.8518 -0.1097 0.5123 +vn -0.8569 0.0000 0.5154 +vn -0.7963 -0.1136 0.5942 +vn 0.8485 0.1833 -0.4964 +vn -0.8526 -0.1493 0.5008 +vn -0.8514 -0.1959 0.4866 +vn -0.8946 -0.0000 0.4470 +vn -0.8794 -0.1824 0.4397 +vn 0.7825 0.3546 -0.5119 +vn 0.0000 0.3631 -0.9317 +vn 0.8310 0.2508 -0.4965 +vn 0.7019 0.2587 -0.6637 +vn 0.8124 0.2281 -0.5366 +vn -0.8695 0.4906 -0.0579 +vn -0.8348 0.2395 -0.4958 +vn 0.4574 0.5064 -0.7310 +vn 1.0000 0.0000 0.0000 +vn 0.9588 0.0621 0.2773 +vn 0.7739 0.4061 -0.4861 +vn 0.8203 0.2833 -0.4968 +vn 0.8263 0.2670 -0.4959 +vn 0.8671 0.0457 -0.4961 +vn 0.8678 0.0180 -0.4967 +vn 0.8546 0.1572 -0.4949 +vn 0.8613 0.1122 -0.4956 +vn 0.8531 0.1621 -0.4959 +vn 0.9702 0.2421 0.0000 +vn 0.8618 0.0900 -0.4992 +vn 0.8641 0.0845 -0.4962 +vn 0.8570 0.1281 -0.4991 +vn 0.8613 0.1119 -0.4957 +vn 0.8573 0.1363 -0.4964 +vn 0.9569 0.2047 -0.2060 +vn 0.7724 0.4476 -0.4506 +vn 0.8548 0.1590 -0.4941 +vn 0.8411 0.2173 -0.4953 +vn 0.8928 0.0000 -0.4505 +vn 0.8698 0.0121 -0.4932 +usemtl None +s off +f 1036/1023/1469 1053/1024/1469 1058/1025/1469 +f 1025/1026/1470 1028/1027/1470 1031/1028/1470 +f 1028/1027/1470 1025/1026/1470 1032/1029/1470 +f 1030/1030/1471 1029/1031/1471 1033/1032/1471 +f 1025/1026/1472 1024/1033/1472 1034/1034/1472 +f 1032/1029/1470 1025/1026/1470 1036/1023/1470 +f 1025/1026/1473 1034/1034/1473 1036/1023/1473 +f 1024/1033/1474 1025/1026/1474 1038/1035/1474 +f 1027/1036/1475 1030/1030/1475 1038/1035/1475 +f 1030/1030/1471 1033/1032/1471 1038/1035/1471 +f 1033/1032/1471 1029/1031/1471 1039/1037/1471 +f 1028/1027/1470 1032/1029/1470 1040/1038/1470 +f 1035/1039/1476 1029/1031/1476 1041/1040/1476 +f 1026/1041/1477 1035/1039/1477 1041/1040/1477 +f 1030/1030/1478 1040/1038/1478 1041/1040/1478 +f 1037/1042/1479 1039/1037/1479 1042/1043/1479 +f 1025/1026/1470 1031/1028/1470 1043/1044/1470 +f 1038/1035/1474 1025/1026/1474 1043/1044/1474 +f 1035/1039/1480 1026/1041/1480 1044/1045/1480 +f 1036/1023/1481 1034/1034/1481 1045/1046/1481 +f 1044/1045/1482 1026/1041/1482 1045/1046/1482 +f 1027/1036/1483 1028/1027/1483 1046/1047/1483 +f 1030/1030/1484 1027/1036/1484 1046/1047/1484 +f 1028/1027/1485 1040/1038/1485 1046/1047/1485 +f 1040/1038/1478 1030/1030/1478 1046/1047/1478 +f 1037/1042/1486 1042/1043/1486 1047/1048/1486 +f 1028/1027/1487 1027/1036/1487 1048/1049/1487 +f 1031/1028/1488 1028/1027/1488 1048/1049/1488 +f 1027/1036/1489 1038/1035/1489 1048/1049/1489 +f 1043/1044/1490 1031/1028/1490 1048/1049/1490 +f 1038/1035/1474 1043/1044/1474 1048/1049/1474 +f 1033/1032/1491 1023/1050/1491 1049/1051/1491 +f 1034/1034/1492 1024/1033/1492 1049/1051/1492 +f 1039/1037/1493 1037/1042/1493 1049/1051/1493 +f 1047/1048/1494 1034/1034/1494 1049/1051/1494 +f 1037/1042/1495 1047/1048/1495 1049/1051/1495 +f 1024/1033/1474 1038/1035/1474 1050/1052/1474 +f 1038/1035/1496 1033/1032/1496 1050/1052/1496 +f 1049/1051/1497 1024/1033/1497 1050/1052/1497 +f 1033/1032/1498 1049/1051/1498 1050/1052/1498 +f 1032/1029/1499 1026/1041/1499 1051/1053/1499 +f 1040/1038/1470 1032/1029/1470 1051/1053/1470 +f 1026/1041/1500 1041/1040/1500 1051/1053/1500 +f 1041/1040/1478 1040/1038/1478 1051/1053/1478 +f 1023/1050/1501 1033/1032/1501 1052/1054/1501 +f 1033/1032/1471 1039/1037/1471 1052/1054/1471 +f 1049/1051/1502 1023/1050/1502 1052/1054/1502 +f 1039/1037/1503 1049/1051/1503 1052/1054/1503 +f 1045/1046/1504 1026/1041/1504 1053/1024/1504 +f 1036/1023/1505 1045/1046/1505 1053/1024/1505 +f 1042/1043/1506 1035/1039/1506 1054/1055/1506 +f 1035/1039/1507 1044/1045/1507 1054/1055/1507 +f 1047/1048/1508 1042/1043/1508 1054/1055/1508 +f 1029/1031/1471 1030/1030/1471 1055/1056/1471 +f 1041/1040/1509 1029/1031/1509 1055/1056/1509 +f 1030/1030/1478 1041/1040/1478 1055/1056/1478 +f 1045/1046/1510 1034/1034/1510 1056/1057/1510 +f 1044/1045/1511 1045/1046/1511 1056/1057/1511 +f 1034/1034/1512 1047/1048/1512 1056/1057/1512 +f 1054/1055/1513 1044/1045/1513 1056/1057/1513 +f 1047/1048/1514 1054/1055/1514 1056/1057/1514 +f 1029/1031/1515 1035/1039/1515 1057/1058/1515 +f 1039/1037/1516 1029/1031/1516 1057/1058/1516 +f 1035/1039/1517 1042/1043/1517 1057/1058/1517 +f 1042/1043/1518 1039/1037/1518 1057/1058/1518 +f 1026/1041/1519 1032/1029/1519 1058/1025/1519 +f 1032/1029/1470 1036/1023/1470 1058/1025/1470 +f 1053/1024/1520 1026/1041/1520 1058/1025/1520 +o Bowl_hull_33 +v -0.050883 -0.019831 -0.001059 +v -0.083211 0.000431 0.049363 +v -0.083211 -0.003452 0.049363 +v -0.076746 -0.019399 0.049794 +v -0.039678 0.000431 -0.019604 +v -0.040539 -0.003881 -0.025204 +v -0.039678 -0.019831 -0.011412 +v -0.078472 0.000431 0.048502 +v -0.080194 -0.019831 0.048071 +v -0.040108 -0.012501 -0.023050 +v -0.041400 0.000431 -0.023911 +v -0.081920 -0.015519 0.049363 +v -0.039678 -0.019831 -0.018311 +v -0.039678 -0.019399 -0.011412 +v -0.077176 -0.019831 0.050232 +v -0.082781 -0.009486 0.049363 +v -0.042691 -0.008193 -0.020465 +v -0.040539 0.000431 -0.017873 +v -0.079763 0.000431 0.050232 +v -0.039678 0.000431 -0.025642 +v -0.081059 -0.019831 0.050232 +v -0.083211 0.000431 0.050232 +v -0.075024 -0.019399 0.039017 +v -0.040969 -0.019831 -0.017019 +v -0.040108 -0.005606 -0.025642 +v -0.063384 -0.019831 0.019626 +v -0.064245 -0.003881 0.016172 +v -0.042691 -0.009486 -0.020035 +v -0.076315 -0.009914 0.038156 +v -0.039678 -0.009486 -0.024342 +v -0.082781 -0.001727 0.048502 +v -0.048300 -0.002159 -0.011843 +v -0.082781 -0.006900 0.048932 +v -0.040969 -0.014655 -0.020465 +v -0.082781 -0.010347 0.050232 +v -0.040969 -0.019399 -0.009258 +v -0.041400 -0.011640 -0.021327 +vt 0.073904 0.930781 +vt 0.000000 0.990112 +vt 0.056872 0.960446 +vt 0.079581 1.000000 +vt 0.988547 0.000000 +vt 0.977193 0.108870 +vt 0.324002 0.742608 +vt 0.187549 1.000000 +vt 0.971515 0.069317 +vt 0.022807 0.960446 +vt 0.096613 1.000000 +vt 0.187549 1.000000 +vt 0.994225 0.148522 +vt 1.000000 0.138633 +vt 0.102388 0.980223 +vt 1.000000 0.079205 +vt 0.000000 1.000000 +vt 0.005775 0.980223 +vt 0.988547 0.029665 +vt 1.000000 0.049442 +vt 1.000000 0.000000 +vt 0.988547 0.000000 +vt 0.852193 0.188075 +vt 0.113645 0.970335 +vt 0.034162 0.990112 +vt 0.068226 0.930781 +vt 0.596613 0.455453 +vt 0.988547 0.009888 +vt 0.840838 0.158410 +vt 0.017130 1.000000 +vt 0.977193 0.009888 +vt 0.551096 0.435677 +vt 0.181872 0.801939 +vt 0.982870 0.009888 +vt 0.068226 0.970335 +vt 1.000000 0.009888 +vt 0.215936 0.970335 +vn -0.8348 -0.1907 -0.5165 +vn 0.0000 1.0000 0.0000 +vn -0.0000 -1.0000 -0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.8128 -0.3081 0.4944 +vn 0.8805 0.1810 0.4381 +vn 0.8515 0.1955 0.4866 +vn 0.7967 0.1081 0.5946 +vn 0.6674 0.0852 0.7398 +vn -0.7071 0.0697 -0.7036 +vn -0.8984 -0.2519 -0.3597 +vn 0.0000 -0.0000 1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.8483 -0.1917 -0.4936 +vn -0.6331 -0.4461 -0.6326 +vn -0.8575 -0.1365 -0.4961 +vn -0.6201 0.0442 -0.7833 +vn -0.8103 -0.3378 -0.4789 +vn -0.8523 -0.1653 -0.4962 +vn -0.8483 -0.1860 -0.4957 +vn -0.8457 -0.1686 -0.5062 +vn -0.8616 -0.1230 -0.4924 +vn -0.8580 -0.1337 -0.4960 +vn -0.8636 -0.0895 -0.4962 +vn 0.6824 -0.3681 -0.6315 +vn -0.3265 -0.3326 -0.8847 +vn 0.8767 -0.0625 -0.4770 +vn -0.8945 0.0000 -0.4470 +vn -0.8683 0.0246 -0.4955 +vn -0.8680 -0.0309 -0.4956 +vn -0.8680 -0.0284 -0.4958 +vn -0.8658 -0.0230 -0.4999 +vn -0.8664 -0.0534 -0.4964 +vn -0.8682 0.0014 -0.4961 +vn -0.9172 -0.0654 -0.3929 +vn -0.8676 -0.0465 -0.4952 +vn -0.8657 -0.0671 -0.4960 +vn -0.8646 -0.0825 -0.4956 +vn -0.8645 -0.0814 -0.4959 +vn -0.8015 -0.3314 -0.4978 +vn -0.7437 -0.3704 -0.5565 +vn -0.8197 -0.2874 -0.4954 +vn -0.8266 -0.2652 -0.4964 +vn -0.9804 -0.1399 -0.1386 +vn -0.9950 -0.0710 -0.0703 +vn -0.9801 -0.1779 0.0881 +vn -0.9837 -0.0393 0.1756 +vn 0.8550 -0.0266 0.5180 +vn 0.8503 0.1076 0.5152 +vn 0.8576 0.0000 0.5142 +vn 0.8511 0.1232 0.5103 +vn -0.8292 -0.1967 -0.5232 +vn -0.8306 -0.2525 -0.4964 +vn -0.8350 -0.2382 -0.4959 +vn -0.8429 -0.2076 -0.4964 +usemtl None +s off +f 1086/1059/1521 1083/1060/1521 1095/1061/1521 +f 1063/1062/1522 1060/1063/1522 1066/1064/1522 +f 1059/1065/1523 1065/1066/1523 1067/1067/1523 +f 1060/1063/1522 1063/1062/1522 1069/1068/1522 +f 1065/1066/1523 1059/1065/1523 1071/1069/1523 +f 1063/1062/1524 1065/1066/1524 1071/1069/1524 +f 1065/1066/1524 1063/1062/1524 1072/1070/1524 +f 1065/1066/1525 1062/1071/1525 1073/1072/1525 +f 1067/1067/1523 1065/1066/1523 1073/1072/1523 +f 1063/1062/1522 1066/1064/1522 1076/1073/1522 +f 1072/1070/1526 1063/1062/1526 1076/1073/1526 +f 1066/1064/1527 1072/1070/1527 1076/1073/1527 +f 1066/1064/1522 1060/1063/1522 1077/1074/1522 +f 1062/1071/1528 1066/1064/1528 1077/1074/1528 +f 1073/1072/1529 1062/1071/1529 1077/1074/1529 +f 1069/1068/1522 1063/1062/1522 1078/1075/1522 +f 1064/1076/1530 1069/1068/1530 1078/1075/1530 +f 1063/1062/1524 1071/1069/1524 1078/1075/1524 +f 1070/1077/1531 1067/1067/1531 1079/1078/1531 +f 1067/1067/1523 1073/1072/1523 1079/1078/1523 +f 1073/1072/1532 1077/1074/1532 1079/1078/1532 +f 1079/1078/1532 1077/1074/1532 1080/1079/1532 +f 1060/1063/1533 1061/1080/1533 1080/1079/1533 +f 1077/1074/1522 1060/1063/1522 1080/1079/1522 +f 1067/1067/1534 1070/1077/1534 1081/1081/1534 +f 1071/1069/1523 1059/1065/1523 1082/1082/1523 +f 1068/1083/1535 1071/1069/1535 1082/1082/1535 +f 1075/1084/1536 1070/1077/1536 1083/1060/1536 +f 1064/1076/1537 1078/1075/1537 1083/1060/1537 +f 1059/1065/1523 1067/1067/1523 1084/1085/1523 +f 1067/1067/1538 1081/1081/1538 1084/1085/1538 +f 1070/1077/1539 1075/1084/1539 1086/1059/1539 +f 1081/1081/1540 1070/1077/1540 1086/1059/1540 +f 1075/1084/1541 1083/1060/1541 1086/1059/1541 +f 1070/1077/1542 1074/1086/1542 1087/1087/1542 +f 1083/1060/1543 1070/1077/1543 1087/1087/1543 +f 1064/1076/1544 1083/1060/1544 1087/1087/1544 +f 1071/1069/1545 1068/1083/1545 1088/1088/1545 +f 1078/1075/1524 1071/1069/1524 1088/1088/1524 +f 1068/1083/1546 1083/1060/1546 1088/1088/1546 +f 1083/1060/1547 1078/1075/1547 1088/1088/1547 +f 1061/1080/1548 1060/1063/1548 1089/1089/1548 +f 1060/1063/1549 1069/1068/1549 1089/1089/1549 +f 1085/1090/1550 1061/1080/1550 1089/1089/1550 +f 1085/1090/1551 1089/1089/1551 1090/1091/1551 +f 1069/1068/1552 1064/1076/1552 1090/1091/1552 +f 1064/1076/1553 1085/1090/1553 1090/1091/1553 +f 1089/1089/1554 1069/1068/1554 1090/1091/1554 +f 1074/1086/1555 1061/1080/1555 1091/1092/1555 +f 1061/1080/1556 1085/1090/1556 1091/1092/1556 +f 1085/1090/1557 1064/1076/1557 1091/1092/1557 +f 1087/1087/1558 1074/1086/1558 1091/1092/1558 +f 1064/1076/1559 1087/1087/1559 1091/1092/1559 +f 1082/1082/1560 1059/1065/1560 1092/1093/1560 +f 1068/1083/1561 1082/1082/1561 1092/1093/1561 +f 1059/1065/1562 1084/1085/1562 1092/1093/1562 +f 1084/1085/1563 1068/1083/1563 1092/1093/1563 +f 1074/1086/1564 1070/1077/1564 1093/1094/1564 +f 1061/1080/1565 1074/1086/1565 1093/1094/1565 +f 1070/1077/1566 1079/1078/1566 1093/1094/1566 +f 1079/1078/1532 1080/1079/1532 1093/1094/1532 +f 1080/1079/1567 1061/1080/1567 1093/1094/1567 +f 1062/1071/1568 1065/1066/1568 1094/1095/1568 +f 1066/1064/1569 1062/1071/1569 1094/1095/1569 +f 1065/1066/1570 1072/1070/1570 1094/1095/1570 +f 1072/1070/1571 1066/1064/1571 1094/1095/1571 +f 1083/1060/1572 1068/1083/1572 1095/1061/1572 +f 1068/1083/1573 1084/1085/1573 1095/1061/1573 +f 1084/1085/1574 1081/1081/1574 1095/1061/1574 +f 1081/1081/1575 1086/1059/1575 1095/1061/1575 +o Bowl_hull_34 +v -0.046143 -0.039229 0.009282 +v -0.080629 -0.019833 0.048934 +v -0.080629 -0.020266 0.048934 +v -0.040106 -0.020266 -0.017882 +v -0.040106 -0.039660 0.010142 +v -0.072867 -0.040092 0.048934 +v -0.076748 -0.020266 0.050235 +v -0.039673 -0.019833 -0.010981 +v -0.068125 -0.039660 0.049368 +v -0.039673 -0.040092 0.002814 +v -0.077610 -0.030608 0.049368 +v -0.040106 -0.025438 -0.013568 +v -0.068987 -0.040092 0.050235 +v -0.056491 -0.020266 0.008422 +v -0.059938 -0.040092 0.029538 +v -0.075882 -0.019833 0.048508 +v -0.039673 -0.019833 -0.017882 +v -0.078039 -0.029749 0.050235 +v -0.070282 -0.032762 0.039020 +v -0.039673 -0.040092 0.009282 +v -0.040106 -0.031039 -0.007960 +v -0.042263 -0.021128 -0.014001 +v -0.076748 -0.025008 0.044627 +v -0.073296 -0.040092 0.050235 +v -0.080629 -0.019833 0.050235 +v -0.040968 -0.040092 0.003675 +v -0.050453 -0.020266 -0.001493 +v -0.071144 -0.039229 0.045487 +v -0.055196 -0.039660 0.022211 +v -0.050453 -0.019833 -0.001493 +v -0.060796 -0.038367 0.029105 +v -0.041830 -0.025008 -0.011408 +v -0.074158 -0.034918 0.046781 +v -0.068125 -0.020266 0.027811 +v -0.039673 -0.031039 -0.007960 +v -0.040106 -0.034918 -0.003646 +v -0.049591 -0.040092 0.014883 +vt 0.208986 0.989428 +vt 0.398786 0.842013 +vt 0.481010 0.757831 +vt 0.411413 0.989428 +vt 1.000000 0.094753 +vt 0.987275 0.305305 +vt 1.000000 0.284260 +vt 0.980912 0.189507 +vt 0.303837 1.000000 +vt 0.696163 0.505188 +vt 0.974648 0.115897 +vt 0.101312 1.000000 +vt 0.980912 0.000000 +vt 0.000000 1.000000 +vt 0.063332 0.989428 +vt 0.000000 0.989428 +vt 0.980912 0.000000 +vt 0.987275 0.073708 +vt 1.000000 0.063234 +vt 0.398786 1.000000 +vt 0.917678 0.094753 +vt 0.386159 0.589370 +vt 1.000000 0.179033 +vt 1.000000 0.000000 +vt 0.316464 0.968383 +vt 0.240603 0.736785 +vt 0.835356 0.252643 +vt 0.056969 0.936766 +vt 0.930305 0.231597 +vt 0.145654 0.989428 +vt 0.588587 0.620987 +vt 0.240603 0.736785 +vt 0.689800 0.484240 +vt 0.095047 0.947337 +vt 0.949295 0.157987 +vt 0.670811 0.305305 +vt 0.145654 1.000000 +vn -0.6685 -0.5535 -0.4968 +vn 0.7714 0.3184 0.5510 +vn 0.6240 0.2443 0.7423 +vn 0.0000 -1.0000 0.0000 +vn 0.7607 0.4275 0.4885 +vn 0.0000 1.0000 0.0000 +vn 0.7531 0.4719 0.4584 +vn 1.0000 0.0000 0.0000 +vn 0.5388 -0.5396 -0.6469 +vn -0.9411 -0.2825 -0.1859 +vn 0.0000 -0.0000 1.0000 +vn 0.9037 0.3028 0.3027 +vn 0.7701 -0.3231 0.5501 +vn 0.7404 -0.4135 0.5300 +vn -0.8433 -0.2657 -0.4672 +vn -0.8172 -0.2939 -0.4957 +vn -0.8626 -0.4183 -0.2846 +vn -0.9084 -0.4165 -0.0369 +vn -1.0000 0.0000 0.0000 +vn 0.1059 0.9508 0.2912 +vn -0.9641 -0.2518 0.0837 +vn -0.8146 -0.3005 -0.4961 +vn -0.7997 -0.3386 -0.4958 +vn -0.8127 -0.2762 -0.5131 +vn -0.7950 -0.3483 -0.4966 +vn -0.7280 -0.4843 -0.4853 +vn -0.7102 -0.4981 -0.4975 +vn -0.6408 0.6417 -0.4215 +vn -0.8541 0.0000 -0.5201 +vn -0.8456 0.0000 -0.5339 +vn -0.7281 -0.4840 -0.4854 +vn -0.7221 -0.4821 -0.4962 +vn -0.7217 -0.4833 -0.4956 +vn -0.7466 -0.4261 -0.5109 +vn -0.7480 -0.4246 -0.5101 +vn -0.7614 -0.4169 -0.4965 +vn -0.7480 -0.4412 -0.4957 +vn -0.7367 -0.4593 -0.4963 +vn -0.8110 -0.3855 -0.4400 +vn -0.7988 -0.3431 -0.4943 +vn -0.7780 -0.3859 -0.4958 +vn -0.7773 -0.3971 -0.4881 +vn -0.7746 -0.3929 -0.4956 +vn -0.8605 0.0000 -0.5094 +vn -0.8365 -0.2348 -0.4952 +vn -0.8288 -0.2563 -0.4973 +vn -0.8284 0.2606 -0.4957 +vn -0.8446 0.1729 -0.5068 +vn 0.7463 -0.4412 -0.4983 +vn 0.0000 -0.7075 -0.7067 +vn 0.0000 -0.7436 -0.6686 +vn -0.6347 -0.5939 -0.4944 +vn -0.3747 -0.7358 -0.5641 +vn 0.4103 -0.6982 -0.5866 +vn -0.6215 -0.6206 -0.4782 +vn -0.6335 -0.6314 -0.4472 +vn -0.6889 -0.5289 -0.4957 +vn -0.6692 -0.5526 -0.4969 +usemtl None +s off +f 1131/1096/1576 1096/1097/1576 1132/1098/1576 +f 1100/1099/1577 1102/1100/1577 1104/1101/1577 +f 1104/1101/1578 1102/1100/1578 1108/1102/1578 +f 1101/1103/1579 1105/1104/1579 1108/1102/1579 +f 1105/1104/1579 1101/1103/1579 1110/1105/1579 +f 1102/1100/1580 1100/1099/1580 1111/1106/1580 +f 1103/1107/1581 1097/1108/1581 1111/1106/1581 +f 1100/1099/1582 1103/1107/1582 1111/1106/1582 +f 1097/1108/1581 1103/1107/1581 1112/1109/1581 +f 1103/1107/1583 1105/1104/1583 1112/1109/1583 +f 1107/1110/1584 1099/1111/1584 1112/1109/1584 +f 1098/1112/1585 1106/1113/1585 1113/1114/1585 +f 1108/1102/1586 1102/1100/1586 1113/1114/1586 +f 1103/1107/1587 1100/1099/1587 1115/1115/1587 +f 1100/1099/1588 1104/1101/1588 1115/1115/1588 +f 1105/1104/1583 1103/1107/1583 1115/1115/1583 +f 1104/1101/1589 1108/1102/1589 1115/1115/1589 +f 1108/1102/1579 1105/1104/1579 1115/1115/1579 +f 1106/1113/1590 1098/1112/1590 1118/1116/1590 +f 1109/1117/1591 1106/1113/1591 1118/1116/1591 +f 1106/1113/1592 1101/1103/1592 1119/1118/1592 +f 1101/1103/1579 1108/1102/1579 1119/1118/1579 +f 1113/1114/1593 1106/1113/1593 1119/1118/1593 +f 1108/1102/1586 1113/1114/1586 1119/1118/1586 +f 1097/1108/1594 1098/1112/1594 1120/1119/1594 +f 1111/1106/1581 1097/1108/1581 1120/1119/1581 +f 1102/1100/1595 1111/1106/1595 1120/1119/1595 +f 1098/1112/1596 1113/1114/1596 1120/1119/1596 +f 1113/1114/1586 1102/1100/1586 1120/1119/1586 +f 1105/1104/1579 1110/1105/1579 1121/1120/1579 +f 1106/1113/1597 1109/1117/1597 1122/1121/1597 +f 1114/1122/1598 1106/1113/1598 1122/1121/1598 +f 1099/1111/1599 1117/1123/1599 1122/1121/1599 +f 1117/1123/1600 1114/1122/1600 1122/1121/1600 +f 1110/1105/1601 1101/1103/1601 1123/1124/1601 +f 1107/1110/1602 1116/1125/1602 1124/1126/1602 +f 1097/1108/1581 1112/1109/1581 1125/1127/1581 +f 1112/1109/1603 1099/1111/1603 1125/1127/1603 +f 1122/1121/1604 1109/1117/1604 1125/1127/1604 +f 1099/1111/1605 1122/1121/1605 1125/1127/1605 +f 1110/1105/1606 1123/1124/1606 1126/1128/1606 +f 1107/1110/1607 1124/1126/1607 1126/1128/1607 +f 1124/1126/1608 1110/1105/1608 1126/1128/1608 +f 1099/1111/1609 1107/1110/1609 1127/1129/1609 +f 1117/1123/1610 1099/1111/1610 1127/1129/1610 +f 1123/1124/1611 1117/1123/1611 1127/1129/1611 +f 1126/1128/1612 1123/1124/1612 1127/1129/1612 +f 1107/1110/1613 1126/1128/1613 1127/1129/1613 +f 1101/1103/1614 1106/1113/1614 1128/1130/1614 +f 1106/1113/1615 1114/1122/1615 1128/1130/1615 +f 1114/1122/1616 1117/1123/1616 1128/1130/1616 +f 1123/1124/1617 1101/1103/1617 1128/1130/1617 +f 1117/1123/1618 1123/1124/1618 1128/1130/1618 +f 1098/1112/1619 1097/1108/1619 1129/1131/1619 +f 1118/1116/1620 1098/1112/1620 1129/1131/1620 +f 1109/1117/1621 1118/1116/1621 1129/1131/1621 +f 1097/1108/1622 1125/1127/1622 1129/1131/1622 +f 1125/1127/1623 1109/1117/1623 1129/1131/1623 +f 1112/1109/1583 1105/1104/1583 1130/1132/1583 +f 1107/1110/1624 1112/1109/1624 1130/1132/1624 +f 1116/1125/1625 1107/1110/1625 1130/1132/1625 +f 1116/1125/1626 1130/1132/1626 1131/1096/1626 +f 1121/1120/1627 1096/1097/1627 1131/1096/1627 +f 1105/1104/1628 1121/1120/1628 1131/1096/1628 +f 1130/1132/1629 1105/1104/1629 1131/1096/1629 +f 1096/1097/1630 1121/1120/1630 1132/1098/1630 +f 1121/1120/1579 1110/1105/1579 1132/1098/1579 +f 1110/1105/1631 1124/1126/1631 1132/1098/1631 +f 1124/1126/1632 1116/1125/1632 1132/1098/1632 +f 1116/1125/1633 1131/1096/1633 1132/1098/1633 +o Bowl_hull_35 +v 0.037064 -0.024576 -0.018744 +v 0.040084 -0.039663 0.008847 +v 0.040084 -0.039663 0.002376 +v 0.009043 -0.039663 -0.018744 +v 0.039652 -0.006898 -0.018312 +v 0.020255 -0.039663 -0.018744 +v 0.040084 -0.019406 -0.018744 +v 0.009043 -0.039230 -0.018309 +v 0.039652 -0.039227 0.008847 +v 0.030163 -0.032764 -0.018744 +v 0.040084 -0.006898 -0.018744 +v 0.029732 -0.039230 -0.010552 +v 0.040084 -0.031468 -0.007533 +v 0.033184 -0.029743 -0.018744 +v 0.037924 -0.039663 -0.000641 +v 0.025855 -0.036209 -0.018744 +v 0.040084 -0.037504 -0.000641 +v 0.040084 -0.025003 -0.014001 +v 0.032752 -0.039663 -0.006669 +v 0.039652 -0.006898 -0.018744 +vt 0.000000 0.986100 +vt 0.000000 1.000000 +vt 0.000000 0.986100 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 1.000000 0.361198 +vt 0.539546 0.902702 +vt 0.381754 1.000000 +vt 0.986785 0.000000 +vt 0.986688 0.986100 +vt 0.789448 0.680403 +vt 0.749902 1.000000 +vt 0.697240 0.777702 +vt 1.000000 0.930403 +vt 0.894577 0.541601 +vt 0.986785 0.666503 +vt 0.934123 1.000000 +vt 0.552565 1.000000 +vt 1.000000 0.763802 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn -0.5313 -0.6003 0.5978 +vn -0.5620 0.5321 0.6333 +vn 0.5452 0.5393 0.6419 +vn -0.5548 -0.5488 0.6254 +vn 0.6082 0.5113 0.6072 +vn 0.6903 -0.5184 -0.5047 +vn 0.4576 -0.7418 -0.4902 +vn 0.5393 -0.6746 -0.5041 +vn 0.6137 -0.6135 -0.4969 +vn 0.6616 -0.5641 -0.4940 +vn 0.6306 -0.6312 -0.4516 +vn 0.6134 -0.6139 -0.4969 +vn 0.7420 -0.4334 -0.5115 +vn 0.7107 -0.4975 -0.4973 +vn 0.3677 -0.8485 -0.3805 +vn 0.5475 -0.6706 -0.5005 +vn 0.5769 -0.6498 -0.4949 +vn -0.6043 0.5646 -0.5622 +vn -0.7262 0.6875 0.0000 +usemtl None +s off +f 1137/1133/1634 1143/1134/1634 1152/1135/1634 +f 1135/1136/1635 1134/1137/1635 1136/1138/1635 +f 1135/1136/1635 1136/1138/1635 1138/1139/1635 +f 1136/1138/1636 1133/1140/1636 1138/1139/1636 +f 1134/1137/1637 1135/1136/1637 1139/1141/1637 +f 1133/1140/1636 1136/1138/1636 1139/1141/1636 +f 1136/1138/1638 1134/1137/1638 1140/1142/1638 +f 1137/1133/1639 1140/1142/1639 1141/1143/1639 +f 1134/1137/1640 1137/1133/1640 1141/1143/1640 +f 1140/1142/1641 1134/1137/1641 1141/1143/1641 +f 1138/1139/1636 1133/1140/1636 1142/1144/1636 +f 1137/1133/1642 1134/1137/1642 1143/1134/1642 +f 1134/1137/1637 1139/1141/1637 1143/1134/1637 +f 1139/1141/1636 1136/1138/1636 1143/1134/1636 +f 1139/1141/1637 1135/1136/1637 1145/1145/1637 +f 1142/1144/1636 1133/1140/1636 1146/1146/1636 +f 1133/1140/1643 1145/1145/1643 1146/1146/1643 +f 1135/1136/1635 1138/1139/1635 1147/1147/1635 +f 1138/1139/1636 1142/1144/1636 1148/1148/1636 +f 1144/1149/1644 1138/1139/1644 1148/1148/1644 +f 1142/1144/1645 1144/1149/1645 1148/1148/1645 +f 1145/1145/1637 1135/1136/1637 1149/1150/1637 +f 1142/1144/1646 1146/1146/1646 1149/1150/1646 +f 1146/1146/1647 1145/1145/1647 1149/1150/1647 +f 1135/1136/1648 1147/1147/1648 1149/1150/1648 +f 1147/1147/1649 1142/1144/1649 1149/1150/1649 +f 1133/1140/1650 1139/1141/1650 1150/1151/1650 +f 1145/1145/1651 1133/1140/1651 1150/1151/1651 +f 1139/1141/1637 1145/1145/1637 1150/1151/1637 +f 1138/1139/1652 1144/1149/1652 1151/1152/1652 +f 1144/1149/1653 1142/1144/1653 1151/1152/1653 +f 1147/1147/1635 1138/1139/1635 1151/1152/1635 +f 1142/1144/1654 1147/1147/1654 1151/1152/1654 +f 1136/1138/1655 1140/1142/1655 1152/1135/1655 +f 1140/1142/1656 1137/1133/1656 1152/1135/1656 +f 1143/1134/1636 1136/1138/1636 1152/1135/1636 +o Bowl_hull_36 +v -0.039241 -0.029742 -0.010548 +v -0.039673 -0.007763 -0.019172 +v -0.039673 -0.007763 -0.018739 +v -0.005183 -0.039660 -0.019175 +v -0.039241 -0.039657 0.008847 +v -0.022857 -0.037936 -0.019175 +v -0.039673 -0.040094 0.002379 +v -0.039673 -0.019403 -0.019172 +v -0.018549 -0.040091 -0.019175 +v -0.032772 -0.030176 -0.018739 +v -0.005183 -0.039660 -0.018742 +v -0.039241 -0.007763 -0.018739 +v -0.039673 -0.040094 0.008847 +v -0.031050 -0.040094 -0.007962 +v -0.005183 -0.040091 -0.018742 +v -0.029325 -0.033192 -0.019172 +v -0.039673 -0.037932 -0.000638 +v -0.036222 -0.025432 -0.019172 +v -0.037515 -0.040094 -0.000638 +v -0.039673 -0.023283 -0.016152 +v -0.025014 -0.040091 -0.013999 +v -0.027600 -0.036211 -0.017016 +vt 0.487569 0.933242 +vt 0.425020 0.999902 +vt 0.350039 0.879894 +vt 0.000000 0.000000 +vt 1.000000 0.986590 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 0.000000 0.360023 +vt 0.612471 0.999902 +vt 0.012529 0.000000 +vt 0.012529 0.986492 +vt 1.000000 0.986590 +vt 0.000000 1.000000 +vt 0.250000 1.000000 +vt 1.000000 0.999902 +vt 0.000000 0.933144 +vt 0.012529 0.679816 +vt 0.200078 0.693226 +vt 0.100039 0.546496 +vt 0.300020 0.786511 +vt 0.062549 1.000000 +vt 0.000000 0.480031 +vn -0.4879 -0.7148 -0.5010 +vn 0.0000 0.0001 -1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.0002 0.0000 -1.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 1.0000 0.0000 +vn 0.5622 0.6080 -0.5606 +vn 0.0000 0.6542 0.7563 +vn 0.6836 0.7299 0.0000 +vn 0.5225 0.5578 0.6449 +vn -0.5485 0.5427 0.6361 +vn 0.0000 -1.0000 0.0000 +vn 0.0002 -1.0000 0.0001 +vn 0.0228 -0.7094 -0.7045 +vn 1.0000 0.0000 0.0000 +vn 0.6295 0.0000 0.7770 +vn 0.5314 -0.5258 0.6642 +vn 0.0000 -1.0000 -0.0003 +vn -0.6630 -0.5626 -0.4938 +vn -0.0004 -0.0003 -1.0000 +vn -0.6754 -0.5374 -0.5050 +vn -0.0012 -0.0011 -1.0000 +vn -0.4510 -0.4009 -0.7974 +vn -0.6055 -0.6203 -0.4986 +vn -0.5607 -0.6638 -0.4950 +vn -0.6315 -0.6303 -0.4515 +vn -0.6142 -0.6130 -0.4969 +vn -0.8912 -0.3298 -0.3114 +vn -0.7316 -0.4187 -0.5379 +vn -0.7281 -0.4764 -0.4929 +vn -0.3906 -0.7807 -0.4878 +vn -0.0021 -1.0000 -0.0026 +vn -0.4946 -0.7145 -0.4949 +vn -0.4947 -0.6742 -0.5483 +vn -0.5511 -0.6700 -0.4973 +usemtl None +s off +f 1158/1153/1657 1173/1154/1657 1174/1155/1657 +f 1154/1156/1658 1156/1157/1658 1158/1153/1658 +f 1155/1158/1659 1154/1156/1659 1159/1159/1659 +f 1154/1156/1660 1158/1153/1660 1160/1160/1660 +f 1159/1159/1659 1154/1156/1659 1160/1160/1659 +f 1158/1153/1661 1156/1157/1661 1161/1161/1661 +f 1154/1156/1662 1155/1158/1662 1164/1162/1662 +f 1156/1157/1663 1154/1156/1663 1164/1162/1663 +f 1155/1158/1664 1157/1163/1664 1164/1162/1664 +f 1163/1164/1665 1156/1157/1665 1164/1162/1665 +f 1157/1163/1666 1163/1164/1666 1164/1162/1666 +f 1157/1163/1667 1155/1158/1667 1165/1165/1667 +f 1155/1158/1659 1159/1159/1659 1165/1165/1659 +f 1165/1165/1668 1159/1159/1668 1166/1166/1668 +f 1165/1165/1669 1166/1166/1669 1167/1167/1669 +f 1161/1161/1670 1156/1157/1670 1167/1167/1670 +f 1156/1157/1671 1163/1164/1671 1167/1167/1671 +f 1163/1164/1672 1157/1163/1672 1167/1167/1672 +f 1157/1163/1673 1165/1165/1673 1167/1167/1673 +f 1166/1166/1674 1161/1161/1674 1167/1167/1674 +f 1159/1159/1659 1160/1160/1659 1169/1168/1659 +f 1153/1169/1675 1162/1170/1675 1169/1168/1675 +f 1160/1160/1676 1158/1153/1676 1170/1171/1676 +f 1162/1170/1677 1153/1169/1677 1170/1171/1677 +f 1158/1153/1678 1168/1172/1678 1170/1171/1678 +f 1168/1172/1679 1162/1170/1679 1170/1171/1679 +f 1166/1166/1668 1159/1159/1668 1171/1173/1668 +f 1162/1170/1680 1168/1172/1680 1171/1173/1680 +f 1168/1172/1681 1166/1166/1681 1171/1173/1681 +f 1159/1159/1682 1169/1168/1682 1171/1173/1682 +f 1169/1168/1683 1162/1170/1683 1171/1173/1683 +f 1153/1169/1684 1169/1168/1684 1172/1174/1684 +f 1169/1168/1659 1160/1160/1659 1172/1174/1659 +f 1160/1160/1685 1170/1171/1685 1172/1174/1685 +f 1170/1171/1686 1153/1169/1686 1172/1174/1686 +f 1158/1153/1687 1161/1161/1687 1173/1154/1687 +f 1161/1161/1688 1166/1166/1688 1173/1154/1688 +f 1173/1154/1689 1166/1166/1689 1174/1155/1689 +f 1168/1172/1690 1158/1153/1690 1174/1155/1690 +f 1166/1166/1691 1168/1172/1691 1174/1155/1691 +o Bowl_hull_37 +v -0.055196 -0.045701 0.028676 +v -0.042259 -0.071565 0.050235 +v -0.042259 -0.067253 0.050235 +v -0.072867 -0.040094 0.050230 +v -0.042259 -0.040094 0.013162 +v -0.068124 -0.040094 0.049800 +v -0.042691 -0.040525 0.006692 +v -0.054330 -0.063371 0.049365 +v -0.065107 -0.052167 0.049369 +v -0.042691 -0.059061 0.030829 +v -0.064676 -0.040528 0.036864 +v -0.045711 -0.069837 0.049369 +v -0.042691 -0.045701 0.012731 +v -0.061227 -0.056905 0.049800 +v -0.042259 -0.040094 0.006692 +v -0.042691 -0.040094 0.014023 +v -0.071141 -0.043547 0.049369 +v -0.051745 -0.040528 0.018336 +v -0.042259 -0.066821 0.049800 +v -0.059936 -0.055614 0.046352 +v -0.043554 -0.041388 0.008418 +v -0.053471 -0.064234 0.050235 +v -0.065970 -0.047857 0.045921 +v -0.068556 -0.040094 0.050230 +v -0.042259 -0.071565 0.049369 +v -0.053902 -0.056474 0.039882 +v -0.067261 -0.049582 0.050230 +v -0.072867 -0.040094 0.049369 +v -0.050022 -0.066821 0.049365 +v -0.043554 -0.052170 0.022219 +v -0.042259 -0.053464 0.023076 +v -0.051745 -0.040097 0.018336 +v -0.043122 -0.071131 0.048935 +v -0.059073 -0.040960 0.029107 +v -0.061227 -0.050013 0.041608 +v -0.056919 -0.060355 0.048508 +vt 0.910826 0.493148 +vt 0.762236 0.520458 +vt 0.960356 0.643794 +vt 1.000000 0.862960 +vt 1.000000 1.000000 +vt 0.148590 0.000000 +vt 0.999902 0.000000 +vt 0.990016 0.000000 +vt 0.000000 0.000000 +vt 0.138704 0.178152 +vt 0.000000 0.013704 +vt 0.168363 0.000000 +vt 0.990016 0.849256 +vt 0.990016 0.534162 +vt 0.980129 0.383614 +vt 0.039644 0.041112 +vt 0.504894 0.178152 +vt 0.267424 0.013802 +vt 1.000000 0.767032 +vt 0.980129 0.945086 +vt 0.980031 0.739624 +vt 0.980129 0.109730 +vt 0.900940 0.246672 +vt 0.692933 0.013802 +vt 0.999902 0.000000 +vt 0.980129 1.000000 +vt 0.999902 0.301488 +vt 0.980129 0.000000 +vt 0.554327 0.602682 +vt 0.980031 0.849256 +vt 0.356597 0.383712 +vt 0.376272 0.424824 +vt 0.267424 0.000098 +vt 0.970145 0.986198 +vt 0.514781 0.027506 +vt 0.801879 0.315192 +vn -0.6155 -0.6156 -0.4922 +vn 1.0000 0.0000 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.6046 -0.6048 -0.5183 +vn 0.5915 0.5724 0.5679 +vn 0.7618 0.5233 0.3818 +vn 0.6399 0.6193 0.4549 +vn -0.6628 -0.5852 -0.4673 +vn -0.4770 -0.6674 -0.5719 +vn -0.6637 -0.5565 -0.4999 +vn -0.7228 -0.4019 -0.5621 +vn -0.6513 -0.5738 -0.4965 +vn -0.0000 0.0000 1.0000 +vn -0.4873 -0.7451 0.4555 +vn -0.6848 -0.7274 -0.0444 +vn -0.7293 -0.5105 -0.4556 +vn -0.7271 -0.4791 -0.4916 +vn 0.5830 0.5646 0.5843 +vn 0.0001 0.0002 1.0000 +vn 0.0000 0.0002 1.0000 +vn -0.4477 -0.8942 0.0000 +vn -0.5805 -0.6458 -0.4959 +vn -0.6087 -0.6186 -0.4968 +vn -0.6184 -0.6097 -0.4957 +vn -0.7722 -0.6348 -0.0265 +vn -0.8213 -0.4852 0.3000 +vn -0.7784 -0.5449 -0.3117 +vn -0.0008 -0.0005 1.0000 +vn -0.4144 -0.3898 0.8224 +vn -0.8945 -0.4470 0.0000 +vn -0.7770 -0.3883 -0.4955 +vn -0.4977 -0.7122 -0.4950 +vn -0.5657 -0.8084 0.1624 +vn -0.6176 -0.7712 -0.1543 +vn -0.5733 -0.6517 -0.4965 +vn -0.4464 -0.7199 -0.5315 +vn -0.5430 -0.6781 -0.4954 +vn -0.5294 -0.6874 -0.4972 +vn -0.2292 -0.7831 -0.5781 +vn 0.7729 -0.4916 -0.4012 +vn 0.4446 -0.7378 -0.5079 +vn -0.6127 0.6129 -0.4989 +vn -0.7894 0.0000 -0.6138 +vn -0.8200 0.0000 -0.5723 +vn -0.0027 1.0000 -0.0019 +vn -0.7053 0.5216 -0.4801 +vn -0.4527 -0.7369 -0.5020 +vn -0.4477 -0.8942 -0.0048 +vn -0.1362 -0.8228 -0.5518 +vn -0.7719 -0.3377 -0.5387 +vn -0.7221 -0.4837 -0.4946 +vn -0.7007 -0.5115 -0.4973 +vn -0.6792 -0.5402 -0.4969 +vn -0.6546 -0.5708 -0.4957 +vn -0.6631 -0.5669 -0.4888 +vn -0.6893 -0.5317 -0.4921 +vn -0.6905 -0.5266 -0.4960 +vn -0.6447 -0.6620 -0.3823 +vn -0.6336 -0.6161 -0.4679 +vn -0.5855 -0.6428 -0.4940 +usemtl None +s off +f 1194/1175/1692 1200/1176/1692 1210/1177/1692 +f 1177/1178/1693 1176/1179/1693 1179/1180/1693 +f 1179/1180/1694 1178/1181/1694 1180/1182/1694 +f 1178/1181/1694 1179/1180/1694 1189/1183/1694 +f 1179/1180/1693 1176/1179/1693 1189/1183/1693 +f 1187/1184/1695 1181/1185/1695 1189/1183/1695 +f 1179/1180/1694 1180/1182/1694 1190/1186/1694 +f 1177/1178/1693 1179/1180/1693 1193/1187/1693 +f 1180/1182/1696 1177/1178/1696 1193/1187/1696 +f 1179/1180/1697 1190/1186/1697 1193/1187/1697 +f 1190/1186/1698 1180/1182/1698 1193/1187/1698 +f 1188/1188/1699 1183/1189/1699 1194/1175/1699 +f 1181/1185/1700 1187/1184/1700 1195/1190/1700 +f 1175/1191/1701 1192/1192/1701 1195/1190/1701 +f 1192/1192/1702 1181/1185/1702 1195/1190/1702 +f 1194/1175/1703 1175/1191/1703 1195/1190/1703 +f 1176/1179/1704 1177/1178/1704 1196/1193/1704 +f 1186/1194/1705 1176/1179/1705 1196/1193/1705 +f 1188/1188/1706 1182/1195/1706 1196/1193/1706 +f 1183/1189/1707 1191/1196/1707 1197/1197/1707 +f 1191/1196/1708 1185/1198/1708 1197/1197/1708 +f 1177/1178/1709 1180/1182/1709 1198/1199/1709 +f 1180/1182/1694 1178/1181/1694 1198/1199/1694 +f 1196/1193/1710 1177/1178/1710 1198/1199/1710 +f 1178/1181/1711 1196/1193/1711 1198/1199/1711 +f 1176/1179/1712 1186/1194/1712 1199/1200/1712 +f 1189/1183/1693 1176/1179/1693 1199/1200/1693 +f 1187/1184/1713 1182/1195/1713 1200/1176/1713 +f 1195/1190/1714 1187/1184/1714 1200/1176/1714 +f 1194/1175/1715 1195/1190/1715 1200/1176/1715 +f 1183/1189/1716 1188/1188/1716 1201/1201/1716 +f 1178/1181/1717 1191/1196/1717 1201/1201/1717 +f 1191/1196/1718 1183/1189/1718 1201/1201/1718 +f 1196/1193/1719 1178/1181/1719 1201/1201/1719 +f 1188/1188/1720 1196/1193/1720 1201/1201/1720 +f 1178/1181/1694 1189/1183/1694 1202/1202/1694 +f 1191/1196/1721 1178/1181/1721 1202/1202/1721 +f 1185/1198/1722 1191/1196/1722 1202/1202/1722 +f 1184/1203/1723 1186/1194/1723 1203/1204/1723 +f 1186/1194/1724 1196/1193/1724 1203/1204/1724 +f 1196/1193/1725 1182/1195/1725 1203/1204/1725 +f 1182/1195/1726 1187/1184/1726 1204/1205/1726 +f 1187/1184/1727 1184/1203/1727 1204/1205/1727 +f 1203/1204/1728 1182/1195/1728 1204/1205/1728 +f 1184/1203/1729 1203/1204/1729 1204/1205/1729 +f 1184/1203/1730 1187/1184/1730 1205/1206/1730 +f 1187/1184/1731 1189/1183/1731 1205/1206/1731 +f 1199/1200/1732 1184/1203/1732 1205/1206/1732 +f 1189/1183/1693 1199/1200/1693 1205/1206/1693 +f 1189/1183/1733 1181/1185/1733 1206/1207/1733 +f 1181/1185/1734 1192/1192/1734 1206/1207/1734 +f 1192/1192/1735 1185/1198/1735 1206/1207/1735 +f 1202/1202/1736 1189/1183/1736 1206/1207/1736 +f 1185/1198/1737 1202/1202/1737 1206/1207/1737 +f 1186/1194/1738 1184/1203/1738 1207/1208/1738 +f 1199/1200/1739 1186/1194/1739 1207/1208/1739 +f 1184/1203/1740 1199/1200/1740 1207/1208/1740 +f 1185/1198/1741 1192/1192/1741 1208/1209/1741 +f 1197/1197/1742 1185/1198/1742 1208/1209/1742 +f 1192/1192/1743 1197/1197/1743 1208/1209/1743 +f 1192/1192/1744 1175/1191/1744 1209/1210/1744 +f 1175/1191/1745 1194/1175/1745 1209/1210/1745 +f 1194/1175/1746 1183/1189/1746 1209/1210/1746 +f 1183/1189/1747 1197/1197/1747 1209/1210/1747 +f 1197/1197/1748 1192/1192/1748 1209/1210/1748 +f 1182/1195/1749 1188/1188/1749 1210/1177/1749 +f 1188/1188/1750 1194/1175/1750 1210/1177/1750 +f 1200/1176/1751 1182/1195/1751 1210/1177/1751 +o Bowl_hull_38 +v -0.039240 -0.047428 0.011009 +v -0.025879 -0.078894 0.050235 +v -0.025879 -0.075009 0.050235 +v -0.025879 -0.040094 -0.011846 +v -0.041826 -0.040098 0.012735 +v -0.042259 -0.071993 0.049797 +v -0.025879 -0.040531 -0.004511 +v -0.041395 -0.067679 0.050235 +v -0.042259 -0.040531 0.005837 +v -0.026310 -0.052601 0.006263 +v -0.031483 -0.076737 0.048503 +v -0.027603 -0.042251 -0.008395 +v -0.042259 -0.059065 0.030394 +v -0.040965 -0.072426 0.048934 +v -0.042259 -0.066821 0.049366 +v -0.026310 -0.078894 0.048940 +v -0.032344 -0.040960 -0.005374 +v -0.042259 -0.040098 0.012735 +v -0.035361 -0.072856 0.045057 +v -0.025879 -0.062077 0.021345 +v -0.034929 -0.075875 0.050235 +v -0.042259 -0.040098 0.005837 +v -0.025879 -0.040094 -0.005374 +v -0.026310 -0.062077 0.021345 +v -0.040965 -0.062939 0.034708 +v -0.042259 -0.047428 0.014454 +v -0.026310 -0.048723 0.000228 +v -0.041395 -0.040098 0.012303 +v -0.036655 -0.040531 -0.001060 +v -0.025879 -0.040964 -0.011415 +v -0.042259 -0.071993 0.050235 +v -0.027171 -0.045700 -0.003655 +v -0.041826 -0.066821 0.049366 +v -0.041826 -0.056049 0.025654 +vt 0.680403 0.488939 +vt 0.423649 0.189017 +vt 0.604052 0.411218 +vt 1.000000 0.899863 +vt 1.000000 1.000000 +vt 0.000000 0.000000 +vt 0.118148 0.011257 +vt 1.000000 0.710944 +vt 0.992952 0.822142 +vt 0.284847 0.011257 +vt 0.979052 0.833301 +vt 0.986002 0.688821 +vt 0.395948 0.000098 +vt 0.395948 0.000098 +vt 0.972103 0.944401 +vt 0.916601 0.844362 +vt 0.534652 0.566562 +vt 0.979150 1.000000 +vt 1.000000 0.922181 +vt 0.284847 0.000098 +vt 0.104248 0.000000 +vt 0.534652 0.566562 +vt 0.291699 0.322337 +vt 0.055599 0.055599 +vt 0.749902 0.588782 +vt 0.194499 0.222396 +vt 0.388998 0.000098 +vt 0.104248 0.022318 +vt 0.368148 0.189017 +vt 0.173747 0.011257 +vt 0.006950 0.022416 +vt 1.000000 0.822142 +vt 0.131950 0.144479 +vt 0.986002 0.688821 +vn -0.6386 -0.6215 -0.4538 +vn 1.0000 0.0000 0.0000 +vn -0.0000 -0.0000 1.0000 +vn -1.0000 -0.0000 0.0000 +vn -0.5439 -0.6983 -0.4653 +vn 0.0000 0.8079 0.5894 +vn -0.3836 -0.7971 -0.4663 +vn 0.8337 -0.4773 -0.2778 +vn -0.4443 -0.8652 -0.2322 +vn -0.3978 -0.8375 -0.3746 +vn -0.3147 -0.9434 0.1049 +vn -0.3536 -0.8998 -0.2557 +vn -0.0002 1.0000 0.0000 +vn 0.0000 1.0000 0.0002 +vn -0.2979 -0.8151 -0.4968 +vn -0.3596 -0.7901 -0.4964 +vn -0.3537 -0.7933 -0.4956 +vn 0.0000 -0.8468 -0.5320 +vn 0.0000 -0.8539 -0.5204 +vn -0.4908 -0.7163 -0.4960 +vn -0.5394 -0.7005 -0.4672 +vn -0.3986 -0.7716 -0.4958 +vn -0.4018 -0.7700 -0.4956 +vn 0.3888 -0.7751 -0.4981 +vn 0.4799 0.7345 0.4798 +vn 0.5152 0.7252 0.4567 +vn 0.4573 0.7934 0.4016 +vn 0.0018 1.0000 0.0018 +vn -0.5637 -0.6593 -0.4975 +vn -0.7074 0.0000 -0.7068 +vn -0.7761 0.0000 -0.6306 +vn -0.4420 0.7982 -0.4093 +vn -0.5670 -0.6570 -0.4969 +vn -0.6096 -0.6189 -0.4954 +vn -0.6419 -0.3408 -0.6869 +vn -0.5335 -0.6243 -0.5706 +vn 0.4458 -0.7524 -0.4849 +vn -0.6373 0.1277 0.7600 +vn -0.4680 -0.8837 0.0000 +vn -0.4562 -0.7388 -0.4960 +vn -0.4496 -0.7431 -0.4956 +vn -0.4233 -0.7580 -0.4963 +vn -0.3514 -0.7720 -0.5297 +vn -0.3369 -0.7777 -0.5308 +vn 0.3574 0.7545 0.5504 +vn 0.3530 0.7473 0.5629 +vn 0.0000 0.7114 0.7027 +vn -0.5014 -0.7085 -0.4966 +vn -0.5399 -0.6802 -0.4958 +vn -0.5082 -0.7032 -0.4973 +vn -0.5607 -0.6665 -0.4914 +usemtl None +s off +f 1223/1211/1752 1236/1212/1752 1244/1213/1752 +f 1213/1214/1753 1212/1215/1753 1214/1216/1753 +f 1213/1214/1753 1214/1216/1753 1217/1217/1753 +f 1212/1215/1754 1213/1214/1754 1218/1218/1754 +f 1216/1219/1755 1219/1220/1755 1223/1211/1755 +f 1216/1219/1756 1223/1211/1756 1224/1221/1756 +f 1219/1220/1755 1216/1219/1755 1225/1222/1755 +f 1225/1222/1757 1215/1223/1757 1228/1224/1757 +f 1219/1220/1755 1225/1222/1755 1228/1224/1755 +f 1221/1225/1758 1224/1221/1758 1229/1226/1758 +f 1214/1216/1753 1212/1215/1753 1230/1227/1753 +f 1212/1215/1759 1226/1228/1759 1230/1227/1759 +f 1212/1215/1754 1218/1218/1754 1231/1229/1754 +f 1216/1219/1760 1224/1221/1760 1231/1229/1760 +f 1224/1221/1761 1221/1225/1761 1231/1229/1761 +f 1226/1228/1762 1212/1215/1762 1231/1229/1762 +f 1221/1225/1763 1226/1228/1763 1231/1229/1763 +f 1228/1224/1764 1214/1216/1764 1232/1230/1764 +f 1219/1220/1755 1228/1224/1755 1232/1230/1755 +f 1217/1217/1753 1214/1216/1753 1233/1231/1753 +f 1214/1216/1764 1228/1224/1764 1233/1231/1764 +f 1228/1224/1765 1215/1223/1765 1233/1231/1765 +f 1226/1228/1766 1221/1225/1766 1234/1232/1766 +f 1229/1226/1767 1220/1233/1767 1234/1232/1767 +f 1221/1225/1768 1229/1226/1768 1234/1232/1768 +f 1220/1233/1769 1230/1227/1769 1234/1232/1769 +f 1230/1227/1770 1226/1228/1770 1234/1232/1770 +f 1223/1211/1771 1222/1234/1771 1235/1235/1771 +f 1224/1221/1772 1223/1211/1772 1235/1235/1772 +f 1223/1211/1755 1219/1220/1755 1236/1212/1755 +f 1220/1233/1773 1229/1226/1773 1237/1236/1773 +f 1229/1226/1774 1224/1221/1774 1237/1236/1774 +f 1230/1227/1775 1220/1233/1775 1237/1236/1775 +f 1215/1223/1776 1213/1214/1776 1238/1237/1776 +f 1213/1214/1777 1217/1217/1777 1238/1237/1777 +f 1217/1217/1778 1233/1231/1778 1238/1237/1778 +f 1233/1231/1779 1215/1223/1779 1238/1237/1779 +f 1227/1238/1780 1211/1239/1780 1239/1240/1780 +f 1214/1216/1781 1227/1238/1781 1239/1240/1781 +f 1219/1220/1782 1232/1230/1782 1239/1240/1782 +f 1232/1230/1783 1214/1216/1783 1239/1240/1783 +f 1211/1239/1784 1236/1212/1784 1239/1240/1784 +f 1236/1212/1785 1219/1220/1785 1239/1240/1785 +f 1227/1238/1786 1214/1216/1786 1240/1241/1786 +f 1222/1234/1787 1227/1238/1787 1240/1241/1787 +f 1214/1216/1753 1230/1227/1753 1240/1241/1753 +f 1230/1227/1788 1237/1236/1788 1240/1241/1788 +f 1218/1218/1789 1225/1222/1789 1241/1242/1789 +f 1225/1222/1755 1216/1219/1755 1241/1242/1755 +f 1231/1229/1754 1218/1218/1754 1241/1242/1754 +f 1216/1219/1790 1231/1229/1790 1241/1242/1790 +f 1235/1235/1791 1222/1234/1791 1242/1243/1791 +f 1224/1221/1792 1235/1235/1792 1242/1243/1792 +f 1237/1236/1793 1224/1221/1793 1242/1243/1793 +f 1222/1234/1794 1240/1241/1794 1242/1243/1794 +f 1240/1241/1795 1237/1236/1795 1242/1243/1795 +f 1213/1214/1796 1215/1223/1796 1243/1244/1796 +f 1218/1218/1797 1213/1214/1797 1243/1244/1797 +f 1215/1223/1757 1225/1222/1757 1243/1244/1757 +f 1225/1222/1798 1218/1218/1798 1243/1244/1798 +f 1222/1234/1799 1223/1211/1799 1244/1213/1799 +f 1211/1239/1800 1227/1238/1800 1244/1213/1800 +f 1227/1238/1801 1222/1234/1801 1244/1213/1801 +f 1236/1212/1802 1211/1239/1802 1244/1213/1802 +o Bowl_hull_39 +v -0.024582 -0.059067 0.015314 +v -0.013376 -0.081912 0.050235 +v -0.013376 -0.078461 0.050235 +v -0.013376 -0.040094 -0.021331 +v -0.025445 -0.040528 -0.004946 +v -0.025877 -0.075441 0.050235 +v -0.013376 -0.040528 -0.013996 +v -0.025877 -0.078457 0.048070 +v -0.025877 -0.040962 -0.011839 +v -0.014237 -0.042681 -0.017877 +v -0.013807 -0.080185 0.045919 +v -0.021996 -0.080185 0.048932 +v -0.025014 -0.075011 0.049793 +v -0.013376 -0.078032 0.049800 +v -0.025877 -0.040098 -0.005807 +v -0.020703 -0.040528 -0.017016 +v -0.013807 -0.054327 0.001520 +v -0.025014 -0.040098 -0.005807 +v -0.025877 -0.079321 0.050235 +v -0.025877 -0.050876 0.003244 +v -0.017686 -0.081478 0.049366 +v -0.025877 -0.040098 -0.012273 +v -0.013376 -0.040958 -0.020896 +v -0.013376 -0.081912 0.048939 +v -0.015963 -0.041821 -0.018304 +v -0.025445 -0.072424 0.037723 +v -0.013376 -0.040094 -0.014858 +v -0.025877 -0.073287 0.047208 +v -0.020271 -0.044842 -0.010550 +v -0.025877 -0.065956 0.027384 +vt 0.042287 0.041308 +vt 0.825176 0.773101 +vt 0.680697 0.618442 +vt 1.000000 0.917482 +vt 1.000000 1.000000 +vt 0.000000 0.000000 +vt 1.000000 0.845243 +vt 0.102486 0.010376 +vt 0.969753 0.917384 +vt 0.132635 0.020752 +vt 0.993833 0.834965 +vt 0.993931 0.907204 +vt 0.216915 0.000098 +vt 0.981793 0.958692 +vt 0.048258 0.061864 +vt 0.319303 0.340348 +vt 0.228955 0.010376 +vt 0.216915 0.000098 +vt 1.000000 0.938039 +vt 0.343383 0.257831 +vt 0.060298 0.010376 +vt 0.939702 0.958692 +vt 0.987862 0.989624 +vt 0.126566 0.000098 +vt 0.006069 0.020654 +vt 0.981891 1.000000 +vt 0.090446 0.000000 +vt 0.957713 0.793755 +vt 0.512040 0.453700 +vt 0.150646 0.113547 +vn -0.3055 -0.8129 -0.4957 +vn 1.0000 0.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn -1.0000 -0.0000 0.0000 +vn 0.1362 0.5634 0.8149 +vn 0.1810 0.6990 0.6918 +vn -0.2356 -0.8355 -0.4964 +vn 0.2136 0.8273 0.5195 +vn 0.3621 0.8036 0.4724 +vn 0.2144 0.8272 0.5194 +vn 0.0000 0.8948 0.4464 +vn -0.3144 -0.8817 -0.3518 +vn -0.4324 -0.7535 -0.4953 +vn -0.1570 -0.8534 -0.4970 +vn -0.2035 -0.8444 -0.4957 +vn -0.1802 -0.8695 0.4599 +vn -0.2677 -0.9486 -0.1685 +vn -0.0003 1.0000 0.0000 +vn -0.6504 -0.3413 -0.6786 +vn -0.2776 0.8812 -0.3827 +vn -0.4469 -0.4019 -0.7992 +vn -0.0823 -0.8552 -0.5116 +vn 0.4075 -0.7877 -0.4620 +vn 0.0621 -0.8625 -0.5023 +vn -0.1002 -0.9950 -0.0000 +vn -0.1347 -0.8682 -0.4775 +vn -0.3582 -0.7180 -0.5968 +vn -0.2673 -0.8021 -0.5341 +vn -0.2566 -0.8298 -0.4956 +vn -0.2594 -0.8295 -0.4946 +vn -0.2856 -0.8199 -0.4962 +vn 0.3299 0.8431 0.4246 +vn 0.0000 1.0000 0.0005 +vn 0.0950 0.8426 0.5301 +vn -0.1087 0.8100 0.5763 +vn -0.2103 0.8287 0.5188 +vn -0.3694 -0.7869 -0.4943 +vn -0.3794 -0.7811 -0.4959 +vn -0.3311 -0.8024 -0.4965 +vn -0.3522 -0.7892 -0.5031 +vn -0.3922 -0.7802 -0.4874 +vn -0.3138 -0.8097 -0.4958 +vn -0.3981 -0.7851 -0.4745 +usemtl None +s off +f 1269/1245/1803 1270/1246/1803 1274/1247/1803 +f 1247/1248/1804 1246/1249/1804 1248/1250/1804 +f 1246/1249/1805 1247/1248/1805 1250/1251/1805 +f 1247/1248/1804 1248/1250/1804 1251/1252/1804 +f 1252/1253/1806 1250/1251/1806 1253/1254/1806 +f 1250/1251/1807 1247/1248/1807 1257/1255/1807 +f 1247/1248/1804 1251/1252/1804 1258/1256/1804 +f 1257/1255/1808 1247/1248/1808 1258/1256/1808 +f 1253/1254/1806 1250/1251/1806 1259/1257/1806 +f 1256/1258/1809 1254/1259/1809 1261/1260/1809 +f 1249/1261/1810 1257/1255/1810 1262/1262/1810 +f 1258/1256/1811 1251/1252/1811 1262/1262/1811 +f 1257/1255/1812 1258/1256/1812 1262/1262/1812 +f 1259/1257/1813 1249/1261/1813 1262/1262/1813 +f 1246/1249/1805 1250/1251/1805 1263/1263/1805 +f 1250/1251/1806 1252/1253/1806 1263/1263/1806 +f 1252/1253/1814 1256/1258/1814 1263/1263/1814 +f 1252/1253/1806 1253/1254/1806 1264/1264/1806 +f 1253/1254/1815 1260/1265/1815 1264/1264/1815 +f 1261/1260/1816 1255/1266/1816 1265/1267/1816 +f 1256/1258/1817 1261/1260/1817 1265/1267/1817 +f 1246/1249/1818 1263/1263/1818 1265/1267/1818 +f 1263/1263/1819 1256/1258/1819 1265/1267/1819 +f 1259/1257/1820 1248/1250/1820 1266/1268/1820 +f 1253/1254/1806 1259/1257/1806 1266/1268/1806 +f 1260/1265/1821 1253/1254/1821 1266/1268/1821 +f 1248/1250/1822 1260/1265/1822 1266/1268/1822 +f 1248/1250/1804 1246/1249/1804 1267/1269/1804 +f 1260/1265/1823 1248/1250/1823 1267/1269/1823 +f 1261/1260/1824 1254/1259/1824 1267/1269/1824 +f 1261/1260/1825 1267/1269/1825 1268/1270/1825 +f 1255/1266/1826 1261/1260/1826 1268/1270/1826 +f 1246/1249/1827 1265/1267/1827 1268/1270/1827 +f 1265/1267/1828 1255/1266/1828 1268/1270/1828 +f 1267/1269/1804 1246/1249/1804 1268/1270/1804 +f 1260/1265/1829 1267/1269/1829 1269/1245/1829 +f 1267/1269/1830 1254/1259/1830 1269/1245/1830 +f 1254/1259/1831 1256/1258/1831 1270/1246/1831 +f 1256/1258/1832 1252/1253/1832 1270/1246/1832 +f 1269/1245/1833 1254/1259/1833 1270/1246/1833 +f 1251/1252/1804 1248/1250/1804 1271/1271/1804 +f 1248/1250/1820 1259/1257/1820 1271/1271/1820 +f 1262/1262/1834 1251/1252/1834 1271/1271/1834 +f 1259/1257/1835 1262/1262/1835 1271/1271/1835 +f 1257/1255/1836 1249/1261/1836 1272/1272/1836 +f 1250/1251/1837 1257/1255/1837 1272/1272/1837 +f 1249/1261/1838 1259/1257/1838 1272/1272/1838 +f 1259/1257/1806 1250/1251/1806 1272/1272/1806 +f 1245/1273/1839 1264/1264/1839 1273/1274/1839 +f 1264/1264/1840 1260/1265/1840 1273/1274/1840 +f 1269/1245/1841 1245/1273/1841 1273/1274/1841 +f 1260/1265/1842 1269/1245/1842 1273/1274/1842 +f 1264/1264/1843 1245/1273/1843 1274/1247/1843 +f 1252/1253/1806 1264/1264/1806 1274/1247/1806 +f 1245/1273/1844 1269/1245/1844 1274/1247/1844 +f 1270/1246/1845 1252/1253/1845 1274/1247/1845 diff --git a/cram_boxy/cram_boxy_assembly_demo/resource/bowl.stl b/cram_3d_world/cram_bullet_reasoning/resource/bowl_non_compound.stl similarity index 100% rename from cram_boxy/cram_boxy_assembly_demo/resource/bowl.stl rename to cram_3d_world/cram_bullet_reasoning/resource/bowl_non_compound.stl diff --git a/cram_3d_world/cram_bullet_reasoning/resource/bowl_compound.dae b/cram_3d_world/cram_bullet_reasoning/resource/bowl_round.dae similarity index 100% rename from cram_3d_world/cram_bullet_reasoning/resource/bowl_compound.dae rename to cram_3d_world/cram_bullet_reasoning/resource/bowl_round.dae diff --git a/cram_3d_world/cram_bullet_reasoning/resource/bowl.stl b/cram_3d_world/cram_bullet_reasoning/resource/bowl_round.stl similarity index 100% rename from cram_3d_world/cram_bullet_reasoning/resource/bowl.stl rename to cram_3d_world/cram_bullet_reasoning/resource/bowl_round.stl diff --git a/cram_3d_world/cram_bullet_reasoning/resource/cup_jeroen.obj b/cram_3d_world/cram_bullet_reasoning/resource/cup_jeroen.obj new file mode 100644 index 0000000000..6f38a826b1 --- /dev/null +++ b/cram_3d_world/cram_bullet_reasoning/resource/cup_jeroen.obj @@ -0,0 +1,4111 @@ +# Blender v2.83.4 OBJ File: '' +# www.blender.org +mtllib cup_33.mtl +o Cup_hull_1 +v 0.014889 0.020425 -0.050166 +v -0.014857 -0.020390 -0.048198 +v -0.015384 -0.020122 -0.048198 +v 0.014889 0.020425 -0.048198 +v 0.019895 -0.015647 -0.050166 +v -0.020386 0.014891 -0.050166 +v -0.015648 0.019893 -0.048198 +v 0.020427 -0.014856 -0.048198 +v -0.015384 -0.020122 -0.050166 +v -0.020390 -0.014856 -0.048198 +v 0.020423 0.014891 -0.050166 +v 0.014893 -0.020390 -0.048198 +v -0.014857 0.020425 -0.050166 +v 0.020423 0.014891 -0.048198 +v 0.014893 -0.020390 -0.050166 +v -0.020390 -0.014856 -0.050166 +v -0.020386 0.014891 -0.048198 +v 0.020427 -0.014856 -0.050166 +v -0.014857 0.020425 -0.048198 +v -0.014857 -0.020390 -0.050166 +v 0.018577 0.017260 -0.048198 +v -0.018808 0.016997 -0.050166 +v 0.016999 -0.018807 -0.048198 +v -0.019072 -0.016702 -0.048198 +v 0.017258 0.018579 -0.050166 +v -0.016702 -0.019071 -0.050166 +v -0.018808 0.016997 -0.048198 +v 0.016999 -0.018807 -0.050166 +v -0.016966 0.018839 -0.050166 +v 0.018840 -0.016966 -0.048198 +v -0.019072 -0.016702 -0.050166 +vt 0.090348 0.032302 +vt 0.032302 0.090348 +vt 0.032302 0.090348 +vt 0.122651 0.006558 +vt 0.135572 0.000000 +vt 0.864330 1.000000 +vt 0.864330 1.000000 +vt 0.986981 0.116190 +vt 0.000098 0.864428 +vt 0.116190 0.986981 +vt 1.000000 0.135572 +vt 0.122651 0.006558 +vt 0.000000 0.135572 +vt 0.999902 0.864428 +vt 0.864428 0.000000 +vt 0.135572 1.000000 +vt 0.999902 0.864428 +vt 0.864428 0.000000 +vt 0.000000 0.135572 +vt 0.000098 0.864428 +vt 1.000000 0.135572 +vt 0.135572 1.000000 +vt 0.135572 0.000000 +vt 0.954679 0.922475 +vt 0.038763 0.916014 +vt 0.916014 0.038763 +vt 0.922377 0.954777 +vt 0.038763 0.916014 +vt 0.916014 0.038763 +vt 0.083888 0.961139 +vt 0.961139 0.083888 +vn -0.7071 -0.7071 0.0000 +vn 0.0000 0.0000 1.0000 +vn -0.0000 0.0000 -1.0000 +vn -0.4526 -0.8917 0.0000 +vn 0.0000 1.0000 0.0000 +vn 1.0000 0.0001 0.0000 +vn 0.0000 -1.0000 0.0000 +vn -1.0000 0.0001 0.0000 +vn 0.8301 -0.5576 0.0000 +vn -0.5576 0.8301 0.0000 +vn 0.7888 0.6146 0.0000 +vn -0.8002 0.5998 0.0000 +vn 0.6007 -0.7995 0.0000 +vn -0.8137 -0.5813 0.0000 +vn 0.6146 0.7889 0.0000 +vn 0.6495 0.7570 0.0720 +vn 0.7569 0.6495 -0.0720 +vn -0.6232 -0.7820 0.0000 +vn -0.6786 -0.7317 0.0640 +vn -0.6007 0.7990 -0.0258 +vn -0.6745 0.7360 0.0575 +vn -0.7071 0.7071 0.0000 +vn 0.7990 -0.6008 0.0258 +vn 0.7360 -0.6746 -0.0575 +vn 0.7071 -0.7071 0.0000 +usemtl None +s off +f 26/1/1 24/2/1 31/3/1 +f 3/4/2 2/5/2 4/6/2 +f 1/7/3 5/8/3 6/9/3 +f 3/4/2 4/6/2 7/10/2 +f 4/6/2 2/5/2 8/11/2 +f 2/5/4 3/4/4 9/12/4 +f 6/9/3 5/8/3 9/12/3 +f 3/4/2 7/10/2 10/13/2 +f 5/8/3 1/7/3 11/14/3 +f 8/11/2 2/5/2 12/15/2 +f 4/6/5 1/7/5 13/16/5 +f 1/7/3 6/9/3 13/16/3 +f 4/6/2 8/11/2 14/17/2 +f 8/11/6 11/14/6 14/17/6 +f 9/12/3 5/8/3 15/18/3 +f 12/15/7 2/5/7 15/18/7 +f 6/9/3 9/12/3 16/19/3 +f 10/13/8 6/9/8 16/19/8 +f 6/9/8 10/13/8 17/20/8 +f 10/13/2 7/10/2 17/20/2 +f 8/11/9 5/8/9 18/21/9 +f 5/8/3 11/14/3 18/21/3 +f 11/14/6 8/11/6 18/21/6 +f 7/10/2 4/6/2 19/22/2 +f 4/6/5 13/16/5 19/22/5 +f 13/16/10 7/10/10 19/22/10 +f 2/5/4 9/12/4 20/23/4 +f 15/18/7 2/5/7 20/23/7 +f 9/12/3 15/18/3 20/23/3 +f 4/6/2 14/17/2 21/24/2 +f 14/17/11 11/14/11 21/24/11 +f 13/16/3 6/9/3 22/25/3 +f 6/9/12 17/20/12 22/25/12 +f 8/11/2 12/15/2 23/26/2 +f 12/15/13 15/18/13 23/26/13 +f 3/4/2 10/13/2 24/2/2 +f 10/13/14 16/19/14 24/2/14 +f 1/7/15 4/6/15 25/27/15 +f 11/14/3 1/7/3 25/27/3 +f 4/6/16 21/24/16 25/27/16 +f 21/24/17 11/14/17 25/27/17 +f 9/12/18 3/4/18 26/1/18 +f 16/19/3 9/12/3 26/1/3 +f 3/4/19 24/2/19 26/1/19 +f 17/20/2 7/10/2 27/28/2 +f 22/25/12 17/20/12 27/28/12 +f 15/18/3 5/8/3 28/29/3 +f 23/26/13 15/18/13 28/29/13 +f 7/10/20 13/16/20 29/30/20 +f 13/16/3 22/25/3 29/30/3 +f 27/28/21 7/10/21 29/30/21 +f 22/25/22 27/28/22 29/30/22 +f 5/8/23 8/11/23 30/31/23 +f 8/11/2 23/26/2 30/31/2 +f 28/29/24 5/8/24 30/31/24 +f 23/26/25 28/29/25 30/31/25 +f 24/2/14 16/19/14 31/3/14 +f 16/19/3 26/1/3 31/3/3 +o Cup_hull_2 +v 0.020427 0.005943 -0.048198 +v 0.013054 0.012263 0.015036 +v 0.013317 0.011736 0.013909 +v 0.020427 0.012526 0.015036 +v 0.013054 0.012526 -0.048198 +v 0.017003 0.005943 0.015036 +v 0.020427 0.012526 -0.048198 +v 0.016740 0.006206 -0.048198 +v 0.020427 0.005943 0.015036 +v 0.013054 0.012526 0.015036 +v 0.013317 0.011736 -0.048198 +v 0.017003 0.005943 -0.048198 +v 0.016740 0.006206 0.015036 +v 0.013054 0.012263 -0.048198 +vt 1.000000 0.000000 +vt 1.000000 0.035732 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 0.000000 0.535683 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.499951 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 0.017815 0.035732 +vt 1.000000 0.535683 +vt 0.000000 0.499951 +vn 0.0000 0.0000 -1.0000 +vn -0.0000 0.0000 1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.8945 -0.4470 0.0000 +vn -0.8503 -0.5263 0.0000 +vn -0.7073 -0.7069 0.0000 +vn -0.8534 -0.5194 0.0435 +usemtl None +s off +f 36/32/26 42/33/26 45/34/26 +f 35/35/27 33/36/27 37/37/27 +f 35/35/28 32/38/28 38/39/28 +f 32/38/26 36/32/26 38/39/26 +f 36/32/29 35/35/29 38/39/29 +f 36/32/26 32/38/26 39/40/26 +f 32/38/28 35/35/28 40/41/28 +f 35/35/27 37/37/27 40/41/27 +f 37/37/30 32/38/30 40/41/30 +f 33/36/27 35/35/27 41/42/27 +f 35/35/29 36/32/29 41/42/29 +f 36/32/31 33/36/31 41/42/31 +f 34/43/32 33/36/32 42/33/32 +f 36/32/26 39/40/26 42/33/26 +f 39/40/33 34/43/33 42/33/33 +f 32/38/30 37/37/30 43/44/30 +f 39/40/26 32/38/26 43/44/26 +f 37/37/34 39/40/34 43/44/34 +f 33/36/35 34/43/35 44/45/35 +f 37/37/27 33/36/27 44/45/27 +f 34/43/33 39/40/33 44/45/33 +f 39/40/34 37/37/34 44/45/34 +f 33/36/31 36/32/31 45/34/31 +f 42/33/32 33/36/32 45/34/32 +o Cup_hull_3 +v -0.012229 0.013316 -0.048198 +v -0.020392 0.007259 0.015036 +v -0.016442 0.007259 0.015036 +v -0.020392 0.013316 0.015036 +v -0.020392 0.007259 -0.048198 +v -0.020392 0.013316 -0.048198 +v -0.012229 0.013316 0.015036 +v -0.016442 0.007259 -0.048198 +v -0.012229 0.013053 0.015036 +v -0.012229 0.013053 -0.048198 +v -0.016179 0.007523 -0.048198 +v -0.016179 0.007523 0.015036 +vt 1.000000 0.516104 +vt 0.000000 1.000000 +vt 0.000000 0.516104 +vt 0.000000 0.000000 +vt 0.000000 0.483896 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 0.483896 +vt 1.000000 1.000000 +vn 0.8137 -0.5813 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0001 1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.7084 -0.7059 0.0000 +vn 0.0001 0.0000 -1.0000 +usemtl None +s off +f 56/46/36 54/47/36 57/48/36 +f 47/49/37 48/50/37 49/51/37 +f 48/50/38 47/49/38 50/52/38 +f 47/49/39 49/51/39 50/52/39 +f 49/51/40 46/53/40 51/54/40 +f 46/53/41 50/52/41 51/54/41 +f 50/52/39 49/51/39 51/54/39 +f 49/51/37 48/50/37 52/55/37 +f 46/53/40 49/51/40 52/55/40 +f 50/52/41 46/53/41 53/56/41 +f 48/50/38 50/52/38 53/56/38 +f 46/53/42 52/55/42 54/47/42 +f 52/55/37 48/50/37 54/47/37 +f 53/56/41 46/53/41 55/57/41 +f 46/53/42 54/47/42 55/57/42 +f 48/50/43 53/56/43 56/46/43 +f 53/56/44 55/57/44 56/46/44 +f 55/57/36 54/47/36 56/46/36 +f 54/47/37 48/50/37 57/48/37 +f 48/50/43 56/46/43 57/48/43 +o Cup_hull_4 +v 0.017003 0.005679 0.015036 +v 0.020427 0.005943 -0.048198 +v 0.020427 -0.000377 -0.048198 +v 0.017003 0.005943 -0.048198 +v 0.020427 0.005943 0.015036 +v 0.018057 -0.000377 0.015036 +v 0.018057 -0.000377 -0.048198 +v 0.020427 -0.000377 0.015036 +v 0.017003 0.005943 0.015036 +v 0.017003 0.005415 -0.048198 +v 0.017003 0.005415 0.014751 +vt 1.000000 0.916504 +vt 0.000000 0.000000 +vt 0.004503 0.916504 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 1.000000 1.000000 +vt 0.000000 1.000000 +vt 0.000000 0.958203 +vt 1.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vn -0.9839 -0.1790 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.0001 0.0000 -1.0000 +vn -0.9730 -0.1693 0.1567 +usemtl None +s off +f 67/58/45 63/59/45 68/60/45 +f 59/61/46 60/62/46 61/63/46 +f 60/62/47 59/61/47 62/64/47 +f 59/61/48 61/63/48 62/64/48 +f 62/64/49 58/65/49 63/59/49 +f 61/63/46 60/62/46 64/66/46 +f 60/62/50 63/59/50 64/66/50 +f 60/62/47 62/64/47 65/67/47 +f 63/59/50 60/62/50 65/67/50 +f 62/64/49 63/59/49 65/67/49 +f 61/63/51 58/65/51 66/68/51 +f 58/65/49 62/64/49 66/68/49 +f 62/64/48 61/63/48 66/68/48 +f 58/65/51 61/63/51 67/58/51 +f 61/63/52 64/66/52 67/58/52 +f 64/66/45 63/59/45 67/58/45 +f 63/59/53 58/65/53 68/60/53 +f 58/65/51 67/58/51 68/60/51 +o Cup_hull_5 +v -0.002748 -0.025132 0.032181 +v -0.013281 -0.021446 0.050166 +v -0.013017 -0.021708 0.050166 +v 0.000413 -0.024341 0.050166 +v -0.012753 -0.018548 0.032181 +v 0.000413 -0.022761 0.032181 +v -0.013017 -0.021708 0.032181 +v -0.006961 -0.024342 0.050166 +v -0.012753 -0.020392 0.050166 +v 0.000413 -0.025132 0.050166 +v -0.009330 -0.023552 0.032181 +v 0.000413 -0.025132 0.032181 +v 0.000413 -0.024078 0.048477 +v -0.002485 -0.025132 0.050166 +v -0.013281 -0.018548 0.033306 +v -0.005909 -0.024605 0.032181 +v -0.009856 -0.023288 0.050166 +v 0.000413 -0.022761 0.033306 +v -0.013281 -0.021446 0.032181 +v -0.004591 -0.024868 0.050166 +v -0.013017 -0.018548 0.033306 +v -0.013281 -0.020392 0.050166 +v -0.006961 -0.024342 0.034992 +v -0.004591 -0.024868 0.032181 +v -0.008540 -0.023814 0.050166 +v -0.012753 -0.018548 0.032462 +vt 1.000000 0.038567 +vt 0.937451 0.019284 +vt 0.984338 0.038567 +vt 0.000000 0.000000 +vt 0.000000 0.019284 +vt 0.000000 1.000000 +vt 1.000000 0.769186 +vt 1.000000 1.000000 +vt 1.000000 0.019284 +vt 0.000000 0.461531 +vt 0.000000 0.038567 +vt 0.000000 1.000000 +vt 1.000000 0.288567 +vt 1.000000 1.000000 +vt 0.093872 1.000000 +vt 0.000000 0.788371 +vt 1.000000 0.538371 +vt 0.000000 0.250098 +vt 0.937451 1.000000 +vt 1.000000 0.000000 +vt 0.937451 0.000000 +vt 0.000000 0.634593 +vt 0.000000 0.000000 +vt 0.843677 0.461531 +vt 1.000000 0.634593 +vt 0.000000 0.346222 +vn 0.0000 1.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn -0.7047 -0.7095 0.0000 +vn 1.0000 0.0000 0.0000 +vn -0.4471 -0.8945 0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.2842 0.9474 0.1475 +vn -0.4470 -0.8945 0.0000 +vn 0.3048 0.9524 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.8931 0.1628 -0.4193 +vn -0.1242 -0.9923 0.0018 +vn -0.2169 -0.9762 0.0016 +vn 0.2801 0.9547 0.1000 +vn 0.0000 0.9941 0.1087 +vn -0.3164 -0.9486 0.0000 +vn -0.2941 -0.9555 -0.0207 +vn -0.2424 -0.9702 0.0000 +vn -0.1416 -0.9899 0.0000 +vn -0.1962 -0.9806 0.0000 +vn -0.3167 -0.9485 0.0000 +vn -0.3714 -0.9285 0.0027 +vn 0.2990 0.9507 0.0825 +vn 0.2898 0.9528 0.0907 +usemtl None +s off +f 73/69/54 89/70/54 94/71/54 +f 70/72/55 71/73/55 72/74/55 +f 69/75/56 73/69/56 74/76/56 +f 71/73/57 70/72/57 75/77/57 +f 73/69/56 69/75/56 75/77/56 +f 72/74/55 71/73/55 76/78/55 +f 70/72/55 72/74/55 77/79/55 +f 74/76/58 72/74/58 78/80/58 +f 72/74/55 76/78/55 78/80/55 +f 75/77/56 69/75/56 79/81/56 +f 71/73/59 75/77/59 79/81/59 +f 69/75/56 74/76/56 80/82/56 +f 78/80/60 69/75/60 80/82/60 +f 74/76/58 78/80/58 80/82/58 +f 72/74/58 74/76/58 81/83/58 +f 77/79/61 72/74/61 81/83/61 +f 69/75/60 78/80/60 82/84/60 +f 78/80/55 76/78/55 82/84/55 +f 79/81/56 69/75/56 84/85/56 +f 76/78/55 71/73/55 85/86/55 +f 71/73/62 79/81/62 85/86/62 +f 74/76/63 73/69/63 86/87/63 +f 81/83/58 74/76/58 86/87/58 +f 75/77/57 70/72/57 87/88/57 +f 73/69/56 75/77/56 87/88/56 +f 70/72/64 83/89/64 87/88/64 +f 83/89/65 73/69/65 87/88/65 +f 69/75/66 82/84/66 88/90/66 +f 82/84/55 76/78/55 88/90/55 +f 76/78/67 84/85/67 88/90/67 +f 77/79/68 81/83/68 89/70/68 +f 73/69/54 83/89/54 89/70/54 +f 83/89/69 77/79/69 89/70/69 +f 70/72/55 77/79/55 90/91/55 +f 83/89/64 70/72/64 90/91/64 +f 77/79/69 83/89/69 90/91/69 +f 76/78/70 79/81/70 91/92/70 +f 79/81/71 84/85/71 91/92/71 +f 84/85/72 76/78/72 91/92/72 +f 84/85/56 69/75/56 92/93/56 +f 69/75/73 88/90/73 92/93/73 +f 88/90/74 84/85/74 92/93/74 +f 79/81/75 76/78/75 93/94/75 +f 76/78/55 85/86/55 93/94/55 +f 85/86/76 79/81/76 93/94/76 +f 86/87/63 73/69/63 94/71/63 +f 81/83/77 86/87/77 94/71/77 +f 89/70/78 81/83/78 94/71/78 +o Cup_hull_6 +v -0.004591 -0.024868 0.018410 +v -0.013281 -0.021443 0.032177 +v -0.013017 -0.021707 0.032177 +v 0.000413 -0.022497 0.031895 +v -0.013017 -0.012229 0.015037 +v 0.000413 -0.018023 0.015037 +v -0.013281 -0.020390 0.015037 +v -0.013281 -0.018286 0.032177 +v 0.000413 -0.025130 0.032177 +v 0.000413 -0.024868 0.017286 +v -0.005909 -0.024605 0.032177 +v -0.009330 -0.023550 0.018410 +v -0.013017 -0.012756 0.017286 +v 0.000413 -0.020654 0.015037 +v 0.000413 -0.018548 0.018130 +v -0.013017 -0.021707 0.018130 +v -0.013281 -0.012229 0.015037 +v -0.009330 -0.023550 0.032177 +v -0.001695 -0.024341 0.016724 +v -0.002485 -0.025130 0.018410 +v -0.002485 -0.025130 0.032177 +v -0.005382 -0.024341 0.017286 +v -0.013017 -0.018286 0.032177 +v 0.000413 -0.025130 0.017848 +v -0.007751 -0.024077 0.018130 +v 0.000413 -0.022761 0.032177 +v 0.000413 -0.018023 0.015881 +v -0.013017 -0.012493 0.016444 +v -0.008804 -0.020654 0.015037 +v -0.013281 -0.021443 0.017848 +v -0.009068 -0.023288 0.017286 +v -0.005909 -0.024605 0.018410 +v -0.004591 -0.024868 0.032177 +v -0.002485 -0.024604 0.017006 +v -0.010910 -0.022761 0.017848 +v 0.000413 -0.024341 0.016724 +v -0.007751 -0.024077 0.032177 +vt 0.000000 0.288567 +vt 0.819561 0.403876 +vt 0.000000 0.403876 +vt 1.000000 0.019284 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.019284 +vt 0.016448 1.000000 +vt 0.000000 1.000000 +vt 0.868807 1.000000 +vt 0.000000 0.538371 +vt 1.000000 1.000000 +vt 0.819561 1.000000 +vt 0.819561 0.019284 +vt 1.000000 0.000000 +vt 0.868807 0.019284 +vt 0.000000 0.788371 +vt 0.803211 0.788371 +vt 0.803211 0.634593 +vt 0.000000 0.019284 +vt 0.836009 1.000000 +vt 0.803211 0.288567 +vt 0.000000 1.000000 +vt 0.950754 1.000000 +vt 0.917956 0.019284 +vt 1.000000 0.326938 +vt 0.901606 0.846124 +vt 0.836009 0.000000 +vt 0.868807 0.576840 +vt 0.868807 0.307655 +vt 0.803211 0.538371 +vt 0.000000 0.634593 +vt 0.885158 0.788371 +vt 0.836009 0.173160 +vt 0.901606 1.000000 +vn -0.3164 -0.9486 0.0000 +vn 0.0000 0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 1.0000 -0.0000 0.0000 +vn -0.7070 -0.7072 0.0000 +vn -0.6912 0.6814 0.2408 +vn 0.0000 -1.0000 0.0000 +vn -0.1238 -0.9923 0.0000 +vn 0.2885 0.8976 0.3333 +vn 0.0000 0.9375 0.3481 +vn 0.2363 0.7093 0.6641 +vn 0.3961 0.9182 0.0000 +vn 0.3797 0.9008 0.2105 +vn 0.3458 0.8958 0.2794 +vn 0.3704 0.8929 0.2561 +vn 0.0000 0.9828 0.1845 +vn -0.5337 0.8073 0.2518 +vn 0.3813 0.9086 0.1706 +vn -0.0270 -0.4585 -0.8883 +vn 0.0000 -0.4160 -0.9094 +vn -0.4896 -0.8165 -0.3060 +vn -0.2225 -0.7788 -0.5865 +vn -0.2486 -0.8701 -0.4256 +vn -0.1955 -0.9807 0.0000 +vn -0.1861 -0.9335 -0.3064 +vn -0.2756 -0.9613 0.0000 +vn -0.2162 -0.9231 -0.3180 +vn -0.0868 -0.5956 -0.7986 +vn -0.0006 -0.7308 -0.6826 +vn -0.1160 -0.9300 -0.3487 +vn -0.1183 -0.9286 -0.3518 +vn -0.1315 -0.6757 -0.7254 +vn -0.0415 -0.9052 -0.4230 +vn -0.0680 -0.9342 -0.3503 +vn -0.4472 -0.8945 0.0000 +vn -0.4578 -0.8314 -0.3151 +vn -0.4470 -0.8945 0.0000 +vn -0.4469 -0.8946 0.0000 +vn -0.3480 -0.8951 -0.2786 +vn -0.3632 -0.8403 -0.4024 +vn -0.3449 -0.8911 -0.2950 +vn 0.0000 -0.7297 -0.6837 +usemtl None +s off +f 112/95/79 119/96/79 131/97/79 +f 99/98/80 100/99/80 101/100/80 +f 101/100/81 96/101/81 102/102/81 +f 96/101/82 97/103/82 102/102/82 +f 100/99/83 98/104/83 103/105/83 +f 102/102/82 97/103/82 103/105/82 +f 100/99/83 103/105/83 104/106/83 +f 103/105/82 97/103/82 105/107/82 +f 101/100/80 100/99/80 108/108/80 +f 100/99/83 104/106/83 108/108/83 +f 98/104/83 100/99/83 109/109/83 +f 97/103/84 96/101/84 110/110/84 +f 99/98/80 101/100/80 111/111/80 +f 101/100/81 102/102/81 111/111/81 +f 102/102/85 107/112/85 111/111/85 +f 105/107/82 97/103/82 112/95/82 +f 103/105/82 105/107/82 115/113/82 +f 114/114/86 103/105/86 115/113/86 +f 95/115/87 114/114/87 115/113/87 +f 102/102/82 103/105/82 117/116/82 +f 98/104/88 107/112/88 117/116/88 +f 107/112/89 102/102/89 117/116/89 +f 104/106/83 103/105/83 118/117/83 +f 103/105/86 114/114/86 118/117/86 +f 112/95/79 106/118/79 119/96/79 +f 103/105/83 98/104/83 120/119/83 +f 98/104/90 117/116/90 120/119/90 +f 117/116/82 103/105/82 120/119/82 +f 100/99/91 99/98/91 121/120/91 +f 109/109/83 100/99/83 121/120/83 +f 109/109/92 121/120/92 122/121/92 +f 107/112/93 98/104/93 122/121/93 +f 98/104/94 109/109/94 122/121/94 +f 99/98/95 111/111/95 122/121/95 +f 111/111/96 107/112/96 122/121/96 +f 121/120/97 99/98/97 122/121/97 +f 101/100/80 108/108/80 123/122/80 +f 113/123/98 101/100/98 123/122/98 +f 108/108/99 113/123/99 123/122/99 +f 96/101/81 101/100/81 124/124/81 +f 110/110/84 96/101/84 124/124/84 +f 101/100/100 110/110/100 124/124/100 +f 101/100/101 116/125/101 125/126/101 +f 116/125/102 119/96/102 125/126/102 +f 95/115/103 105/107/103 126/127/103 +f 116/125/104 95/115/104 126/127/104 +f 105/107/105 119/96/105 126/127/105 +f 119/96/106 116/125/106 126/127/106 +f 105/107/103 95/115/103 127/128/103 +f 95/115/87 115/113/87 127/128/87 +f 115/113/82 105/107/82 127/128/82 +f 101/100/107 113/123/107 128/129/107 +f 113/123/108 104/106/108 128/129/108 +f 114/114/109 95/115/109 128/129/109 +f 95/115/110 116/125/110 128/129/110 +f 116/125/111 101/100/111 128/129/111 +f 104/106/112 118/117/112 128/129/112 +f 118/117/113 114/114/113 128/129/113 +f 97/103/114 110/110/114 129/130/114 +f 110/110/115 101/100/115 129/130/115 +f 112/95/116 97/103/116 129/130/116 +f 106/118/117 112/95/117 129/130/117 +f 119/96/118 106/118/118 129/130/118 +f 101/100/119 125/126/119 129/130/119 +f 125/126/120 119/96/120 129/130/120 +f 108/108/83 104/106/83 130/131/83 +f 104/106/121 113/123/121 130/131/121 +f 113/123/99 108/108/99 130/131/99 +f 105/107/82 112/95/82 131/97/82 +f 119/96/105 105/107/105 131/97/105 +o Cup_hull_7 +v -0.006700 0.024377 0.032460 +v -0.014335 0.019637 0.050164 +v -0.013806 0.019637 0.050164 +v -0.014335 0.017795 0.032460 +v 0.000413 0.024113 0.050164 +v 0.000413 0.022797 0.032460 +v -0.006700 0.024377 0.050164 +v -0.013806 0.021217 0.032460 +v 0.000413 0.025167 0.032460 +v -0.013017 0.021742 0.050164 +v -0.002222 0.025167 0.050164 +v -0.014070 0.017795 0.033306 +v -0.009855 0.023323 0.032460 +v 0.000413 0.025167 0.050164 +v -0.004328 0.024903 0.032460 +v -0.014335 0.020691 0.032460 +v -0.009855 0.023323 0.050164 +v -0.014335 0.020691 0.050164 +v 0.000413 0.022797 0.033586 +v -0.002222 0.025167 0.032460 +v -0.004328 0.024903 0.050164 +v -0.013017 0.021742 0.032460 +v -0.013806 0.021217 0.050164 +v -0.005646 0.024639 0.050164 +vt 0.000000 0.678543 +vt 1.000000 0.678543 +vt 0.000000 0.589174 +vt 0.000000 0.000000 +vt 0.000000 0.035826 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 1.000000 0.517717 +vt 1.000000 1.000000 +vt 0.000000 0.517717 +vt 1.000000 0.035826 +vt 1.000000 1.000000 +vt 0.000000 0.089370 +vt 0.000000 0.821359 +vt 0.952232 0.017913 +vt 1.000000 0.303739 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.303739 +vt 0.000000 0.000000 +vt 0.936374 1.000000 +vt 1.000000 0.821359 +vt 1.000000 0.089370 +vt 0.000000 0.035826 +vn -0.1960 0.9806 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 -0.9941 0.1086 +vn -0.3146 -0.9441 0.0983 +vn 0.2988 -0.9492 0.0991 +vn 0.3196 -0.9423 -0.0998 +vn -0.3167 0.9485 0.0000 +vn 0.0000 1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.4472 0.8944 0.0000 +vn -0.7056 0.7086 0.0000 +vn 0.3242 -0.9430 0.0749 +vn 0.3265 -0.9452 0.0000 +vn -0.1244 0.9922 0.0000 +vn -0.5540 0.8325 0.0000 +vn -0.2419 0.9703 0.0000 +vn -0.2166 0.9763 -0.0016 +usemtl None +s off +f 152/132/122 146/133/122 155/134/122 +f 133/135/123 134/136/123 136/137/123 +f 135/138/124 132/139/124 137/140/124 +f 133/135/123 136/137/123 138/141/123 +f 132/139/124 135/138/124 139/142/124 +f 137/140/124 132/139/124 140/143/124 +f 136/137/125 137/140/125 140/143/125 +f 133/135/123 138/141/123 141/144/123 +f 138/141/123 136/137/123 142/145/123 +f 134/136/126 133/135/126 143/146/126 +f 133/135/127 135/138/127 143/146/127 +f 136/137/128 134/136/128 143/146/128 +f 135/138/129 137/140/129 143/146/129 +f 138/141/130 132/139/130 144/147/130 +f 132/139/124 139/142/124 144/147/124 +f 136/137/125 140/143/125 145/148/125 +f 142/145/123 136/137/123 145/148/123 +f 140/143/131 142/145/131 145/148/131 +f 140/143/124 132/139/124 146/133/124 +f 135/138/132 133/135/132 147/149/132 +f 139/142/124 135/138/124 147/149/124 +f 141/144/123 138/141/123 148/150/123 +f 138/141/130 144/147/130 148/150/130 +f 144/147/133 141/144/133 148/150/133 +f 133/135/123 141/144/123 149/151/123 +f 147/149/132 133/135/132 149/151/132 +f 139/142/134 147/149/134 149/151/134 +f 137/140/125 136/137/125 150/152/125 +f 136/137/135 143/146/135 150/152/135 +f 143/146/136 137/140/136 150/152/136 +f 142/145/131 140/143/131 151/153/131 +f 140/143/124 146/133/124 151/153/124 +f 146/133/137 142/145/137 151/153/137 +f 138/141/123 142/145/123 152/132/123 +f 142/145/137 146/133/137 152/132/137 +f 139/142/138 141/144/138 153/154/138 +f 144/147/124 139/142/124 153/154/124 +f 141/144/133 144/147/133 153/154/133 +f 141/144/138 139/142/138 154/155/138 +f 149/151/123 141/144/123 154/155/123 +f 139/142/134 149/151/134 154/155/134 +f 132/139/139 138/141/139 155/134/139 +f 146/133/140 132/139/140 155/134/140 +f 138/141/123 152/132/123 155/134/123 +o Cup_hull_8 +v -0.003801 0.024902 0.017846 +v -0.014335 0.017794 0.032458 +v -0.014335 0.020688 0.032458 +v 0.000413 0.022796 0.032458 +v -0.014070 0.011212 0.015036 +v 0.000413 0.018057 0.015036 +v -0.014335 0.020426 0.015036 +v 0.000413 0.025166 0.032458 +v 0.000413 0.024376 0.016722 +v -0.009858 0.023322 0.032458 +v -0.014070 0.011475 0.017004 +v -0.009858 0.023322 0.018409 +v -0.005645 0.024639 0.032458 +v 0.000413 0.018320 0.017285 +v 0.000413 0.022532 0.032179 +v 0.000413 0.020426 0.015036 +v -0.014070 0.017531 0.032179 +v -0.013017 0.021741 0.018409 +v 0.000413 0.025166 0.017846 +v -0.014335 0.011212 0.016161 +v -0.002222 0.025166 0.032458 +v -0.006698 0.024376 0.018128 +v -0.013017 0.021741 0.032458 +v -0.014070 0.011212 0.016161 +v -0.005645 0.024111 0.017004 +v -0.002222 0.025166 0.018409 +v -0.004328 0.024902 0.018409 +v -0.013806 0.021215 0.018128 +v -0.001958 0.024639 0.017004 +v -0.006698 0.024376 0.032458 +v 0.000413 0.018057 0.015880 +v -0.004328 0.024902 0.032458 +v -0.014335 0.011212 0.015036 +v -0.014335 0.020688 0.017285 +v -0.013806 0.021215 0.032458 +v -0.009330 0.023322 0.017565 +vt 0.822516 0.517815 +vt 0.887029 0.589272 +vt 0.854821 0.339370 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.017913 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 0.903182 1.000000 +vt 0.000000 0.303543 +vt 0.000000 0.589272 +vt 0.870876 1.000000 +vt 0.016055 1.000000 +vt 1.000000 1.000000 +vt 0.016055 0.017913 +vt 0.887029 0.017913 +vt 0.806363 0.303543 +vt 0.806363 0.089370 +vt 0.838669 1.000000 +vt 0.935389 0.000000 +vt 0.000000 0.821359 +vt 0.000000 0.089370 +vt 0.935389 0.017913 +vt 0.838669 0.714272 +vt 0.806363 0.821359 +vt 0.806363 0.678543 +vt 0.822516 0.035826 +vt 0.887029 0.839272 +vt 0.000000 0.517815 +vt 0.951542 1.000000 +vt 0.000000 0.678543 +vt 1.000000 0.000000 +vt 0.870876 0.000000 +vt 0.000000 0.035826 +vn -0.2516 0.8624 -0.4393 +vn 0.0000 0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 0.3927 -0.9197 +vn 0.2065 -0.6089 0.7659 +vn 0.3054 -0.8844 0.3530 +vn 0.2437 -0.7058 0.6652 +vn -0.4409 0.8811 -0.1713 +vn -0.4475 0.8943 0.0000 +vn -0.4642 -0.8213 0.3317 +vn -0.2519 -0.8988 0.3587 +vn 0.0000 1.0000 0.0000 +vn -0.3166 0.9486 0.0000 +vn 0.4273 -0.9041 0.0000 +vn 0.3853 -0.8811 0.2743 +vn 0.4112 -0.8771 0.2481 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 -0.9548 0.2972 +vn -0.2012 0.8944 -0.3995 +vn -0.0599 0.9580 -0.2805 +vn -0.1242 0.9923 0.0000 +vn -0.1926 0.9646 -0.1803 +vn -0.2164 0.9763 -0.0020 +vn -0.1234 0.9856 -0.1155 +vn -0.5179 0.8459 -0.1275 +vn -0.5543 0.8323 0.0000 +vn -0.0430 0.5239 -0.8507 +vn -0.0570 0.9105 -0.4095 +vn 0.0223 0.8181 -0.5747 +vn -0.0894 0.6249 -0.7755 +vn -0.1204 0.8415 -0.5266 +vn -0.2415 0.9704 0.0000 +vn 0.4240 -0.8903 0.1661 +vn -0.1964 0.9805 0.0000 +vn -0.7064 0.7078 0.0000 +vn -0.6278 0.7731 -0.0901 +vn -0.3902 0.8877 -0.2442 +vn -0.3262 0.9230 -0.2041 +vn -0.2527 0.8463 -0.4689 +usemtl None +s off +f 177/156/141 180/157/141 191/158/141 +f 158/159/142 157/160/142 159/161/142 +f 161/162/143 160/163/143 162/164/143 +f 157/160/144 158/159/144 162/164/144 +f 158/159/142 159/161/142 163/165/142 +f 159/161/145 161/162/145 163/165/145 +f 163/165/145 161/162/145 164/166/145 +f 158/159/142 163/165/142 165/167/142 +f 165/167/142 163/165/142 168/168/142 +f 161/162/145 159/161/145 169/169/145 +f 169/169/145 159/161/145 170/170/145 +f 161/162/143 162/164/143 171/171/143 +f 164/166/145 161/162/145 171/171/145 +f 162/164/146 164/166/146 171/171/146 +f 159/161/147 157/160/147 172/172/147 +f 166/173/148 170/170/148 172/172/148 +f 170/170/149 159/161/149 172/172/149 +f 167/174/150 162/164/150 173/175/150 +f 165/167/151 167/174/151 173/175/151 +f 163/165/145 164/166/145 174/176/145 +f 157/160/144 162/164/144 175/177/144 +f 172/172/152 157/160/152 175/177/152 +f 166/173/153 172/172/153 175/177/153 +f 168/168/142 163/165/142 176/178/142 +f 163/165/154 174/176/154 176/178/154 +f 167/174/155 165/167/155 177/156/155 +f 158/159/142 165/167/142 178/179/142 +f 165/167/151 173/175/151 178/179/151 +f 160/163/156 161/162/156 179/180/156 +f 170/170/157 166/173/157 179/180/157 +f 169/169/158 170/170/158 179/180/158 +f 175/177/159 160/163/159 179/180/159 +f 166/173/160 175/177/160 179/180/160 +f 177/156/161 156/181/161 180/157/161 +f 174/176/162 156/181/162 181/182/162 +f 176/178/154 174/176/154 181/182/154 +f 176/178/163 181/182/163 182/183/163 +f 156/181/164 177/156/164 182/183/164 +f 177/156/165 168/168/165 182/183/165 +f 181/182/166 156/181/166 182/183/166 +f 173/175/167 162/164/167 183/184/167 +f 178/179/168 173/175/168 183/184/168 +f 164/166/169 162/164/169 184/185/169 +f 156/181/170 174/176/170 184/185/170 +f 174/176/171 164/166/171 184/185/171 +f 162/164/172 180/157/172 184/185/172 +f 180/157/173 156/181/173 184/185/173 +f 165/167/142 168/168/142 185/186/142 +f 177/156/155 165/167/155 185/186/155 +f 168/168/174 177/156/174 185/186/174 +f 161/162/145 169/169/145 186/187/145 +f 179/180/156 161/162/156 186/187/156 +f 169/169/175 179/180/175 186/187/175 +f 168/168/142 176/178/142 187/188/142 +f 176/178/163 182/183/163 187/188/163 +f 182/183/176 168/168/176 187/188/176 +f 162/164/143 160/163/143 188/189/143 +f 160/163/159 175/177/159 188/189/159 +f 175/177/144 162/164/144 188/189/144 +f 162/164/144 158/159/144 189/190/144 +f 158/159/177 183/184/177 189/190/177 +f 183/184/178 162/164/178 189/190/178 +f 158/159/142 178/179/142 190/191/142 +f 183/184/177 158/159/177 190/191/177 +f 178/179/168 183/184/168 190/191/168 +f 162/164/179 167/174/179 191/158/179 +f 167/174/180 177/156/180 191/158/180 +f 180/157/181 162/164/181 191/158/181 +o Cup_hull_9 +v 0.004625 -0.024868 0.026844 +v 0.008313 -0.016178 0.015036 +v 0.007785 -0.016178 0.015036 +v 0.008313 -0.022761 0.050166 +v 0.000413 -0.024077 0.049041 +v 0.000413 -0.018023 0.015036 +v 0.008313 -0.023814 0.017848 +v 0.000413 -0.025132 0.017848 +v 0.004363 -0.024868 0.050166 +v 0.008313 -0.020655 0.015036 +v 0.007785 -0.024077 0.050166 +v 0.000413 -0.025132 0.050166 +v 0.008049 -0.016178 0.016442 +v 0.000413 -0.020655 0.015036 +v 0.000676 -0.024077 0.049884 +v 0.002520 -0.025132 0.018409 +v 0.000413 -0.018023 0.015882 +v 0.001730 -0.024341 0.016724 +v 0.005942 -0.024604 0.018409 +v 0.007785 -0.022761 0.050166 +v 0.002520 -0.025132 0.050166 +v 0.008313 -0.023814 0.050166 +v 0.005679 -0.024077 0.017006 +v 0.004625 -0.024868 0.048477 +v 0.007785 -0.024077 0.018409 +v 0.000413 -0.024341 0.016724 +v 0.008313 -0.023287 0.017006 +v 0.003309 -0.024868 0.017567 +v 0.000940 -0.024077 0.050166 +v 0.008313 -0.016178 0.016442 +vt 0.959965 1.000000 +vt 0.000000 0.264781 +vt 0.959965 1.000000 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.793951 +vt 0.919930 0.147220 +vt 0.032009 0.117756 +vt 0.919930 0.000000 +vt 1.000000 0.500000 +vt 0.000000 0.029464 +vt 0.000000 0.117756 +vt 0.000000 0.000000 +vt 1.000000 0.500000 +vt 0.008027 0.117756 +vt 0.903974 0.000000 +vt 0.975920 0.793951 +vt 0.951938 0.088293 +vt 0.663861 0.029464 +vt 0.903974 0.058927 +vt 0.000000 0.264781 +vt 0.000000 0.000000 +vt 0.000000 0.147220 +vt 0.943911 0.117756 +vt 0.048062 0.029464 +vt 0.903974 0.117756 +vt 0.951938 0.088293 +vt 0.943911 0.206049 +vt 0.927956 0.029464 +vt 0.000000 0.117756 +vn 0.0000 0.9815 0.1916 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn -1.0000 -0.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 1.0000 0.0000 +vn -0.9093 0.3035 0.2846 +vn 0.0000 -1.0000 0.0000 +vn -0.2427 0.9701 0.0000 +vn -0.2377 0.9703 0.0446 +vn -0.4977 0.8532 0.1558 +vn -0.2432 0.9546 0.1719 +vn 0.0000 -0.4164 -0.9092 +vn 0.1524 -0.9883 -0.0071 +vn 0.1244 -0.9922 0.0000 +vn 0.4474 -0.8944 0.0000 +vn 0.0960 -0.5511 -0.8289 +vn 0.2249 -0.9738 0.0349 +vn 0.1964 -0.9805 0.0000 +vn 0.2416 -0.9704 0.0021 +vn 0.1417 -0.9897 0.0220 +vn 0.2697 -0.9439 -0.1905 +vn 0.2747 -0.9615 0.0000 +vn 0.0000 -0.8181 -0.5751 +vn 0.2466 -0.8217 -0.5138 +vn 0.1770 -0.5898 -0.7879 +vn 0.0645 -0.9680 -0.2426 +vn 0.0212 -0.8294 -0.5583 +vn 0.1503 -0.9749 -0.1644 +vn 0.2113 -0.9015 -0.3778 +vn 0.2112 -0.9013 -0.3782 +vn 0.0968 -0.7522 -0.6518 +vn -0.6860 0.3432 0.6416 +vn -0.1968 0.9630 0.1841 +vn -0.1855 0.9647 0.1869 +usemtl None +s off +f 204/192/182 195/193/182 221/194/182 +f 194/195/183 193/196/183 197/197/183 +f 193/196/184 195/193/184 198/198/184 +f 196/199/185 197/197/185 199/200/185 +f 197/197/183 193/196/183 201/201/183 +f 193/196/184 198/198/184 201/201/184 +f 195/193/186 200/202/186 202/203/186 +f 196/199/185 199/200/185 203/204/185 +f 200/202/186 195/193/186 203/204/186 +f 193/196/187 194/195/187 204/192/187 +f 199/200/185 197/197/185 205/205/185 +f 197/197/183 201/201/183 205/205/183 +f 196/199/188 203/204/188 206/206/188 +f 203/204/189 199/200/189 207/207/189 +f 194/195/190 197/197/190 208/208/190 +f 197/197/185 196/199/185 208/208/185 +f 204/192/191 194/195/191 208/208/191 +f 196/199/192 206/206/192 208/208/192 +f 206/206/193 204/192/193 208/208/193 +f 205/205/194 201/201/194 209/209/194 +f 192/210/195 207/207/195 210/211/195 +f 203/204/186 195/193/186 211/212/186 +f 195/193/182 204/192/182 211/212/182 +f 200/202/186 203/204/186 212/213/186 +f 207/207/196 192/210/196 212/213/196 +f 203/204/189 207/207/189 212/213/189 +f 198/198/184 195/193/184 213/214/184 +f 202/203/197 198/198/197 213/214/197 +f 195/193/186 202/203/186 213/214/186 +f 209/209/198 201/201/198 214/215/198 +f 202/203/199 200/202/199 215/216/199 +f 192/210/200 210/211/200 215/216/200 +f 210/211/201 202/203/201 215/216/201 +f 212/213/196 192/210/196 215/216/196 +f 200/202/202 212/213/202 215/216/202 +f 198/198/197 202/203/197 216/217/197 +f 210/211/203 198/198/203 216/217/203 +f 202/203/204 210/211/204 216/217/204 +f 199/200/185 205/205/185 217/218/185 +f 209/209/205 199/200/205 217/218/205 +f 205/205/194 209/209/194 217/218/194 +f 201/201/184 198/198/184 218/219/184 +f 198/198/206 214/215/206 218/219/206 +f 214/215/207 201/201/207 218/219/207 +f 207/207/208 199/200/208 219/220/208 +f 199/200/209 209/209/209 219/220/209 +f 210/211/210 207/207/210 219/220/210 +f 198/198/211 210/211/211 219/220/211 +f 214/215/212 198/198/212 219/220/212 +f 209/209/213 214/215/213 219/220/213 +f 206/206/214 203/204/214 220/221/214 +f 204/192/215 206/206/215 220/221/215 +f 203/204/186 211/212/186 220/221/186 +f 211/212/216 204/192/216 220/221/216 +f 195/193/184 193/196/184 221/194/184 +f 193/196/187 204/192/187 221/194/187 +o Cup_hull_10 +v 0.021743 -0.013016 0.050164 +v 0.025167 -0.000378 0.032460 +v 0.025167 -0.002222 0.032460 +v 0.017793 -0.014070 0.032460 +v 0.024113 -0.000379 0.050164 +v 0.021743 -0.013016 0.032460 +v 0.022796 -0.000379 0.032460 +v 0.019637 -0.014335 0.050164 +v 0.024640 -0.005645 0.050164 +v 0.024113 -0.007750 0.032460 +v 0.025167 -0.000378 0.050164 +v 0.020691 -0.014335 0.032460 +v 0.023323 -0.009856 0.050164 +v 0.019637 -0.013806 0.050164 +v 0.017793 -0.014070 0.033306 +v 0.020691 -0.014335 0.050164 +v 0.022796 -0.000379 0.033586 +v 0.025167 -0.002222 0.050164 +v 0.024903 -0.004328 0.032460 +v 0.023323 -0.009856 0.032460 +v 0.017793 -0.014335 0.032460 +v 0.024113 -0.007750 0.050164 +v 0.021217 -0.013806 0.032460 +v 0.024903 -0.004328 0.050164 +v 0.024640 -0.005645 0.032460 +v 0.021217 -0.013806 0.050164 +vt 0.000000 0.000000 +vt 1.000000 0.037882 +vt 0.000000 0.037882 +vt 1.000000 1.000000 +vt 1.000000 0.867854 +vt 1.000000 0.018990 +vt 1.000000 0.094460 +vt 1.000000 0.999902 +vt 0.000000 0.094460 +vt 0.000000 0.999902 +vt 0.000000 0.000000 +vt 0.000000 0.622651 +vt 1.000000 0.471809 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.320869 +vt 0.000000 0.037882 +vt 0.952232 0.018990 +vt 0.936374 0.999902 +vt 0.000000 0.867854 +vt 1.000000 0.717012 +vt 1.000000 0.320869 +vt 1.000000 0.000000 +vt 0.000000 0.471809 +vt 0.000000 0.717012 +vt 1.000000 0.622651 +vn 0.7093 -0.7049 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 0.0000 1.0000 +vn 1.0000 0.0000 0.0000 +vn -0.0006 1.0000 0.0000 +vn 0.8944 -0.4472 0.0000 +vn -0.9941 0.0000 0.1087 +vn -0.9392 0.3433 0.0000 +vn -0.9441 0.3147 0.0984 +vn 0.0000 -1.0000 0.0000 +vn -0.0013 1.0000 0.0001 +vn -0.9371 0.3410 0.0744 +vn 0.9923 -0.1242 0.0000 +vn 0.9363 -0.3513 0.0000 +vn -0.9444 -0.3139 0.0984 +vn -1.0000 0.0000 0.0000 +vn 0.9701 -0.2428 0.0000 +vn 0.8322 -0.5545 0.0000 +vn 0.9806 -0.1962 0.0000 +usemtl None +s off +f 237/222/217 244/223/217 247/224/217 +f 223/225/218 224/226/218 225/227/218 +f 225/227/218 224/226/218 227/228/218 +f 223/225/218 225/227/218 228/229/218 +f 222/230/219 226/231/219 229/232/219 +f 226/231/219 222/230/219 230/233/219 +f 227/228/218 224/226/218 231/234/218 +f 224/226/220 223/225/220 232/235/220 +f 223/225/221 228/229/221 232/235/221 +f 226/231/219 230/233/219 232/235/219 +f 225/227/218 227/228/218 233/236/218 +f 222/230/222 227/228/222 234/237/222 +f 230/233/219 222/230/219 234/237/219 +f 229/232/219 226/231/219 235/238/219 +f 229/232/223 235/238/223 236/239/223 +f 228/229/224 225/227/224 236/239/224 +f 235/238/225 226/231/225 236/239/225 +f 222/230/219 229/232/219 237/222/219 +f 229/232/226 233/236/226 237/222/226 +f 232/235/221 228/229/221 238/240/221 +f 226/231/227 232/235/227 238/240/227 +f 228/229/224 236/239/224 238/240/224 +f 236/239/228 226/231/228 238/240/228 +f 224/226/220 232/235/220 239/241/220 +f 232/235/219 230/233/219 239/241/219 +f 231/234/218 224/226/218 240/242/218 +f 224/226/229 239/241/229 240/242/229 +f 227/228/218 231/234/218 241/243/218 +f 234/237/222 227/228/222 241/243/222 +f 231/234/230 234/237/230 241/243/230 +f 225/227/218 233/236/218 242/244/218 +f 233/236/226 229/232/226 242/244/226 +f 229/232/231 236/239/231 242/244/231 +f 236/239/232 225/227/232 242/244/232 +f 231/234/233 230/233/233 243/245/233 +f 230/233/219 234/237/219 243/245/219 +f 234/237/230 231/234/230 243/245/230 +f 227/228/234 222/230/234 244/223/234 +f 233/236/218 227/228/218 244/223/218 +f 237/222/217 233/236/217 244/223/217 +f 239/241/219 230/233/219 245/246/219 +f 230/233/235 240/242/235 245/246/235 +f 240/242/229 239/241/229 245/246/229 +f 230/233/233 231/234/233 246/247/233 +f 231/234/218 240/242/218 246/247/218 +f 240/242/235 230/233/235 246/247/235 +f 222/230/219 237/222/219 247/224/219 +f 244/223/234 222/230/234 247/224/234 +o Cup_hull_11 +v 0.024903 -0.004329 0.032460 +v 0.021479 -0.000377 0.016161 +v 0.020426 -0.000379 0.015036 +v 0.020426 -0.014335 0.015036 +v 0.011211 -0.014335 0.016161 +v 0.017530 -0.014071 0.032177 +v 0.022533 -0.000377 0.032177 +v 0.025166 -0.000377 0.017846 +v 0.020690 -0.014335 0.032458 +v 0.018056 -0.000379 0.015036 +v 0.023322 -0.009856 0.018411 +v 0.025166 -0.000377 0.032460 +v 0.011211 -0.014335 0.015036 +v 0.023322 -0.009856 0.032460 +v 0.024375 -0.006699 0.018128 +v 0.018318 -0.000379 0.017285 +v 0.011474 -0.014071 0.017004 +v 0.021743 -0.013016 0.018411 +v 0.024375 -0.000905 0.016724 +v 0.017794 -0.014335 0.032458 +v 0.025166 -0.002222 0.018411 +v 0.024112 -0.007750 0.032460 +v 0.021743 -0.013016 0.032460 +v 0.024375 -0.004329 0.017004 +v 0.011211 -0.014071 0.016161 +v 0.022796 -0.000377 0.032460 +v 0.021216 -0.013807 0.018130 +v 0.024903 -0.004329 0.018411 +v 0.025166 -0.002222 0.032460 +v 0.023586 -0.008277 0.017285 +v 0.018056 -0.000379 0.015880 +v 0.024639 -0.005646 0.032460 +v 0.020690 -0.014335 0.017285 +v 0.011211 -0.014071 0.015036 +v 0.021216 -0.013807 0.032458 +vt 0.822435 0.037784 +vt 0.000000 0.094460 +vt 0.000098 0.037784 +vt 1.000000 0.999902 +vt 0.935395 1.000000 +vt 0.838684 1.000000 +vt 0.016249 1.000000 +vt 0.935395 0.000000 +vt 1.000000 0.000000 +vt 0.000098 0.000000 +vt 1.000000 0.999902 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.716915 +vt 0.000000 0.320869 +vt 0.016249 0.018892 +vt 0.887040 0.018892 +vt 0.806284 0.320869 +vt 0.806284 0.094460 +vt 0.903093 0.962216 +vt 0.000098 0.000000 +vt 0.806284 0.867854 +vt 0.000000 0.471809 +vt 0.822533 0.547083 +vt 0.887040 0.716915 +vt 0.935395 0.018892 +vt 0.870889 0.999902 +vt 0.000000 1.000000 +vt 0.806284 0.716915 +vt 0.000000 0.867854 +vt 0.870889 0.434025 +vt 0.951547 0.999902 +vt 0.000000 0.622553 +vt 0.870889 0.000000 +vt 1.000000 0.018892 +vn 0.8321 -0.5547 0.0000 +vn 0.0010 1.0000 -0.0021 +vn 0.0000 1.0000 -0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 1.0000 -0.0012 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 0.0000 1.0000 +vn -0.8998 -0.2478 0.3591 +vn -0.8795 0.3213 0.3510 +vn 0.8812 -0.4404 -0.1718 +vn 0.8945 -0.4470 0.0000 +vn 0.3931 0.0000 -0.9195 +vn 0.3488 0.7294 -0.5885 +vn -0.8201 -0.4665 0.3313 +vn 1.0000 0.0000 0.0000 +vn 0.9364 -0.3510 0.0000 +vn 0.9484 -0.3169 -0.0058 +vn 0.0000 -0.0013 1.0000 +vn 0.5751 -0.0666 -0.8153 +vn 0.8266 -0.0458 -0.5610 +vn 0.9275 -0.1094 -0.3575 +vn -1.0000 0.0000 0.0000 +vn -0.8684 0.4306 0.2457 +vn -0.9544 0.0000 0.2986 +vn -0.8736 0.4026 0.2734 +vn -0.7070 0.2583 0.6584 +vn -0.6033 0.2161 0.7677 +vn -0.0004 0.0000 1.0000 +vn 0.8456 -0.5183 -0.1275 +vn 0.9923 -0.1242 0.0000 +vn 0.9237 -0.1641 -0.3461 +vn 0.9300 -0.1164 -0.3485 +vn 0.8884 -0.3554 -0.2906 +vn 0.9131 -0.3265 -0.2442 +vn 0.7927 -0.1996 -0.5760 +vn 0.8765 -0.2063 -0.4350 +vn -0.0004 1.0000 0.0000 +vn -0.0010 1.0000 0.0002 +vn -0.8944 0.4472 0.0000 +vn -0.8809 0.4438 0.1644 +vn 0.9700 -0.2431 0.0000 +vn 0.9805 -0.1963 0.0000 +vn 0.9762 -0.2169 -0.0020 +vn 0.7740 -0.6267 -0.0907 +vn 0.7081 -0.7062 0.0000 +vn 0.0065 -0.0065 1.0000 +usemtl None +s off +f 274/248/236 270/249/236 282/250/236 +f 250/251/237 249/252/237 255/253/237 +f 249/252/238 254/254/238 255/253/238 +f 252/255/239 251/256/239 256/257/239 +f 249/252/240 250/251/240 257/258/240 +f 250/251/241 251/256/241 257/258/241 +f 255/253/238 254/254/238 259/259/238 +f 251/256/239 252/255/239 260/260/239 +f 257/258/241 251/256/241 260/260/241 +f 248/261/242 259/259/242 261/262/242 +f 252/255/243 253/263/243 264/264/243 +f 253/263/244 254/254/244 264/264/244 +f 251/256/245 258/265/245 265/266/245 +f 258/265/246 261/262/246 265/266/246 +f 251/256/247 250/251/247 266/267/247 +f 250/251/248 255/253/248 266/267/248 +f 253/263/249 252/255/249 267/268/249 +f 252/255/239 256/257/239 267/268/239 +f 255/253/250 259/259/250 268/269/250 +f 248/261/242 261/262/242 269/270/242 +f 261/262/251 258/265/251 269/270/251 +f 258/265/252 262/271/252 269/270/252 +f 261/262/242 259/259/242 270/249/242 +f 265/266/246 261/262/246 270/249/246 +f 267/268/253 256/257/253 270/249/253 +f 251/256/254 266/267/254 271/272/254 +f 266/267/255 255/253/255 271/272/255 +f 255/253/256 268/269/256 271/272/256 +f 260/260/257 252/255/257 272/273/257 +f 254/254/258 263/274/258 272/273/258 +f 252/255/259 264/264/259 272/273/259 +f 264/264/260 254/254/260 272/273/260 +f 254/254/261 253/263/261 273/275/261 +f 259/259/238 254/254/238 273/275/238 +f 253/263/262 267/268/262 273/275/262 +f 270/249/242 259/259/242 273/275/242 +f 267/268/263 270/249/263 273/275/263 +f 251/256/264 265/266/264 274/248/264 +f 265/266/236 270/249/236 274/248/236 +f 268/269/265 248/261/265 275/276/265 +f 262/271/266 271/272/266 275/276/266 +f 271/272/267 268/269/267 275/276/267 +f 259/259/242 248/261/242 276/277/242 +f 248/261/265 268/269/265 276/277/265 +f 268/269/250 259/259/250 276/277/250 +f 258/265/268 251/256/268 277/278/268 +f 262/271/269 258/265/269 277/278/269 +f 251/256/270 271/272/270 277/278/270 +f 271/272/271 262/271/271 277/278/271 +f 254/254/272 249/252/272 278/279/272 +f 249/252/272 257/258/272 278/279/272 +f 263/274/273 254/254/273 278/279/273 +f 257/258/274 272/273/274 278/279/274 +f 272/273/275 263/274/275 278/279/275 +f 248/261/242 269/270/242 279/280/242 +f 269/270/276 262/271/276 279/280/276 +f 275/276/277 248/261/277 279/280/277 +f 262/271/278 275/276/278 279/280/278 +f 256/257/239 251/256/239 280/281/239 +f 251/256/279 274/248/279 280/281/279 +f 274/248/280 256/257/280 280/281/280 +f 257/258/241 260/260/241 281/282/241 +f 260/260/257 272/273/257 281/282/257 +f 272/273/274 257/258/274 281/282/274 +f 270/249/281 256/257/281 282/250/281 +f 256/257/280 274/248/280 282/250/280 +o Cup_hull_12 +v 0.024903 0.004363 0.050164 +v 0.021217 0.013580 0.032460 +v 0.021481 0.013315 0.032460 +v 0.022796 -0.000377 0.032460 +v 0.020164 0.013052 0.050164 +v 0.018320 0.013315 0.032460 +v 0.025167 0.002257 0.032460 +v 0.024113 -0.000377 0.050164 +v 0.023322 0.009891 0.050164 +v 0.024376 0.006732 0.032460 +v 0.025167 -0.000377 0.032460 +v 0.021217 0.013580 0.050164 +v 0.025167 -0.000377 0.050164 +v 0.018320 0.013315 0.033306 +v 0.023060 0.010417 0.032460 +v 0.021743 0.013052 0.050164 +v 0.022796 -0.000377 0.033586 +v 0.018320 0.013580 0.033306 +v 0.024376 0.006732 0.050164 +v 0.025167 0.002257 0.050164 +v 0.020164 0.013580 0.050164 +v 0.024903 0.004363 0.032460 +v 0.022006 0.012525 0.032460 +v 0.023586 0.009103 0.032460 +v 0.024640 0.005682 0.045386 +vt 1.000000 0.339663 +vt 1.000000 0.509397 +vt 0.269871 0.434123 +vt 1.000000 1.000000 +vt 1.000000 0.981010 +vt 1.000000 0.000000 +vt 1.000000 0.981010 +vt 1.000000 0.188724 +vt 0.000000 0.339663 +vt 0.000000 0.962216 +vt 0.000000 0.000000 +vt 0.000000 0.735709 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 0.952232 0.981010 +vt 1.000000 0.773395 +vt 0.000000 0.962216 +vt 0.936374 0.000000 +vt 0.952232 1.000000 +vt 0.000000 0.509397 +vt 0.000000 0.188724 +vt 0.000000 1.000000 +vt 1.000000 0.924432 +vt 1.000000 0.679229 +vn 0.9762 0.2171 -0.0023 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn -0.9505 -0.3107 0.0000 +vn -0.9546 -0.2807 0.1000 +vn 0.7093 0.7049 -0.0001 +vn 0.7079 0.7063 0.0000 +vn 0.8946 0.4468 -0.0000 +vn -0.9483 -0.3085 0.0753 +vn -0.0870 0.9506 -0.2979 +vn 0.0000 1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.9941 0.0000 0.1087 +vn 0.9922 0.1244 0.0000 +vn 0.8325 0.5540 -0.0041 +vn 0.8945 0.4471 -0.0000 +vn 0.9282 0.3720 -0.0027 +vn 0.9486 0.3164 0.0001 +vn 0.9488 0.3160 0.0000 +vn 0.9761 0.2171 0.0062 +vn 0.9698 0.2438 0.0000 +vn 0.9807 0.1954 0.0000 +usemtl None +s off +f 304/283/282 292/284/282 307/285/282 +f 284/286/283 285/287/283 286/288/283 +f 284/286/283 286/288/283 288/289/283 +f 286/288/283 285/287/283 289/290/283 +f 283/291/284 287/292/284 290/293/284 +f 287/292/284 283/291/284 291/294/284 +f 289/290/283 285/287/283 292/284/283 +f 286/288/283 289/290/283 293/295/283 +f 290/293/285 286/288/285 293/295/285 +f 287/292/284 291/294/284 294/296/284 +f 283/291/284 290/293/284 295/297/284 +f 293/295/286 289/290/286 295/297/286 +f 290/293/285 293/295/285 295/297/285 +f 288/289/287 286/288/287 296/298/287 +f 290/293/288 287/292/288 296/298/288 +f 292/284/283 285/287/283 297/299/283 +f 285/287/289 284/286/289 298/300/289 +f 284/286/290 294/296/290 298/300/290 +f 294/296/284 291/294/284 298/300/284 +f 291/294/291 297/299/291 298/300/291 +f 286/288/285 290/293/285 299/301/285 +f 296/298/287 286/288/287 299/301/287 +f 290/293/292 296/298/292 299/301/292 +f 284/286/293 288/289/293 300/302/293 +f 294/296/294 284/286/294 300/302/294 +f 288/289/295 296/298/295 300/302/295 +f 296/298/296 287/292/296 300/302/296 +f 291/294/284 283/291/284 301/303/284 +f 289/290/297 283/291/297 302/304/297 +f 283/291/284 295/297/284 302/304/284 +f 295/297/286 289/290/286 302/304/286 +f 287/292/284 294/296/284 303/305/284 +f 294/296/294 300/302/294 303/305/294 +f 300/302/296 287/292/296 303/305/296 +f 283/291/297 289/290/297 304/283/297 +f 289/290/283 292/284/283 304/283/283 +f 297/299/283 285/287/283 305/306/283 +f 285/287/298 298/300/298 305/306/298 +f 298/300/299 297/299/299 305/306/299 +f 297/299/300 291/294/300 306/307/300 +f 292/284/283 297/299/283 306/307/283 +f 291/294/301 301/303/301 306/307/301 +f 301/303/302 292/284/302 306/307/302 +f 301/303/303 283/291/303 307/285/303 +f 292/284/304 301/303/304 307/285/304 +f 283/291/305 304/283/305 307/285/305 +o Cup_hull_13 +v 0.022533 0.001203 0.032460 +v 0.020425 0.013580 0.015036 +v 0.024113 0.006469 0.017285 +v 0.018057 -0.000377 0.015036 +v 0.012001 0.013580 0.015880 +v 0.021215 0.013580 0.032458 +v 0.025167 -0.000377 0.032460 +v 0.024903 -0.000377 0.017285 +v 0.018057 0.013315 0.032177 +v 0.022533 -0.000377 0.032177 +v 0.024640 0.005682 0.032460 +v 0.023060 0.010418 0.018409 +v 0.024903 0.004363 0.018409 +v 0.012001 0.013580 0.015036 +v 0.018319 -0.000377 0.017285 +v 0.020425 -0.000377 0.015036 +v 0.023060 0.010418 0.032460 +v 0.012001 0.013315 0.015880 +v 0.021478 0.013315 0.017846 +v 0.025167 0.002257 0.018409 +v 0.024375 0.006732 0.018409 +v 0.018319 0.013580 0.032458 +v 0.024375 0.000677 0.016724 +v 0.025167 0.002257 0.032460 +v 0.022007 0.012525 0.032460 +v 0.012265 0.013315 0.016724 +v 0.025167 -0.000377 0.017848 +v 0.023585 0.009101 0.032460 +v 0.023585 0.009101 0.018130 +v 0.024375 0.004101 0.017004 +v 0.022007 0.012525 0.018409 +v 0.021215 0.013580 0.017846 +v 0.018057 -0.000377 0.015880 +v 0.024903 0.004363 0.032460 +v 0.024375 0.006732 0.032460 +v 0.022797 -0.000377 0.032460 +v 0.024903 0.003048 0.017567 +vt 0.870889 0.000000 +vt 0.887040 0.320869 +vt 0.854738 0.245399 +vt 1.000000 1.000000 +vt 0.951547 1.000000 +vt 0.000098 1.000000 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 0.016249 0.000000 +vt 0.000000 0.113254 +vt 0.000000 0.434123 +vt 1.000000 1.000000 +vt 0.870889 0.000000 +vt 1.000000 0.000000 +vt 0.000000 0.773493 +vt 0.951547 0.981010 +vt 0.806382 0.773493 +vt 0.838684 0.981010 +vt 0.806382 0.339663 +vt 0.806382 0.509397 +vt 0.870889 0.490505 +vt 0.000098 1.000000 +vt 0.016249 0.981010 +vt 0.903093 0.075568 +vt 0.000000 0.188724 +vt 0.806382 0.188724 +vt 0.000000 0.924432 +vt 0.903093 0.981010 +vt 0.838587 0.000000 +vt 0.000000 0.679131 +vt 0.822435 0.679131 +vt 0.806382 0.924432 +vt 0.838684 1.000000 +vt 0.951547 0.000000 +vt 0.000000 0.339663 +vt 0.000000 0.509397 +vt 0.000000 0.000000 +vn 0.7754 0.0517 -0.6294 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.0000 0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn -0.9103 -0.3950 -0.1240 +vn -1.0000 0.0000 0.0000 +vn -0.8884 -0.3842 0.2513 +vn 0.8637 0.4163 -0.2843 +vn 0.9761 0.2172 -0.0021 +vn 0.9402 0.2092 -0.2690 +vn -0.8192 0.4811 0.3122 +vn 0.3931 0.0000 -0.9195 +vn 0.4355 -0.2435 -0.8667 +vn 1.0000 0.0000 0.0000 +vn 0.9922 0.1244 0.0000 +vn 0.8945 0.4471 0.0000 +vn 0.7999 0.6001 0.0035 +vn 0.0000 0.0016 1.0000 +vn -0.0005 -0.0000 1.0000 +vn -0.9208 0.1815 0.3451 +vn -0.8954 -0.2927 0.3356 +vn -0.9544 0.0000 0.2987 +vn -0.8925 -0.3541 0.2793 +vn 0.9287 0.3708 0.0000 +vn 0.9486 0.3164 0.0000 +vn 0.8514 0.3069 -0.4254 +vn 0.8648 0.4076 -0.2933 +vn 0.9203 0.2739 -0.2795 +vn 0.7206 0.1602 -0.6746 +vn 0.5691 0.0670 -0.8196 +vn 0.7744 0.0515 -0.6306 +vn 0.8750 0.4373 -0.2079 +vn 0.8311 0.5561 0.0000 +vn 0.6962 0.6906 -0.1957 +vn 0.7100 0.7043 0.0000 +vn -0.9145 -0.4045 0.0000 +vn -0.9014 -0.3987 0.1686 +vn 0.9807 0.1956 0.0000 +vn 0.9698 0.2439 0.0000 +vn -0.7111 -0.2325 0.6636 +vn -0.6165 -0.1977 0.7621 +vn -0.0008 -0.0001 1.0000 +vn 0.9349 0.1913 -0.2988 +vn 0.9740 0.1222 -0.1907 +vn 0.9047 0.0349 -0.4247 +vn 0.9661 0.0538 -0.2524 +vn 0.8487 0.1544 -0.5059 +usemtl None +s off +f 315/308/306 337/309/306 344/310/306 +f 309/311/307 312/312/307 313/313/307 +f 314/314/308 311/315/308 315/308/308 +f 311/315/308 314/314/308 317/316/308 +f 308/317/309 314/314/309 318/318/309 +f 309/311/310 311/315/310 321/319/310 +f 312/312/307 309/311/307 321/319/307 +f 311/315/308 317/316/308 322/320/308 +f 311/315/310 309/311/310 323/321/310 +f 315/308/308 311/315/308 323/321/308 +f 308/317/309 318/318/309 324/322/309 +f 321/319/311 311/315/311 325/323/311 +f 312/312/312 321/319/312 325/323/312 +f 322/320/313 317/316/313 325/323/313 +f 319/324/314 309/311/314 326/325/314 +f 318/318/315 320/326/315 328/327/315 +f 320/326/316 310/328/316 328/327/316 +f 313/313/307 312/312/307 329/329/307 +f 312/312/317 316/330/317 329/329/317 +f 323/321/318 309/311/318 330/331/318 +f 315/308/319 323/321/319 330/331/319 +f 318/318/309 314/314/309 331/332/309 +f 314/314/320 327/333/320 331/332/320 +f 327/333/321 320/326/321 331/332/321 +f 308/317/309 324/322/309 332/334/309 +f 324/322/322 319/324/322 332/334/322 +f 326/325/323 313/313/323 332/334/323 +f 313/313/324 329/329/324 332/334/324 +f 329/329/325 308/317/325 332/334/325 +f 316/330/326 312/312/326 333/335/326 +f 317/316/327 316/330/327 333/335/327 +f 312/312/328 325/323/328 333/335/328 +f 325/323/329 317/316/329 333/335/329 +f 314/314/308 315/308/308 334/336/308 +f 327/333/320 314/314/320 334/336/320 +f 324/322/309 318/318/309 335/337/309 +f 319/324/330 324/322/330 335/337/330 +f 335/337/331 328/327/331 336/338/331 +f 310/328/332 309/311/332 336/338/332 +f 309/311/333 319/324/333 336/338/333 +f 328/327/334 310/328/334 336/338/334 +f 319/324/330 335/337/330 336/338/330 +f 309/311/335 310/328/335 337/309/335 +f 330/331/336 309/311/336 337/309/336 +f 315/308/337 330/331/337 337/309/337 +f 319/324/338 326/325/338 338/339/338 +f 332/334/322 319/324/322 338/339/322 +f 326/325/339 332/334/339 338/339/339 +f 309/311/307 313/313/307 339/340/307 +f 326/325/340 309/311/340 339/340/340 +f 313/313/341 326/325/341 339/340/341 +f 311/315/308 322/320/308 340/341/308 +f 325/323/342 311/315/342 340/341/342 +f 322/320/343 325/323/343 340/341/343 +f 320/326/344 318/318/344 341/342/344 +f 318/318/309 331/332/309 341/342/309 +f 331/332/321 320/326/321 341/342/321 +f 318/318/345 328/327/345 342/343/345 +f 335/337/309 318/318/309 342/343/309 +f 328/327/331 335/337/331 342/343/331 +f 314/314/309 308/317/309 343/344/309 +f 317/316/308 314/314/308 343/344/308 +f 316/330/346 317/316/346 343/344/346 +f 329/329/347 316/330/347 343/344/347 +f 308/317/348 329/329/348 343/344/348 +f 310/328/349 320/326/349 344/310/349 +f 320/326/350 327/333/350 344/310/350 +f 334/336/351 315/308/351 344/310/351 +f 327/333/352 334/336/352 344/310/352 +f 337/309/353 310/328/353 344/310/353 +o Cup_hull_14 +v 0.008313 0.022796 0.050166 +v 0.001204 0.025166 0.017848 +v 0.003047 0.024902 0.017567 +v 0.008049 0.015951 0.015036 +v 0.000413 0.024112 0.050166 +v 0.000413 0.018058 0.015036 +v 0.008313 0.023849 0.018130 +v 0.004363 0.024902 0.050166 +v 0.000413 0.024376 0.016724 +v 0.008313 0.020427 0.015036 +v 0.000413 0.025166 0.050166 +v 0.008313 0.023849 0.050166 +v 0.005679 0.024639 0.018409 +v 0.008313 0.015951 0.015318 +v 0.000413 0.018058 0.015882 +v 0.000413 0.020428 0.015036 +v 0.002257 0.025166 0.018409 +v 0.008049 0.015951 0.015318 +v 0.007785 0.022796 0.050166 +v 0.000413 0.025166 0.017848 +v 0.006733 0.023849 0.017006 +v 0.006733 0.024377 0.050166 +v 0.002257 0.025166 0.047913 +v 0.004363 0.024902 0.018409 +v 0.006733 0.024377 0.018409 +v 0.003836 0.024112 0.016724 +v 0.008313 0.023323 0.017006 +v 0.005679 0.024639 0.050166 +vt 0.000000 0.914342 +vt 0.903974 0.942829 +vt 0.000000 0.942829 +vt 0.000000 0.885659 +vt 0.000000 0.742830 +vt 0.000000 0.971415 +vt 0.919930 1.000000 +vt 0.927956 0.971415 +vt 0.951938 0.914244 +vt 1.000000 0.228684 +vt 1.000000 0.000000 +vt 1.000000 0.485756 +vt 0.911903 0.857073 +vt 0.000000 1.000000 +vt 0.000000 0.857073 +vt 0.991973 0.000000 +vt 0.975920 0.228684 +vt 1.000000 0.485854 +vt 0.903974 1.000000 +vt 0.991973 0.000000 +vt 0.000000 0.742830 +vt 0.919930 1.000000 +vt 0.943911 0.857073 +vt 0.064115 1.000000 +vt 0.903974 0.971415 +vt 0.903974 0.914342 +vt 0.951938 0.885659 +vt 0.943911 0.800000 +vn 0.2417 0.9704 0.0000 +vn -0.0000 0.0000 1.0000 +vn 0.0259 0.8092 -0.5869 +vn -1.0000 0.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.7297 -0.0430 -0.6824 +vn -0.2660 -0.9640 0.0000 +vn 0.0000 0.3932 -0.9194 +vn 0.1080 0.9732 -0.2030 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -0.9812 0.1928 +vn 0.0000 -1.0000 0.0000 +vn -0.2506 -0.9533 0.1683 +vn -0.1726 -0.9668 0.1886 +vn 0.0000 0.8182 -0.5750 +vn 0.2058 0.9106 -0.3583 +vn 0.3168 0.9485 0.0000 +vn 0.0664 0.9963 0.0544 +vn 0.1241 0.9923 0.0000 +vn 0.1962 0.9806 0.0000 +vn 0.1876 0.9375 -0.2931 +vn 0.1219 0.9741 -0.1904 +vn 0.2431 0.9079 -0.3415 +vn 0.2270 0.9115 -0.3429 +vn 0.0581 0.7547 -0.6535 +vn 0.0347 0.4508 -0.8920 +vn 0.1305 0.7812 -0.6105 +vn 0.1300 0.5392 -0.8321 +vn 0.2887 0.8672 -0.4056 +vn 0.1841 0.5529 -0.8126 +usemtl None +s off +f 366/345/354 357/346/354 372/347/354 +f 349/348/355 345/349/355 352/350/355 +f 346/351/356 347/352/356 353/353/356 +f 350/354/357 349/348/357 353/353/357 +f 348/355/358 350/354/358 354/356/358 +f 351/357/359 345/349/359 354/356/359 +f 349/348/355 352/350/355 355/358/355 +f 353/353/357 349/348/357 355/358/357 +f 345/349/359 351/357/359 356/359/359 +f 352/350/355 345/349/355 356/359/355 +f 354/356/359 345/349/359 358/360/359 +f 348/355/360 354/356/360 358/360/360 +f 349/348/357 350/354/357 359/361/357 +f 350/354/361 348/355/361 359/361/361 +f 350/354/357 353/353/357 360/362/357 +f 354/356/358 350/354/358 360/362/358 +f 353/353/362 354/356/362 360/362/362 +f 347/352/363 346/351/363 361/363/363 +f 346/351/364 355/358/364 361/363/364 +f 358/360/365 345/349/365 362/364/365 +f 348/355/366 358/360/366 362/364/366 +f 359/361/361 348/355/361 362/364/361 +f 349/348/367 359/361/367 362/364/367 +f 345/349/355 349/348/355 363/365/355 +f 362/364/365 345/349/365 363/365/365 +f 349/348/368 362/364/368 363/365/368 +f 346/351/369 353/353/369 364/366/369 +f 355/358/364 346/351/364 364/366/364 +f 353/353/357 355/358/357 364/366/357 +f 347/352/370 357/346/370 365/367/370 +f 356/359/371 351/357/371 366/345/371 +f 352/350/355 356/359/355 366/345/355 +f 355/358/372 352/350/372 367/368/372 +f 361/363/364 355/358/364 367/368/364 +f 352/350/373 361/363/373 367/368/373 +f 352/350/374 357/346/374 368/369/374 +f 357/346/375 347/352/375 368/369/375 +f 347/352/376 361/363/376 368/369/376 +f 361/363/373 352/350/373 368/369/373 +f 351/357/377 365/367/377 369/370/377 +f 365/367/378 357/346/378 369/370/378 +f 366/345/371 351/357/371 369/370/371 +f 357/346/354 366/345/354 369/370/354 +f 353/353/379 347/352/379 370/371/379 +f 354/356/380 353/353/380 370/371/380 +f 347/352/381 365/367/381 370/371/381 +f 365/367/382 354/356/382 370/371/382 +f 351/357/359 354/356/359 371/372/359 +f 365/367/383 351/357/383 371/372/383 +f 354/356/384 365/367/384 371/372/384 +f 357/346/374 352/350/374 372/347/374 +f 352/350/355 366/345/355 372/347/355 +o Cup_hull_15 +v -0.002221 -0.020392 -0.048198 +v -0.020392 -0.014862 0.015036 +v -0.020126 -0.015389 0.015036 +v -0.002221 -0.017758 0.015036 +v -0.013280 -0.011965 -0.048198 +v -0.014860 -0.020392 -0.048198 +v -0.014860 -0.020392 0.015036 +v -0.013280 -0.011965 0.015036 +v -0.020392 -0.011965 -0.048198 +v -0.002221 -0.020392 0.015036 +v -0.002221 -0.017758 -0.048198 +v -0.020392 -0.011965 0.015036 +v -0.020126 -0.015389 -0.048198 +v -0.016704 -0.019073 -0.027679 +v -0.019074 -0.016704 0.015036 +v -0.019074 -0.016704 -0.048198 +v -0.020392 -0.014862 -0.048198 +v -0.015386 -0.020128 0.015036 +v -0.015386 -0.020128 -0.048198 +v -0.016968 -0.018811 0.015036 +v -0.016704 -0.019073 -0.048198 +vt 0.000000 0.188430 +vt 1.000000 0.072533 +vt 1.000000 0.202917 +vt 0.000000 0.000000 +vt 0.000000 0.014585 +vt 0.000000 1.000000 +vt 1.000000 0.391347 +vt 1.000000 1.000000 +vt 1.000000 0.304424 +vt 0.000000 0.304424 +vt 0.000000 0.391347 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 0.000000 0.000000 +vt 1.000000 0.014585 +vt 0.000000 0.072533 +vt 1.000000 0.000000 +vt 0.000000 0.275450 +vt 1.000000 0.275450 +vt 0.675509 0.202917 +vn -0.7071 -0.7071 -0.0000 +vn -0.0000 0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.4640 0.8858 0.0000 +vn -0.0001 1.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.8934 -0.4492 0.0000 +vn -0.7807 -0.6248 0.0000 +vn -0.4482 -0.8939 0.0000 +vn -0.6246 -0.7809 0.0000 +vn -0.7072 -0.7070 0.0000 +vn -0.6398 -0.7685 0.0008 +vn -0.7059 -0.7083 0.0000 +usemtl None +s off +f 392/373/385 388/374/385 393/375/385 +f 374/376/386 375/377/386 376/378/386 +f 377/379/387 373/380/387 378/381/387 +f 378/381/388 373/380/388 379/382/388 +f 376/378/386 375/377/386 379/382/386 +f 374/376/386 376/378/386 380/383/386 +f 376/378/389 377/379/389 380/383/389 +f 380/383/390 377/379/390 381/384/390 +f 377/379/387 378/381/387 381/384/387 +f 373/380/391 376/378/391 382/385/391 +f 379/382/388 373/380/388 382/385/388 +f 376/378/386 379/382/386 382/385/386 +f 376/378/391 373/380/391 383/386/391 +f 373/380/387 377/379/387 383/386/387 +f 377/379/389 376/378/389 383/386/389 +f 374/376/386 380/383/386 384/387/386 +f 380/383/390 381/384/390 384/387/390 +f 381/384/392 374/376/392 384/387/392 +f 375/377/393 374/376/393 385/388/393 +f 381/384/387 378/381/387 385/388/387 +f 379/382/386 375/377/386 387/389/386 +f 375/377/394 385/388/394 387/389/394 +f 385/388/387 378/381/387 388/374/387 +f 387/389/394 385/388/394 388/374/394 +f 374/376/392 381/384/392 389/390/392 +f 385/388/393 374/376/393 389/390/393 +f 381/384/387 385/388/387 389/390/387 +f 378/381/395 379/382/395 390/391/395 +f 379/382/386 387/389/386 390/391/386 +f 388/374/387 378/381/387 391/392/387 +f 378/381/395 390/391/395 391/392/395 +f 390/391/396 386/393/396 391/392/396 +f 387/389/397 388/374/397 392/373/397 +f 386/393/398 390/391/398 392/373/398 +f 390/391/386 387/389/386 392/373/386 +f 388/374/387 391/392/387 393/375/387 +f 391/392/396 386/393/396 393/375/396 +f 386/393/399 392/373/399 393/375/399 +o Cup_hull_16 +v -0.020127 -0.011963 0.015036 +v -0.018021 -0.000377 -0.048198 +v -0.013545 -0.011700 -0.048198 +v -0.020392 -0.011963 -0.048198 +v -0.020392 -0.000377 0.015029 +v -0.013545 -0.011963 0.015036 +v -0.018021 -0.000377 0.015036 +v -0.020392 -0.000377 -0.048198 +v -0.020392 -0.011963 0.015029 +v -0.013545 -0.011963 -0.048198 +v -0.013545 -0.011700 0.015036 +vt 1.000000 0.022712 +vt 0.000000 1.000000 +vt 0.000000 0.022712 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000098 1.000000 +vt 1.000000 1.000000 +vt 0.000098 0.000000 +vt 1.000000 0.000000 +vn 0.9300 0.3677 0.0000 +vn -0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn -0.0026 0.0005 1.0000 +vn 0.0000 1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.0234 0.0000 0.9997 +vn 1.0000 0.0000 0.0000 +usemtl None +s off +f 396/394/400 400/395/400 404/396/400 +f 395/397/401 396/394/401 397/398/401 +f 394/399/402 397/398/402 399/400/402 +f 394/399/403 399/400/403 400/395/403 +f 396/394/400 395/397/400 400/395/400 +f 398/401/404 394/399/404 400/395/404 +f 395/397/405 398/401/405 400/395/405 +f 395/397/401 397/398/401 401/402/401 +f 397/398/406 398/401/406 401/402/406 +f 398/401/405 395/397/405 401/402/405 +f 397/398/402 394/399/402 402/403/402 +f 394/399/407 398/401/407 402/403/407 +f 398/401/406 397/398/406 402/403/406 +f 397/398/401 396/394/401 403/404/401 +f 396/394/408 399/400/408 403/404/408 +f 399/400/402 397/398/402 403/404/402 +f 399/400/408 396/394/408 404/396/408 +f 400/395/403 399/400/403 404/396/403 +o Cup_hull_17 +v 0.015424 -0.020127 0.015036 +v 0.020163 -0.000379 -0.048198 +v 0.018057 -0.000379 -0.048198 +v 0.012263 -0.020390 -0.048198 +v 0.020426 -0.014861 -0.048192 +v 0.018057 -0.000379 0.015036 +v 0.012263 -0.013017 0.015036 +v 0.020426 -0.014859 0.015036 +v 0.012263 -0.013017 -0.048198 +v 0.020426 -0.000379 0.015036 +v 0.012263 -0.020390 0.015036 +v 0.014897 -0.020390 -0.048198 +v 0.018846 -0.016967 -0.048198 +v 0.020426 -0.000379 -0.048192 +v 0.018583 -0.017230 0.015036 +v 0.017003 -0.018811 -0.048198 +v 0.014897 -0.020390 0.015036 +v 0.017003 -0.018811 0.015036 +v 0.019899 -0.015651 0.015036 +v 0.015424 -0.020127 -0.044540 +v 0.019899 -0.015651 -0.048198 +vt 0.000000 0.236832 +vt 1.000000 0.171040 +vt 1.000000 0.236832 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 0.000000 0.013119 +vt 0.000000 0.368416 +vt 0.000000 0.276385 +vt 1.000000 0.368416 +vt 0.000000 1.000000 +vt 0.999902 0.276287 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 0.999902 1.000000 +vt 0.000000 0.157920 +vt 1.000000 0.078911 +vt 0.000000 0.000000 +vt 0.000000 0.078911 +vt 0.942150 0.013119 +vn 0.7809 -0.6247 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 1.0000 0.0000 +vn -0.0000 0.0000 1.0000 +vn -0.9090 0.4167 0.0000 +vn -1.0000 0.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0235 0.0000 -0.9997 +vn 0.4461 -0.8950 0.0000 +vn 0.7072 -0.7070 0.0000 +vn 0.7071 -0.7071 0.0000 +vn 0.6404 -0.7681 0.0000 +vn 0.8326 -0.5539 0.0000 +vn 0.7682 -0.6403 0.0005 +vn 0.5997 -0.7997 -0.0289 +vn 0.0121 -0.0002 -0.9999 +vn 0.8319 -0.5549 0.0000 +usemtl None +s off +f 423/405/409 417/406/409 425/407/409 +f 407/408/410 406/409/410 408/410/410 +f 406/409/411 407/408/411 410/411/411 +f 405/412/412 410/411/412 411/413/412 +f 410/411/413 407/408/413 411/413/413 +f 410/411/412 405/412/412 412/414/412 +f 407/408/410 408/410/410 413/415/410 +f 411/413/413 407/408/413 413/415/413 +f 408/410/414 411/413/414 413/415/414 +f 406/409/411 410/411/411 414/416/411 +f 412/414/415 409/417/415 414/416/415 +f 410/411/412 412/414/412 414/416/412 +f 405/412/412 411/413/412 415/418/412 +f 411/413/414 408/410/414 415/418/414 +f 408/410/410 406/409/410 416/419/410 +f 415/418/416 408/410/416 416/419/416 +f 416/419/410 406/409/410 417/406/410 +f 409/417/417 406/409/417 418/420/417 +f 406/409/411 414/416/411 418/420/411 +f 414/416/415 409/417/415 418/420/415 +f 412/414/412 405/412/412 419/421/412 +f 416/419/410 417/406/410 420/422/410 +f 405/412/412 415/418/412 421/423/412 +f 416/419/418 405/412/418 421/423/418 +f 415/418/416 416/419/416 421/423/416 +f 419/421/412 405/412/412 422/424/412 +f 417/406/419 419/421/419 422/424/419 +f 420/422/420 417/406/420 422/424/420 +f 405/412/421 420/422/421 422/424/421 +f 409/417/422 412/414/422 423/405/422 +f 412/414/412 419/421/412 423/405/412 +f 419/421/423 417/406/423 423/405/423 +f 405/412/418 416/419/418 424/425/418 +f 420/422/421 405/412/421 424/425/421 +f 416/419/424 420/422/424 424/425/424 +f 406/409/425 409/417/425 425/407/425 +f 417/406/410 406/409/410 425/407/410 +f 409/417/426 423/405/426 425/407/426 +o Cup_hull_18 +v -0.015651 0.019899 -0.048198 +v -0.020392 0.013317 0.015036 +v -0.011965 0.013317 0.015036 +v 0.000413 0.020426 0.015036 +v -0.011965 0.013317 -0.048198 +v 0.000413 0.018056 -0.048198 +v -0.014861 0.020425 0.015036 +v -0.020392 0.014897 -0.048198 +v 0.000413 0.020426 -0.048198 +v 0.000413 0.018056 0.015036 +v -0.020392 0.013317 -0.048198 +v -0.018811 0.017002 0.015036 +v -0.014861 0.020425 -0.048198 +v -0.020392 0.014897 0.015036 +v -0.018811 0.017002 -0.048198 +v -0.017231 0.018583 0.015036 +v -0.020127 0.015424 0.015036 +v -0.016966 0.018846 -0.048198 +v -0.015651 0.019899 0.015036 +v -0.020127 0.015424 -0.045667 +vt 0.000000 0.012725 +vt 1.000000 0.075959 +vt 0.959965 0.012725 +vt 0.000000 0.000000 +vt 0.000000 0.405051 +vt 0.000000 1.000000 +vt 1.000000 0.405051 +vt 1.000000 1.000000 +vt 1.000000 0.227878 +vt 0.000000 0.265858 +vt 1.000000 0.000000 +vt 1.000000 1.000000 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.075959 +vt 1.000000 0.265858 +vt 0.000000 0.000000 +vt 0.000000 0.151919 +vt 1.000000 0.164644 +vt 0.000000 0.227878 +vn -0.7682 0.6402 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.3576 -0.9339 0.0000 +vn -0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn -0.0000 1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.5543 0.8323 0.0000 +vn -0.7072 0.7070 0.0000 +vn -0.8935 0.4490 0.0000 +vn -0.7069 0.7074 -0.0000 +vn -0.6400 0.7684 0.0005 +vn -0.6249 0.7807 0.0000 +vn -0.7991 0.5998 -0.0413 +usemtl None +s off +f 442/426/427 440/427/427 445/428/427 +f 427/429/428 428/430/428 429/431/428 +f 428/430/429 427/429/429 430/432/429 +f 428/430/430 430/432/430 431/433/430 +f 430/432/431 426/434/431 431/433/431 +f 427/429/428 429/431/428 432/435/428 +f 426/434/431 430/432/431 433/436/431 +f 429/431/432 431/433/432 434/437/432 +f 431/433/431 426/434/431 434/437/431 +f 432/435/433 429/431/433 434/437/433 +f 429/431/428 428/430/428 435/438/428 +f 428/430/430 431/433/430 435/438/430 +f 431/433/432 429/431/432 435/438/432 +f 430/432/429 427/429/429 436/439/429 +f 433/436/431 430/432/431 436/439/431 +f 427/429/434 433/436/434 436/439/434 +f 427/429/428 432/435/428 437/440/428 +f 426/434/435 432/435/435 438/441/435 +f 434/437/431 426/434/431 438/441/431 +f 432/435/433 434/437/433 438/441/433 +f 433/436/434 427/429/434 439/442/434 +f 427/429/428 437/440/428 439/442/428 +f 426/434/431 433/436/431 440/427/431 +f 440/427/436 437/440/436 441/443/436 +f 437/440/428 432/435/428 441/443/428 +f 433/436/437 439/442/437 442/426/437 +f 439/442/428 437/440/428 442/426/428 +f 437/440/427 440/427/427 442/426/427 +f 426/434/431 440/427/431 443/444/431 +f 440/427/438 441/443/438 443/444/438 +f 443/444/439 441/443/439 444/445/439 +f 432/435/435 426/434/435 444/445/435 +f 441/443/428 432/435/428 444/445/428 +f 426/434/440 443/444/440 444/445/440 +f 440/427/441 433/436/441 445/428/441 +f 433/436/437 442/426/437 445/428/437 +o Cup_hull_19 +v 0.018056 0.017793 -0.048198 +v 0.000413 0.018056 0.015036 +v 0.012788 0.012527 0.015036 +v 0.014896 0.020427 0.015036 +v 0.000413 0.020426 -0.048198 +v 0.012788 0.012527 -0.048198 +v 0.020427 0.012527 0.015036 +v 0.020427 0.012527 -0.048192 +v 0.014896 0.020427 -0.048198 +v 0.000413 0.020426 0.015036 +v 0.000413 0.018056 -0.048198 +v 0.020427 0.014897 0.015036 +v 0.020427 0.014897 -0.048192 +v 0.018319 0.017529 0.015036 +v 0.015686 0.019898 0.015036 +v 0.019900 0.015686 -0.048198 +v 0.017265 0.018583 -0.048198 +v 0.019900 0.015686 0.015036 +v 0.018583 0.017266 -0.048198 +v 0.015686 0.019898 -0.048198 +v 0.017792 0.018056 0.015036 +vt 1.000000 0.842013 +vt 0.000000 0.763117 +vt 0.000000 0.868344 +vt 0.000000 0.000000 +vt 0.000000 0.618344 +vt 0.000000 0.723669 +vt 1.000000 0.618344 +vt 1.000000 0.000000 +vt 1.000000 0.881558 +vt 0.000000 1.000000 +vt 0.999902 1.000000 +vt 1.000000 0.723669 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 0.999902 1.000000 +vt 0.000000 0.894675 +vt 1.000000 0.973669 +vt 0.000000 0.973669 +vt 1.000000 0.907890 +vt 1.000000 0.763117 +vn 0.6585 0.7526 0.0008 +vn 0.0000 0.0000 1.0000 +vn -0.4079 -0.9130 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.0001 1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.5560 0.8312 0.0000 +vn 0.0008 -0.0018 -1.0000 +vn 0.0117 0.0000 -0.9999 +vn 0.8317 0.5552 -0.0000 +vn 0.8315 0.5555 0.0000 +vn 0.7682 0.6402 0.0000 +vn 0.7069 0.7073 0.0000 +vn -0.0001 0.0000 -1.0000 +vn 0.7590 0.6511 0.0005 +vn 0.6401 0.7683 0.0000 +vn 0.7066 0.7076 0.0000 +usemtl None +s off +f 462/446/442 460/447/442 466/448/442 +f 447/449/443 448/450/443 449/451/443 +f 448/450/444 447/449/444 451/452/444 +f 450/453/445 446/454/445 451/452/445 +f 448/450/446 451/452/446 452/455/446 +f 449/451/443 448/450/443 452/455/443 +f 452/455/446 451/452/446 453/456/446 +f 446/454/445 450/453/445 454/457/445 +f 450/453/447 449/451/447 454/457/447 +f 447/449/443 449/451/443 455/458/443 +f 449/451/447 450/453/447 455/458/447 +f 450/453/448 447/449/448 455/458/448 +f 447/449/448 450/453/448 456/459/448 +f 451/452/444 447/449/444 456/459/444 +f 450/453/445 451/452/445 456/459/445 +f 449/451/443 452/455/443 457/460/443 +f 452/455/449 453/456/449 457/460/449 +f 457/460/449 453/456/449 458/461/449 +f 449/451/443 457/460/443 459/462/443 +f 454/457/450 449/451/450 460/447/450 +f 449/451/443 459/462/443 460/447/443 +f 451/452/445 446/454/445 461/463/445 +f 453/456/451 451/452/451 461/463/451 +f 458/461/452 453/456/452 461/463/452 +f 457/460/453 458/461/453 461/463/453 +f 446/454/445 454/457/445 462/446/445 +f 459/462/443 457/460/443 463/464/443 +f 457/460/454 461/463/454 463/464/454 +f 463/464/455 461/463/455 464/465/455 +f 446/454/456 459/462/456 464/465/456 +f 461/463/457 446/454/457 464/465/457 +f 459/462/458 463/464/458 464/465/458 +f 454/457/450 460/447/450 465/466/450 +f 462/446/445 454/457/445 465/466/445 +f 460/447/459 462/446/459 465/466/459 +f 459/462/456 446/454/456 466/448/456 +f 460/447/443 459/462/443 466/448/443 +f 446/454/460 462/446/460 466/448/460 +o Cup_hull_20 +v -0.019075 -0.016703 0.048477 +v -0.021180 -0.009068 0.034429 +v -0.023551 -0.009068 0.034429 +v -0.013281 -0.021182 0.034429 +v -0.013281 -0.020127 0.050166 +v -0.022498 -0.009068 0.050166 +v -0.019075 -0.016703 0.034429 +v -0.013281 -0.018811 0.034429 +v -0.021708 -0.013019 0.050166 +v -0.015389 -0.020127 0.050166 +v -0.020918 -0.014335 0.034429 +v -0.023287 -0.009859 0.050166 +v -0.016705 -0.019074 0.034429 +v -0.013808 -0.021182 0.050166 +v -0.022234 -0.009068 0.049039 +v -0.014335 -0.020917 0.034429 +v -0.021180 -0.009068 0.035553 +v -0.022498 -0.011439 0.034429 +v -0.016705 -0.019074 0.050166 +v -0.013281 -0.018811 0.035553 +v -0.020127 -0.015387 0.050166 +v -0.023551 -0.009068 0.046230 +v -0.013281 -0.021182 0.050166 +v -0.023551 -0.009332 0.034429 +v -0.021708 -0.013019 0.034429 +v -0.023287 -0.009068 0.050166 +v -0.013808 -0.021182 0.034429 +vt 0.000000 0.000000 +vt 1.000000 0.021829 +vt 1.000000 0.000000 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 0.369714 +vt 1.000000 0.195673 +vt 0.000000 0.087020 +vt 0.000000 0.673845 +vt 0.000000 0.087020 +vt 1.000000 0.565192 +vt 0.000000 0.934710 +vt 0.107283 0.369714 +vt 1.000000 0.173943 +vt 0.071554 1.000000 +vt 0.928543 1.000000 +vt 1.000000 0.804229 +vt 0.000000 0.173943 +vt 0.928543 0.195673 +vt 0.000000 0.478367 +vt 0.250098 1.000000 +vt 0.000000 0.000000 +vt 1.000000 0.978172 +vt 1.000000 0.673845 +vt 0.000000 1.000000 +vn -0.4486 -0.8937 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 1.0000 -0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn -0.7074 -0.7068 0.0000 +vn 0.7560 0.6300 0.1775 +vn -0.6137 -0.7895 -0.0015 +vn -0.5547 -0.8321 0.0046 +vn 0.7768 0.6297 0.0000 +vn 0.7728 0.6317 0.0604 +vn -0.8945 -0.4471 0.0000 +vn -0.6248 -0.7808 0.0000 +vn 0.7756 0.6287 0.0566 +vn -0.7810 -0.6246 0.0000 +vn -0.7892 -0.6141 -0.0014 +vn -0.8318 -0.5551 0.0047 +vn -0.7311 -0.6784 0.0731 +vn 0.0000 -1.0000 0.0000 +vn -0.0001 0.0000 -1.0000 +vn -0.8946 -0.4469 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.9579 -0.2870 0.0064 +vn -0.8574 -0.5147 0.0000 +vn -0.8943 -0.4474 0.0000 +vn -0.9978 0.0000 0.0668 +usemtl None +s off +f 480/467/461 482/468/461 493/469/461 +f 469/470/462 468/471/462 470/472/462 +f 468/471/463 469/470/463 472/473/463 +f 469/470/462 470/472/462 473/474/462 +f 470/472/462 468/471/462 474/475/462 +f 471/476/464 470/472/464 474/475/464 +f 471/476/465 472/473/465 475/477/465 +f 471/476/465 475/477/465 476/478/465 +f 469/470/462 473/474/462 477/479/462 +f 475/477/465 472/473/465 478/480/465 +f 467/481/466 473/474/466 479/482/466 +f 473/474/462 470/472/462 479/482/462 +f 471/476/465 476/478/465 480/467/465 +f 468/471/463 472/473/463 481/483/463 +f 472/473/467 471/476/467 481/483/467 +f 479/482/462 470/472/462 482/468/462 +f 476/478/468 479/482/468 482/468/468 +f 480/467/469 476/478/469 482/468/469 +f 474/475/470 468/471/470 483/484/470 +f 468/471/463 481/483/463 483/484/463 +f 481/483/471 471/476/471 483/484/471 +f 469/470/462 477/479/462 484/485/462 +f 475/477/472 478/480/472 484/485/472 +f 476/478/465 475/477/465 485/486/465 +f 467/481/466 479/482/466 485/486/466 +f 479/482/473 476/478/473 485/486/473 +f 471/476/464 474/475/464 486/487/464 +f 474/475/470 483/484/470 486/487/470 +f 483/484/474 471/476/474 486/487/474 +f 473/474/475 467/481/475 487/488/475 +f 477/479/476 473/474/476 487/488/476 +f 475/477/477 477/479/477 487/488/477 +f 467/481/478 485/486/478 487/488/478 +f 485/486/465 475/477/465 487/488/465 +f 472/473/463 469/470/463 488/489/463 +f 470/472/464 471/476/464 489/490/464 +f 480/467/479 470/472/479 489/490/479 +f 471/476/465 480/467/465 489/490/465 +f 469/470/480 484/485/480 490/491/480 +f 484/485/481 478/480/481 490/491/481 +f 488/489/482 469/470/482 490/491/482 +f 478/480/483 488/489/483 490/491/483 +f 477/479/484 475/477/484 491/492/484 +f 484/485/462 477/479/462 491/492/462 +f 475/477/485 484/485/485 491/492/485 +f 478/480/465 472/473/465 492/493/465 +f 472/473/463 488/489/463 492/493/463 +f 488/489/486 478/480/486 492/493/486 +f 470/472/479 480/467/479 493/469/479 +f 482/468/462 470/472/462 493/469/462 +o Cup_hull_21 +v -0.016705 -0.019073 0.034427 +v -0.015388 -0.009068 0.015038 +v -0.020391 -0.009068 0.015038 +v -0.013281 -0.020391 0.015038 +v -0.023552 -0.009332 0.034427 +v -0.013281 -0.018548 0.034143 +v -0.020127 -0.015387 0.015038 +v -0.020918 -0.009068 0.034143 +v -0.013281 -0.011966 0.015038 +v -0.023552 -0.009068 0.018410 +v -0.013808 -0.021182 0.018129 +v -0.013281 -0.021182 0.034427 +v -0.020918 -0.014335 0.034427 +v -0.016969 -0.018811 0.015038 +v -0.021708 -0.013019 0.018129 +v -0.015915 -0.009068 0.017568 +v -0.019075 -0.016704 0.034427 +v -0.014335 -0.020917 0.034427 +v -0.015388 -0.020126 0.015038 +v -0.021181 -0.009068 0.034427 +v -0.013281 -0.012492 0.017287 +v -0.022760 -0.009859 0.017006 +v -0.019075 -0.016704 0.015038 +v -0.023552 -0.009068 0.034427 +v -0.023552 -0.009332 0.018410 +v -0.021708 -0.013019 0.034427 +v -0.013281 -0.021182 0.017568 +v -0.013281 -0.018811 0.034427 +v -0.020391 -0.014861 0.015038 +v -0.020918 -0.014335 0.018410 +v -0.013808 -0.021182 0.034427 +v -0.022497 -0.009068 0.016725 +v -0.014335 -0.020917 0.018410 +vt 0.000000 0.021829 +vt 1.000000 0.087118 +vt 0.826057 0.021829 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.065290 +vt 1.000000 0.478367 +vt 0.014683 1.000000 +vt 1.000000 0.760768 +vt 0.014683 0.217404 +vt 0.826057 1.000000 +vt 0.000000 0.978172 +vt 0.000000 0.174041 +vt 0.000000 0.000000 +vt 0.000000 0.565192 +vt 1.000000 0.195673 +vt 0.869518 1.000000 +vt 0.000000 0.369616 +vt 0.000000 1.000000 +vt 0.884005 0.717306 +vt 1.000000 0.369616 +vt 0.000000 1.000000 +vt 0.826057 0.978172 +vt 0.840544 0.673845 +vt 0.898493 0.934710 +vt 0.000000 0.673845 +vt 0.869518 0.000000 +vt 0.840544 0.000000 +vt 0.000000 0.195673 +vt 1.000000 0.521731 +vt 0.826057 0.565192 +vt 0.000000 0.000000 +vt 0.912980 1.000000 +vn -0.6004 -0.7997 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 1.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn -0.0000 0.0000 1.0000 +vn 0.7581 0.6107 0.2288 +vn -0.7893 -0.6140 0.0011 +vn -0.7070 -0.7072 0.0000 +vn -0.6396 -0.7687 -0.0017 +vn -0.6140 -0.7893 0.0012 +vn 0.8012 0.5826 0.1364 +vn 0.7884 0.5929 0.1641 +vn 0.7832 0.5852 0.2102 +vn -0.7813 -0.6242 0.0000 +vn -0.7073 -0.7069 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.8944 -0.4473 0.0000 +vn -0.8713 0.0000 -0.4908 +vn 0.0001 0.0000 1.0000 +vn -0.8574 -0.5147 0.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.1189 -0.9477 -0.2963 +vn -0.2242 -0.9516 -0.2102 +vn 0.6737 0.5426 0.5017 +vn 0.6308 0.5114 0.5836 +vn -0.8882 -0.4454 -0.1129 +vn -0.8916 -0.4368 -0.1194 +vn -0.8797 -0.2601 -0.3981 +vn -0.7995 -0.6007 0.0000 +vn -0.8532 -0.5202 -0.0377 +vn -0.4486 -0.8937 0.0000 +vn -0.8440 0.0935 -0.5281 +vn -0.6252 0.0000 -0.7804 +vn -0.6798 -0.0338 -0.7326 +vn -0.4726 -0.8793 -0.0586 +usemtl None +s off +f 511/494/487 512/495/487 526/496/487 +f 496/497/488 495/498/488 497/499/488 +f 496/497/488 497/499/488 500/500/488 +f 495/498/489 496/497/489 501/501/489 +f 497/499/488 495/498/488 502/502/488 +f 499/503/490 497/499/490 502/502/490 +f 501/501/489 496/497/489 503/504/489 +f 498/505/491 494/506/491 505/507/491 +f 497/499/490 499/503/490 505/507/490 +f 494/506/491 498/505/491 506/508/491 +f 500/500/488 497/499/488 507/509/488 +f 495/498/489 501/501/489 509/510/489 +f 501/501/492 499/503/492 509/510/492 +f 494/506/491 506/508/491 510/511/491 +f 506/508/493 500/500/493 510/511/493 +f 507/509/494 494/506/494 510/511/494 +f 505/507/491 494/506/491 511/494/491 +f 507/509/488 497/499/488 512/495/488 +f 494/506/495 507/509/495 512/495/495 +f 511/494/496 494/506/496 512/495/496 +f 501/501/489 503/504/489 513/512/489 +f 498/505/491 505/507/491 513/512/491 +f 502/502/497 495/498/497 514/513/497 +f 499/503/490 502/502/490 514/513/490 +f 495/498/498 509/510/498 514/513/498 +f 509/510/499 499/503/499 514/513/499 +f 500/500/488 507/509/488 516/514/488 +f 510/511/500 500/500/500 516/514/500 +f 507/509/501 510/511/501 516/514/501 +f 503/504/502 498/505/502 517/515/502 +f 498/505/491 513/512/491 517/515/491 +f 513/512/489 503/504/489 517/515/489 +f 498/505/502 503/504/502 518/516/502 +f 508/517/503 498/505/503 518/516/503 +f 503/504/504 515/518/504 518/516/504 +f 506/508/505 498/505/505 519/519/505 +f 498/505/503 508/517/503 519/519/503 +f 508/517/506 506/508/506 519/519/506 +f 497/499/490 505/507/490 520/520/490 +f 505/507/507 504/521/507 520/520/507 +f 512/495/508 497/499/508 520/520/508 +f 504/521/509 512/495/509 520/520/509 +f 499/503/510 501/501/510 521/522/510 +f 505/507/490 499/503/490 521/522/490 +f 501/501/511 513/512/511 521/522/511 +f 513/512/491 505/507/491 521/522/491 +f 496/497/488 500/500/488 522/523/488 +f 500/500/512 508/517/512 522/523/512 +f 508/517/513 518/516/513 522/523/513 +f 518/516/514 515/518/514 522/523/514 +f 500/500/515 506/508/515 523/524/515 +f 508/517/516 500/500/516 523/524/516 +f 506/508/506 508/517/506 523/524/506 +f 504/521/507 505/507/507 524/525/507 +f 505/507/491 511/494/491 524/525/491 +f 511/494/517 504/521/517 524/525/517 +f 503/504/489 496/497/489 525/526/489 +f 515/518/518 503/504/518 525/526/518 +f 496/497/519 522/523/519 525/526/519 +f 522/523/520 515/518/520 525/526/520 +f 504/521/517 511/494/517 526/496/517 +f 512/495/521 504/521/521 526/496/521 +o Cup_hull_22 +v -0.024078 -0.007750 0.050164 +v -0.023025 -0.000378 0.033584 +v -0.025132 -0.000378 0.033584 +v -0.021182 -0.009067 0.033584 +v -0.024078 -0.000642 0.050164 +v -0.023814 -0.008540 0.033584 +v -0.022499 -0.009067 0.050164 +v -0.025132 -0.002485 0.050164 +v -0.024868 -0.004592 0.033584 +v -0.025132 -0.000378 0.050164 +v -0.021182 -0.008803 0.034991 +v -0.023551 -0.009067 0.050164 +v -0.023551 -0.009067 0.033584 +v -0.024604 -0.005907 0.050164 +v -0.023025 -0.000378 0.034991 +v -0.022499 -0.008540 0.050164 +v -0.025132 -0.002485 0.033584 +v -0.024604 -0.005907 0.033584 +v -0.024868 -0.004592 0.050164 +v -0.024078 -0.000378 0.048758 +v -0.021182 -0.008540 0.033584 +vt 0.915133 1.000000 +vt 0.915133 0.030345 +vt 1.000000 0.060689 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 1.000000 0.060689 +vt 0.000000 0.969655 +vt 0.000000 0.151527 +vt 0.000000 0.000000 +vt 0.000000 0.757537 +vt 1.000000 0.515074 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 0.000000 0.363645 +vt 0.000000 0.060689 +vt 1.000000 0.757537 +vt 1.000000 0.363645 +vt 0.000000 0.515074 +vt 0.084769 1.000000 +vn 0.9761 0.2136 0.0400 +vn 0.0000 0.0000 -1.0000 +vn -0.0000 0.0000 1.0000 +vn 0.0000 1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.9183 -0.3892 0.0729 +vn -0.9285 -0.3714 0.0029 +vn 0.0000 -1.0000 0.0000 +vn -0.8947 -0.4467 0.0000 +vn 0.9744 0.2132 0.0713 +vn 0.9773 0.1954 0.0814 +vn 0.9963 0.0000 0.0865 +vn -0.9922 -0.1244 0.0000 +vn -0.9578 -0.2874 -0.0015 +vn -0.9615 -0.2747 0.0000 +vn -0.9806 -0.1962 0.0000 +vn 0.2388 0.9544 0.1790 +vn 0.9238 0.3764 0.0706 +vn 1.0000 0.0000 0.0000 +vn 0.9754 0.2203 0.0000 +usemtl None +s off +f 541/527/522 537/528/522 547/529/522 +f 529/530/523 528/531/523 530/532/523 +f 529/530/523 530/532/523 532/533/523 +f 531/534/524 527/535/524 533/536/524 +f 527/535/524 531/534/524 534/537/524 +f 529/530/523 532/533/523 535/538/523 +f 528/531/525 529/530/525 536/539/525 +f 534/537/524 531/534/524 536/539/524 +f 529/530/526 534/537/526 536/539/526 +f 533/536/527 530/532/527 537/528/527 +f 527/535/528 532/533/528 538/540/528 +f 530/532/529 533/536/529 538/540/529 +f 533/536/524 527/535/524 538/540/524 +f 532/533/523 530/532/523 539/541/523 +f 538/540/530 532/533/530 539/541/530 +f 530/532/529 538/540/529 539/541/529 +f 527/535/524 534/537/524 540/542/524 +f 528/531/525 536/539/525 541/527/525 +f 531/534/531 537/528/531 541/527/531 +f 531/534/524 533/536/524 542/543/524 +f 537/528/532 531/534/532 542/543/532 +f 533/536/533 537/528/533 542/543/533 +f 534/537/526 529/530/526 543/544/526 +f 529/530/523 535/538/523 543/544/523 +f 535/538/534 534/537/534 543/544/534 +f 532/533/535 527/535/535 544/545/535 +f 535/538/523 532/533/523 544/545/523 +f 527/535/536 540/542/536 544/545/536 +f 540/542/537 535/538/537 544/545/537 +f 534/537/534 535/538/534 545/546/534 +f 540/542/524 534/537/524 545/546/524 +f 535/538/537 540/542/537 545/546/537 +f 536/539/538 531/534/538 546/547/538 +f 541/527/525 536/539/525 546/547/525 +f 531/534/539 541/527/539 546/547/539 +f 530/532/523 528/531/523 547/529/523 +f 537/528/540 530/532/540 547/529/540 +f 528/531/541 541/527/541 547/529/541 +o Cup_hull_23 +v -0.015652 -0.009067 0.015036 +v -0.025131 -0.002485 0.033582 +v -0.024868 -0.004592 0.033582 +v -0.024868 -0.003275 0.017567 +v -0.018022 -0.000378 0.015037 +v -0.020918 -0.009066 0.033301 +v -0.023550 -0.009066 0.017846 +v -0.022761 -0.000378 0.033301 +v -0.025131 -0.000378 0.017846 +v -0.020655 -0.008803 0.015037 +v -0.023550 -0.009066 0.033582 +v -0.015915 -0.008804 0.017004 +v -0.025131 -0.000378 0.033582 +v -0.020655 -0.000378 0.015037 +v -0.018549 -0.000378 0.018128 +v -0.024605 -0.005907 0.018409 +v -0.024341 -0.000378 0.016722 +v -0.025131 -0.002485 0.018409 +v -0.024078 -0.007750 0.033582 +v -0.024341 -0.004592 0.017004 +v -0.021181 -0.008277 0.033582 +v -0.020918 -0.008803 0.033301 +v -0.023024 -0.009066 0.017004 +v -0.023814 -0.008540 0.018409 +v -0.018022 -0.000378 0.015880 +v -0.022761 -0.000906 0.033582 +v -0.024868 -0.004592 0.018409 +v -0.024605 -0.005907 0.033582 +v -0.015652 -0.008804 0.015880 +v -0.020392 -0.009066 0.015037 +vt 0.893882 0.222222 +vt 0.999902 0.472149 +vt 0.999902 0.499951 +vt 0.015174 0.250024 +vt 0.999902 0.749976 +vt 0.848458 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.027704 +vt 0.000000 0.166716 +vt 1.000000 1.000000 +vt 0.015174 0.444445 +vt 0.848458 0.166716 +vt 0.893882 0.972198 +vt 0.000000 0.000000 +vt 0.999902 0.472149 +vt 0.833284 0.694371 +vt 0.863534 0.027704 +vt 0.909055 0.083309 +vt 0.818111 0.000000 +vt 0.000000 0.111111 +vt 0.818111 0.055507 +vt 0.893882 0.083309 +vt 0.000000 0.416642 +vt 0.015174 0.444445 +vt 0.818111 0.138913 +vt 0.954479 0.749976 +vt 0.000000 0.250024 +vt 0.818111 0.027704 +vt 0.000000 0.055507 +vt 0.954479 1.000000 +vn -0.5131 -0.5145 -0.6870 +vn 0.0000 1.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.0001 -1.0000 0.0000 +vn 0.6427 -0.7434 0.1853 +vn -1.0000 0.0000 0.0000 +vn 0.0000 0.0002 -1.0000 +vn -0.0004 0.0000 -1.0000 +vn 0.9313 0.2566 0.2585 +vn -0.8181 -0.0187 -0.5748 +vn -0.4157 0.0000 -0.9095 +vn -0.9923 -0.1237 0.0000 +vn -0.9683 -0.0645 -0.2414 +vn -0.9078 -0.2076 -0.3645 +vn -0.8945 -0.2302 -0.3832 +vn -0.7764 -0.0420 -0.6288 +vn -0.5198 -0.0569 -0.8524 +vn 0.1013 -0.3039 0.9473 +vn 0.9560 0.0000 0.2935 +vn 0.9357 0.2047 0.2872 +vn 0.7299 0.0000 0.6835 +vn -0.0001 -1.0000 -0.0001 +vn -0.8229 -0.2422 -0.5140 +vn -0.6161 -0.1813 -0.7665 +vn -0.8942 -0.4476 0.0000 +vn -0.9427 -0.2831 -0.1766 +vn -0.9283 -0.3718 0.0032 +vn -0.9577 -0.2876 -0.0017 +vn 0.9390 0.2641 0.2202 +vn 0.1042 0.4682 0.8774 +vn 0.9069 0.1984 0.3717 +vn 0.8662 0.1856 0.4639 +vn -0.9805 -0.1965 0.0000 +vn -0.9373 -0.1878 -0.2936 +vn -0.9743 -0.1214 -0.1898 +vn -0.9615 -0.2749 0.0000 +vn 0.9615 0.2623 -0.0817 +vn 0.7851 -0.5914 0.1841 +vn 0.9626 0.2708 0.0000 +vn -0.0004 -0.0004 -1.0000 +vn -0.0002 -1.0000 -0.0002 +usemtl None +s off +f 570/548/542 557/549/542 577/550/542 +f 555/551/543 552/552/543 556/553/543 +f 549/554/544 550/555/544 558/556/544 +f 548/557/545 553/558/545 558/556/545 +f 554/559/546 548/557/546 558/556/546 +f 553/558/547 548/557/547 559/560/547 +f 556/553/548 549/554/548 560/561/548 +f 555/551/543 556/553/543 560/561/543 +f 549/554/544 558/556/544 560/561/544 +f 552/552/549 548/557/549 561/562/549 +f 556/553/543 552/552/543 561/562/543 +f 548/557/550 557/549/550 561/562/550 +f 552/552/543 555/551/543 562/563/543 +f 555/551/551 559/560/551 562/563/551 +f 551/564/552 556/553/552 564/565/552 +f 556/553/543 561/562/543 564/565/543 +f 561/562/553 557/549/553 564/565/553 +f 550/555/554 549/554/554 565/566/554 +f 549/554/548 556/553/548 565/566/548 +f 556/553/555 551/564/555 565/566/555 +f 558/556/544 550/555/544 566/567/544 +f 563/568/556 551/564/556 567/569/556 +f 554/559/557 563/568/557 567/569/557 +f 551/564/558 564/565/558 567/569/558 +f 564/565/559 557/549/559 567/569/559 +f 558/556/560 553/558/560 568/570/560 +f 560/561/544 558/556/544 568/570/544 +f 553/558/561 559/560/561 569/571/561 +f 559/560/562 555/551/562 569/571/562 +f 568/570/563 553/558/563 569/571/563 +f 548/557/564 554/559/564 570/548/564 +f 554/559/565 567/569/565 570/548/565 +f 567/569/566 557/549/566 570/548/566 +f 554/559/567 558/556/567 571/572/567 +f 563/568/568 554/559/568 571/572/568 +f 558/556/569 566/567/569 571/572/569 +f 566/567/570 563/568/570 571/572/570 +f 552/552/543 562/563/543 572/573/543 +f 562/563/571 559/560/571 572/573/571 +f 555/551/572 560/561/572 573/574/572 +f 560/561/544 568/570/544 573/574/544 +f 569/571/573 555/551/573 573/574/573 +f 568/570/574 569/571/574 573/574/574 +f 563/568/575 550/555/575 574/575/575 +f 551/564/576 563/568/576 574/575/576 +f 550/555/554 565/566/554 574/575/554 +f 565/566/577 551/564/577 574/575/577 +f 550/555/575 563/568/575 575/576/575 +f 566/567/544 550/555/544 575/576/544 +f 563/568/578 566/567/578 575/576/578 +f 548/557/579 552/552/579 576/577/579 +f 559/560/580 548/557/580 576/577/580 +f 552/552/581 572/573/581 576/577/581 +f 572/573/571 559/560/571 576/577/571 +f 557/549/582 548/557/582 577/550/582 +f 548/557/583 570/548/583 577/550/583 +o Cup_hull_24 +v -0.025132 0.002520 0.050166 +v -0.021182 0.008313 0.032181 +v -0.023814 0.008313 0.032181 +v -0.022762 -0.000376 0.032181 +v -0.022762 0.008313 0.050166 +v -0.025132 -0.000376 0.032181 +v -0.024341 -0.000376 0.050166 +v -0.024078 0.007785 0.050166 +v -0.024604 0.005941 0.032181 +v -0.021182 0.007785 0.032744 +v -0.025132 -0.000376 0.050166 +v -0.025132 0.002520 0.032181 +v -0.024078 0.000677 0.050166 +v -0.022762 -0.000376 0.033306 +v -0.024604 0.005941 0.050166 +v -0.022762 0.007785 0.050166 +v -0.023814 0.008313 0.050166 +v -0.024078 0.007785 0.032181 +v -0.024868 0.004362 0.050166 +vt 0.000000 0.727068 +vt 1.000000 0.727068 +vt 0.000000 0.545276 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.333333 +vt 0.000000 0.939207 +vt 0.968677 0.939207 +vt 0.000000 0.000000 +vt 1.000000 0.333333 +vt 0.000000 0.121194 +vt 0.937451 0.000000 +vt 0.000000 0.939207 +vt 0.000000 1.000000 +vt 1.000000 0.939207 +vn -0.9864 0.1644 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -1.0000 -0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.9703 -0.1765 -0.1655 +vn 0.9919 0.0929 0.0871 +vn -1.0000 0.0000 0.0000 +vn 0.9791 -0.1835 0.0879 +vn 0.9818 -0.1901 0.0000 +vn 0.9662 -0.2416 0.0905 +vn -0.9615 0.2747 0.0000 +vn 0.9959 0.0000 0.0903 +vn 0.9794 -0.1813 0.0888 +vn -0.8950 0.4461 0.0000 +vn -0.9899 0.1419 0.0000 +vn -0.9883 0.1524 -0.0011 +usemtl None +s off +f 592/578/584 586/579/584 596/580/584 +f 580/581/585 579/582/585 581/583/585 +f 579/582/586 580/581/586 582/584/586 +f 580/581/585 581/583/585 583/585/585 +f 583/585/587 581/583/587 584/586/587 +f 582/584/588 578/587/588 584/586/588 +f 578/587/588 582/584/588 585/588/588 +f 580/581/585 583/585/585 586/579/585 +f 581/583/589 579/582/589 587/589/589 +f 579/582/590 582/584/590 587/589/590 +f 578/587/591 583/585/591 588/590/591 +f 583/585/587 584/586/587 588/590/587 +f 584/586/588 578/587/588 588/590/588 +f 583/585/591 578/587/591 589/591/591 +f 586/579/585 583/585/585 589/591/585 +f 582/584/588 584/586/588 590/592/588 +f 587/589/592 590/592/592 591/593/592 +f 584/586/587 581/583/587 591/593/587 +f 581/583/593 587/589/593 591/593/593 +f 590/592/594 584/586/594 591/593/594 +f 578/587/588 585/588/588 592/578/588 +f 585/588/595 586/579/595 592/578/595 +f 587/589/596 582/584/596 593/594/596 +f 582/584/588 590/592/588 593/594/588 +f 590/592/597 587/589/597 593/594/597 +f 582/584/586 580/581/586 594/595/586 +f 580/581/598 585/588/598 594/595/598 +f 585/588/588 582/584/588 594/595/588 +f 585/588/598 580/581/598 595/596/598 +f 580/581/585 586/579/585 595/596/585 +f 586/579/595 585/588/595 595/596/595 +f 589/591/599 578/587/599 596/580/599 +f 586/579/600 589/591/600 596/580/600 +f 578/587/588 592/578/588 596/580/588 +o Cup_hull_25 +v -0.023551 0.007522 0.017006 +v -0.025132 -0.000376 0.032177 +v -0.022760 -0.000376 0.032177 +v -0.020655 -0.000376 0.015037 +v -0.016179 0.008313 0.016444 +v -0.023814 0.008313 0.032177 +v -0.025132 -0.000376 0.017848 +v -0.018023 -0.000376 0.015881 +v -0.020917 0.008313 0.031895 +v -0.020655 0.008313 0.015037 +v -0.024604 0.005941 0.018410 +v -0.016179 0.007785 0.015037 +v -0.025132 0.002520 0.032177 +v -0.023814 0.008313 0.017848 +v -0.022497 -0.000376 0.031895 +v -0.024340 0.001730 0.016724 +v -0.025132 0.002520 0.018410 +v -0.024604 0.005941 0.032177 +v -0.018023 -0.000376 0.015037 +v -0.016179 0.008048 0.016444 +v -0.018549 -0.000376 0.018130 +v -0.020917 0.008048 0.031895 +v -0.021180 0.008313 0.032177 +v -0.024340 0.004362 0.017006 +v -0.024340 -0.000376 0.016724 +v -0.024077 0.007785 0.032177 +v -0.016179 0.008313 0.015037 +v -0.024077 0.007785 0.018410 +v -0.024867 0.004362 0.018130 +v -0.024867 0.001730 0.017286 +vt 0.803211 0.000000 +vt 0.819561 0.029561 +vt 0.868807 0.029561 +vt 0.000000 0.264879 +vt 0.000000 0.000000 +vt 1.000000 0.500000 +vt 0.000000 0.147220 +vt 0.836009 0.000000 +vt 0.950754 0.794048 +vt 0.917956 1.000000 +vt 0.016448 0.470732 +vt 1.000000 0.500000 +vt 1.000000 1.000000 +vt 0.000000 0.000000 +vt 0.836009 0.147220 +vt 0.885158 0.176586 +vt 0.016448 0.294244 +vt 0.901606 0.088391 +vt 0.000000 0.058927 +vt 1.000000 0.794048 +vt 0.917956 1.000000 +vt 0.819561 0.735219 +vt 0.016448 0.470732 +vt 0.000000 0.441366 +vt 0.885158 0.088391 +vt 0.901606 0.088391 +vt 0.000000 0.117756 +vt 0.803211 0.058927 +vt 1.000000 1.000000 +vt 0.803211 0.117756 +vn -0.9527 0.0929 -0.2895 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 1.0000 -0.0000 +vn -0.0000 0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.5764 0.4982 -0.6477 +vn -0.4161 0.0000 -0.9093 +vn 0.9754 -0.2204 0.0000 +vn 0.9561 0.0000 0.2932 +vn 0.9755 -0.2162 0.0405 +vn 1.0000 0.0000 0.0000 +vn 0.9397 -0.2105 0.2695 +vn 0.9492 -0.2226 0.2223 +vn 0.7245 -0.1359 0.6757 +vn 0.9410 -0.1765 0.2886 +vn 0.6667 -0.1212 0.7354 +vn 0.7313 0.0000 0.6820 +vn -0.5831 0.1457 -0.7992 +vn -0.8571 0.2142 -0.4686 +vn -0.5422 0.0895 -0.8355 +vn -0.8946 0.4468 0.0000 +vn -0.9615 0.2747 0.0000 +vn -0.9441 0.2698 -0.1895 +vn -0.9058 0.2155 -0.3647 +vn -0.9898 0.1423 0.0000 +vn -0.9864 0.1642 0.0000 +vn -0.9883 0.1524 0.0014 +vn -0.8860 0.2066 -0.4151 +vn -0.8973 0.1348 -0.4203 +vn -0.9635 0.0510 -0.2626 +vn -0.7278 0.0730 -0.6819 +vn -0.8167 -0.0508 -0.5748 +vn -0.7298 0.0000 -0.6837 +usemtl None +s off +f 613/597/601 625/598/601 626/599/601 +f 599/600/602 598/601/602 600/602/602 +f 598/601/603 599/600/603 602/603/603 +f 600/602/602 598/601/602 603/604/602 +f 599/600/602 600/602/602 604/605/602 +f 601/606/604 602/603/604 605/607/604 +f 602/603/604 601/606/604 606/608/604 +f 600/602/605 606/608/605 608/609/605 +f 598/601/603 602/603/603 609/610/603 +f 603/604/606 598/601/606 609/610/606 +f 602/603/604 606/608/604 610/611/604 +f 606/608/607 597/612/607 610/611/607 +f 599/600/602 604/605/602 611/613/602 +f 606/608/608 600/602/608 612/614/608 +f 603/604/606 609/610/606 613/597/606 +f 609/610/603 602/603/603 614/615/603 +f 604/605/602 600/602/602 615/616/602 +f 600/602/605 608/609/605 615/616/605 +f 608/609/609 604/605/609 615/616/609 +f 601/606/610 605/607/610 616/617/610 +f 604/605/611 608/609/611 616/617/611 +f 608/609/612 601/606/612 616/617/612 +f 616/617/613 611/613/613 617/618/613 +f 611/613/602 604/605/602 617/618/602 +f 604/605/614 616/617/614 617/618/614 +f 599/600/615 611/613/615 618/619/615 +f 616/617/610 605/607/610 618/619/610 +f 611/613/616 616/617/616 618/619/616 +f 602/603/603 599/600/603 619/620/603 +f 605/607/604 602/603/604 619/620/604 +f 599/600/617 618/619/617 619/620/617 +f 618/619/618 605/607/618 619/620/618 +f 597/612/619 606/608/619 620/621/619 +f 610/611/620 597/612/620 620/621/620 +f 606/608/621 612/614/621 620/621/621 +f 600/602/602 603/604/602 621/622/602 +f 612/614/608 600/602/608 621/622/608 +f 602/603/622 610/611/622 622/623/622 +f 614/615/603 602/603/603 622/623/603 +f 607/624/623 614/615/623 622/623/623 +f 606/608/604 601/606/604 623/625/604 +f 601/606/612 608/609/612 623/625/612 +f 608/609/605 606/608/605 623/625/605 +f 610/611/624 607/624/624 624/626/624 +f 622/623/622 610/611/622 624/626/622 +f 607/624/623 622/623/623 624/626/623 +f 607/624/625 610/611/625 625/598/625 +f 613/597/626 609/610/626 625/598/626 +f 614/615/627 607/624/627 625/598/627 +f 609/610/628 614/615/628 625/598/628 +f 610/611/629 620/621/629 625/598/629 +f 625/598/630 620/621/630 626/599/630 +f 603/604/631 613/597/631 626/599/631 +f 620/621/632 612/614/632 626/599/632 +f 621/622/633 603/604/633 626/599/633 +f 612/614/634 621/622/634 626/599/634 +o Cup_hull_26 +v -0.020654 0.014632 0.050164 +v -0.014335 0.020690 0.033584 +v -0.014335 0.017793 0.033584 +v -0.023815 0.008313 0.033584 +v -0.022761 0.008313 0.050164 +v -0.014335 0.019373 0.050164 +v -0.021180 0.008578 0.034149 +v -0.020127 0.015422 0.033584 +v -0.015388 0.020163 0.050164 +v -0.023288 0.009895 0.050164 +v -0.021708 0.013055 0.033584 +v -0.016968 0.018846 0.033584 +v -0.018549 0.017265 0.050164 +v -0.023815 0.008313 0.050164 +v -0.021444 0.008313 0.033584 +v -0.014335 0.020690 0.050164 +v -0.021708 0.013055 0.050164 +v -0.023288 0.009895 0.033584 +v -0.022497 0.008578 0.050164 +v -0.014598 0.020690 0.033584 +v -0.014335 0.017793 0.034430 +v -0.021444 0.008313 0.035272 +v -0.018812 0.017002 0.033584 +v -0.016968 0.018846 0.050164 +v -0.023815 0.008578 0.050164 +v -0.015388 0.020163 0.033584 +v -0.023815 0.008578 0.033584 +v -0.019865 0.015685 0.050164 +v -0.014598 0.020690 0.050164 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.765955 +vt 1.000000 0.000000 +vt 0.000000 0.893598 +vt 0.000000 0.510572 +vt 0.000000 0.000000 +vt 1.000000 0.574393 +vt 0.000000 0.957420 +vt 0.000000 0.127839 +vt 1.000000 0.383124 +vt 1.000000 0.851018 +vt 0.000000 0.723277 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 0.965936 0.021437 +vt 0.000000 0.383124 +vt 1.000000 0.127839 +vt 0.000000 0.021437 +vt 0.949002 0.765955 +vt 0.898199 0.000000 +vt 1.000000 0.702036 +vt 0.000000 0.851018 +vt 0.000000 0.021437 +vt 1.000000 0.957420 +vt 1.000000 0.021437 +vt 0.000000 0.595634 +vn 0.0000 1.0000 0.0000 +vn -0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.7967 -0.5975 -0.0911 +vn -0.8316 0.5553 0.0000 +vn -0.8317 0.5552 0.0000 +vn -0.8944 0.4473 0.0000 +vn 0.8027 -0.5963 0.0000 +vn 0.8012 -0.5966 0.0471 +vn 0.7095 -0.7047 0.0000 +vn 0.7081 -0.7034 0.0626 +vn 0.7958 -0.6018 0.0670 +vn 0.8011 -0.5955 0.0598 +vn -0.7073 0.7070 0.0000 +vn -0.6402 0.7682 0.0000 +vn -0.7071 0.7071 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.9284 0.3716 0.0000 +vn -0.5551 0.8318 0.0000 +vn -0.8000 0.6001 0.0032 +vn 0.0001 0.0000 1.0000 +vn -0.7686 0.6397 0.0020 +vn -0.7684 0.6400 0.0021 +usemtl None +s off +f 642/627/635 646/628/635 655/629/635 +f 628/630/636 629/631/636 630/632/636 +f 629/631/637 628/630/637 632/633/637 +f 627/634/638 631/635/638 632/633/638 +f 628/630/636 630/632/636 634/636/636 +f 627/634/638 632/633/638 635/637/638 +f 631/635/638 627/634/638 636/638/638 +f 634/636/636 630/632/636 637/639/636 +f 628/630/636 634/636/636 638/640/636 +f 627/634/638 635/637/638 639/641/638 +f 630/632/639 631/635/639 640/642/639 +f 631/635/638 636/638/638 640/642/638 +f 630/632/636 629/631/636 641/643/636 +f 631/635/639 630/632/639 641/643/639 +f 629/631/640 633/644/640 641/643/640 +f 632/633/637 628/630/637 642/627/637 +f 635/637/638 632/633/638 642/627/638 +f 627/634/641 634/636/641 643/645/641 +f 636/638/638 627/634/638 643/645/638 +f 634/636/642 637/639/642 643/645/642 +f 637/639/643 636/638/643 643/645/643 +f 637/639/636 630/632/636 644/646/636 +f 636/638/643 637/639/643 644/646/643 +f 632/633/638 631/635/638 645/647/638 +f 628/630/636 638/640/636 646/628/636 +f 642/627/635 628/630/635 646/628/635 +f 629/631/637 632/633/637 647/648/637 +f 633/644/644 629/631/644 647/648/644 +f 633/644/645 647/648/645 648/649/645 +f 631/635/639 641/643/639 648/649/639 +f 641/643/646 633/644/646 648/649/646 +f 645/647/647 631/635/647 648/649/647 +f 632/633/648 645/647/648 648/649/648 +f 647/648/649 632/633/649 648/649/649 +f 638/640/636 634/636/636 649/650/636 +f 649/650/650 639/641/650 650/651/650 +f 635/637/651 638/640/651 650/651/651 +f 639/641/638 635/637/638 650/651/638 +f 638/640/652 649/650/652 650/651/652 +f 630/632/653 640/642/653 651/652/653 +f 640/642/638 636/638/638 651/652/638 +f 636/638/654 644/646/654 651/652/654 +f 638/640/651 635/637/651 652/653/651 +f 646/628/636 638/640/636 652/653/636 +f 635/637/655 646/628/655 652/653/655 +f 644/646/636 630/632/636 653/654/636 +f 630/632/653 651/652/653 653/654/653 +f 651/652/654 644/646/654 653/654/654 +f 634/636/656 627/634/656 654/655/656 +f 627/634/657 639/641/657 654/655/657 +f 649/650/658 634/636/658 654/655/658 +f 639/641/659 649/650/659 654/655/659 +f 635/637/638 642/627/638 655/629/638 +f 646/628/655 635/637/655 655/629/655 +o Cup_hull_27 +v -0.023550 0.008578 0.017568 +v -0.014335 0.020690 0.017848 +v -0.014335 0.020426 0.015039 +v -0.015915 0.008313 0.015882 +v -0.021180 0.008313 0.033582 +v -0.014335 0.020690 0.033582 +v -0.021708 0.013055 0.033582 +v -0.020127 0.015422 0.015039 +v -0.014335 0.017529 0.033301 +v -0.014335 0.010684 0.015039 +v -0.023815 0.008313 0.033582 +v -0.016968 0.018845 0.033582 +v -0.020654 0.008313 0.015039 +v -0.023288 0.009895 0.018411 +v -0.017233 0.018582 0.015039 +v -0.018812 0.017002 0.033582 +v -0.015388 0.020163 0.016724 +v -0.021708 0.013055 0.018411 +v -0.023815 0.008313 0.018411 +v -0.023288 0.009895 0.033582 +v -0.016179 0.008313 0.017005 +v -0.020127 0.015422 0.033582 +v -0.014598 0.020690 0.033582 +v -0.015915 0.008313 0.015039 +v -0.014335 0.010947 0.016443 +v -0.018812 0.017002 0.015039 +v -0.014335 0.017793 0.033582 +v -0.020391 0.014895 0.015039 +v -0.023815 0.008578 0.018411 +v -0.015388 0.020163 0.033582 +v -0.022761 0.008313 0.016724 +v -0.014862 0.020426 0.015039 +v -0.014598 0.020690 0.017848 +v -0.023815 0.008578 0.033582 +vt 0.000000 0.127839 +vt 0.818191 0.021437 +vt 0.000000 0.021437 +vt 1.000000 0.978661 +vt 0.848541 1.000000 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 0.000000 0.383125 +vt 0.015175 0.744616 +vt 1.000000 0.574393 +vt 1.000000 0.191562 +vt 0.954572 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.850920 +vt 1.000000 0.000000 +vt 1.000000 0.829679 +vt 0.000000 0.702036 +vt 0.909144 0.957420 +vt 0.818191 0.383125 +vt 0.818191 0.127839 +vt 0.818191 0.000000 +vt 0.893969 0.000000 +vt 0.000000 0.574393 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.924320 0.212803 +vt 1.000000 0.702036 +vt 0.000000 0.765955 +vt 1.000000 0.531813 +vt 0.863619 0.021437 +vt 0.000000 0.957420 +vt 0.909144 0.000000 +vt 1.000000 0.978661 +vt 0.848541 1.000000 +vn -0.9284 0.3716 0.0000 +vn 1.0000 0.0000 0.0000 +vn -0.0000 0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.7069 0.7073 0.0001 +vn -0.6500 0.7600 -0.0015 +vn -0.8317 0.5552 0.0000 +vn -0.8895 0.4449 -0.1046 +vn -0.8944 0.4473 0.0000 +vn 0.7835 -0.5747 0.2364 +vn -0.7686 0.6397 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.8321 -0.5546 0.0000 +vn 0.8439 -0.5274 0.0988 +vn 0.8227 -0.5347 0.1929 +vn 0.8217 -0.5309 0.2073 +vn -0.7072 0.7070 0.0000 +vn 0.7105 -0.5131 0.4816 +vn -0.8895 0.4448 -0.1047 +vn -0.9014 0.3608 -0.2395 +vn -0.9541 0.0000 -0.2995 +vn -1.0000 0.0000 0.0000 +vn -0.8985 0.3365 -0.2821 +vn -0.6405 0.7679 0.0000 +vn -0.5551 0.8318 0.0000 +vn -0.6501 -0.6421 -0.4063 +vn -0.7153 0.0799 -0.6942 +vn -0.6244 0.0250 -0.7807 +vn 0.0000 0.9956 -0.0936 +vn -0.6125 0.7875 -0.0684 +vn -0.5241 0.8511 -0.0309 +usemtl None +s off +f 675/656/660 684/657/660 689/658/660 +f 658/659/661 657/660/661 661/661/661 +f 660/662/662 661/661/662 662/663/662 +f 658/659/661 661/661/661 664/664/661 +f 663/665/663 658/659/663 665/666/663 +f 658/659/661 664/664/661 665/666/661 +f 659/667/664 660/662/664 666/668/664 +f 660/662/662 662/663/662 666/668/662 +f 662/663/662 661/661/662 667/669/662 +f 663/665/663 665/666/663 668/670/663 +f 659/667/664 666/668/664 668/670/664 +f 658/659/663 663/665/663 670/671/663 +f 667/669/665 670/671/665 671/672/665 +f 662/663/662 667/669/662 671/672/662 +f 670/671/666 667/669/666 672/673/666 +f 662/663/667 663/665/667 673/674/667 +f 663/665/668 669/675/668 673/674/668 +f 669/675/669 662/663/669 673/674/669 +f 668/670/664 666/668/664 674/676/664 +f 666/668/662 662/663/662 675/656/662 +f 662/663/669 669/675/669 675/656/669 +f 660/662/664 659/667/664 676/677/664 +f 664/664/670 660/662/670 676/677/670 +f 663/665/667 662/663/667 677/678/667 +f 662/663/662 671/672/662 677/678/662 +f 671/672/671 663/665/671 677/678/671 +f 661/661/672 657/660/672 678/679/672 +f 667/669/662 661/661/662 678/679/662 +f 665/666/673 659/667/673 679/680/673 +f 668/670/663 665/666/663 679/680/663 +f 659/667/664 668/670/664 679/680/664 +f 659/667/674 665/666/674 680/681/674 +f 665/666/661 664/664/661 680/681/661 +f 676/677/675 659/667/675 680/681/675 +f 664/664/676 676/677/676 680/681/676 +f 670/671/663 663/665/663 681/682/663 +f 671/672/677 670/671/677 681/682/677 +f 663/665/671 671/672/671 681/682/671 +f 661/661/662 660/662/662 682/683/662 +f 660/662/678 664/664/678 682/683/678 +f 664/664/661 661/661/661 682/683/661 +f 663/665/663 668/670/663 683/684/663 +f 669/675/679 663/665/679 683/684/679 +f 669/675/680 683/684/680 684/657/680 +f 656/685/681 674/676/681 684/657/681 +f 674/676/682 666/668/682 684/657/682 +f 675/656/660 669/675/660 684/657/660 +f 683/684/683 656/685/683 684/657/683 +f 672/673/684 667/669/684 685/686/684 +f 667/669/662 678/679/662 685/686/662 +f 678/679/685 672/673/685 685/686/685 +f 674/676/686 656/685/686 686/687/686 +f 668/670/664 674/676/664 686/687/664 +f 656/685/687 683/684/687 686/687/687 +f 683/684/688 668/670/688 686/687/688 +f 657/660/689 658/659/689 687/688/689 +f 658/659/663 670/671/663 687/688/663 +f 670/671/690 672/673/690 687/688/690 +f 678/679/672 657/660/672 688/689/672 +f 672/673/685 678/679/685 688/689/685 +f 657/660/689 687/688/689 688/689/689 +f 687/688/691 672/673/691 688/689/691 +f 666/668/662 675/656/662 689/658/662 +f 684/657/682 666/668/682 689/658/682 +o Cup_hull_28 +v 0.018582 -0.017233 0.015041 +v 0.008313 -0.023815 0.050164 +v 0.008579 -0.023815 0.050164 +v 0.019372 -0.014335 0.050164 +v 0.008313 -0.015916 0.015041 +v 0.008313 -0.023815 0.018414 +v 0.020425 -0.014335 0.015041 +v 0.015421 -0.020128 0.050164 +v 0.010685 -0.014335 0.015041 +v 0.015421 -0.020128 0.015041 +v 0.020689 -0.014598 0.050164 +v 0.008579 -0.022497 0.050164 +v 0.013054 -0.021707 0.018414 +v 0.008313 -0.020653 0.015041 +v 0.018055 -0.017759 0.050164 +v 0.008313 -0.015916 0.015883 +v 0.013056 -0.021707 0.050164 +v 0.009895 -0.023288 0.018132 +v 0.020688 -0.014599 0.017850 +v 0.017002 -0.018812 0.015041 +v 0.009105 -0.023023 0.017008 +v 0.020689 -0.014335 0.050164 +v 0.019898 -0.015651 0.050164 +v 0.009896 -0.023288 0.050164 +v 0.017001 -0.018812 0.050164 +v 0.008313 -0.022760 0.050164 +v 0.019899 -0.015652 0.015041 +v 0.018581 -0.017233 0.050164 +v 0.010948 -0.014335 0.016444 +v 0.008578 -0.023815 0.018414 +v 0.014896 -0.020391 0.015041 +v 0.020688 -0.014335 0.017850 +v 0.008578 -0.023550 0.017568 +vt 1.000000 0.531911 +vt 0.911992 0.127839 +vt 0.928047 0.021437 +vt 0.000000 0.000000 +vt 0.000000 0.021535 +vt 0.000000 0.893598 +vt 1.000000 0.000000 +vt 0.903965 0.000000 +vt 1.000000 0.829777 +vt 1.000000 0.978661 +vt 0.000000 0.574393 +vt 1.000000 0.191660 +vt 1.000000 0.574393 +vt 0.000000 1.000000 +vt 0.000000 0.021535 +vt 1.000000 0.000000 +vt 0.000000 0.787197 +vt 0.976016 0.000000 +vt 0.000000 0.383222 +vt 0.903965 0.383124 +vt 1.000000 0.702134 +vt 0.000000 1.000000 +vt 0.920020 0.999902 +vt 0.000000 0.936081 +vt 0.000000 0.127937 +vt 0.000000 0.702036 +vt 0.000000 0.000000 +vt 1.000000 0.936179 +vt 0.000000 0.829679 +vt 0.960059 0.212901 +vt 0.903965 0.021437 +vt 0.944004 0.064017 +vt 0.920020 0.999902 +vn 0.3165 -0.8917 -0.3237 +vn 0.0000 0.0000 1.0000 +vn -1.0000 -0.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 1.0000 0.0000 +vn -0.5547 0.8321 0.0000 +vn -0.5958 0.7878 0.1559 +vn 0.5550 -0.8318 0.0000 +vn 0.5548 -0.8320 -0.0000 +vn 0.4476 -0.8942 -0.0000 +vn 0.4524 -0.8865 -0.0974 +vn 0.6397 -0.7686 0.0000 +vn 0.7070 -0.7072 0.0000 +vn 1.0000 0.0000 -0.0000 +vn 0.3716 -0.9284 -0.0000 +vn 0.6400 -0.7683 0.0000 +vn 0.7069 -0.7073 0.0000 +vn -0.6949 0.7052 0.1408 +vn 0.9220 -0.3679 -0.1209 +vn 0.8005 -0.5993 -0.0000 +vn 0.7996 -0.6005 0.0000 +vn 0.7684 -0.6399 0.0000 +vn 0.7074 -0.7068 0.0000 +vn 0.7683 -0.6401 0.0000 +vn -0.5306 0.8372 0.1326 +vn -0.5274 0.8438 0.0988 +vn 0.4439 -0.8887 -0.1148 +vn 0.0253 -0.6334 -0.7734 +vn 0.9957 0.0000 -0.0932 +vn -0.8238 -0.4136 -0.3877 +vn -0.1297 -0.6585 -0.7413 +vn 0.0000 -0.9544 -0.2984 +vn 0.3032 -0.9095 -0.2844 +vn 0.1567 -0.7887 -0.5944 +usemtl None +s off +f 720/690/692 707/691/692 722/692/692 +f 691/693/693 692/694/693 693/695/693 +f 691/693/694 694/696/694 695/697/694 +f 692/694/695 691/693/695 695/697/695 +f 690/698/696 694/696/696 696/699/696 +f 693/695/693 692/694/693 697/700/693 +f 693/695/697 696/699/697 698/701/697 +f 696/699/696 694/696/696 698/701/696 +f 694/696/696 690/698/696 699/702/696 +f 693/695/693 697/700/693 700/703/693 +f 691/693/693 693/695/693 701/704/693 +f 695/697/694 694/696/694 703/705/694 +f 694/696/696 699/702/696 703/705/696 +f 700/703/693 697/700/693 704/706/693 +f 694/696/694 691/693/694 705/707/694 +f 698/701/698 694/696/698 705/707/698 +f 701/704/699 693/695/699 705/707/699 +f 697/700/693 692/694/693 706/708/693 +f 699/702/700 697/700/700 706/708/700 +f 702/709/701 699/702/701 706/708/701 +f 702/709/702 706/708/702 707/691/702 +f 699/702/703 702/709/703 707/691/703 +f 699/702/696 690/698/696 709/710/696 +f 697/700/704 699/702/704 709/710/704 +f 690/698/705 704/706/705 709/710/705 +f 696/699/697 693/695/697 711/711/697 +f 693/695/693 700/703/693 711/711/693 +f 700/703/706 708/712/706 711/711/706 +f 700/703/693 704/706/693 712/713/693 +f 706/708/693 692/694/693 713/714/693 +f 707/691/702 706/708/702 713/714/702 +f 692/694/707 707/691/707 713/714/707 +f 704/706/693 697/700/693 714/715/693 +f 697/700/708 709/710/708 714/715/708 +f 709/710/709 704/706/709 714/715/709 +f 691/693/693 701/704/693 715/716/693 +f 705/707/694 691/693/694 715/716/694 +f 701/704/710 705/707/710 715/716/710 +f 690/698/696 696/699/696 716/717/696 +f 696/699/711 708/712/711 716/717/711 +f 708/712/712 700/703/712 716/717/712 +f 700/703/713 712/713/713 716/717/713 +f 716/717/714 712/713/714 717/718/714 +f 704/706/715 690/698/715 717/718/715 +f 712/713/693 704/706/693 717/718/693 +f 690/698/716 716/717/716 717/718/716 +f 693/695/697 698/701/697 718/719/697 +f 705/707/717 693/695/717 718/719/717 +f 698/701/718 705/707/718 718/719/718 +f 692/694/695 695/697/695 719/720/695 +f 707/691/707 692/694/707 719/720/707 +f 703/705/696 699/702/696 720/690/696 +f 699/702/719 707/691/719 720/690/719 +f 710/721/720 703/705/720 720/690/720 +f 708/712/721 696/699/721 721/722/721 +f 696/699/697 711/711/697 721/722/697 +f 711/711/706 708/712/706 721/722/706 +f 695/697/722 703/705/722 722/692/722 +f 703/705/723 710/721/723 722/692/723 +f 719/720/724 695/697/724 722/692/724 +f 707/691/725 719/720/725 722/692/725 +f 710/721/726 720/690/726 722/692/726 +o Cup_hull_29 +v -0.020392 -0.000377 0.015036 +v -0.016441 0.007259 -0.048198 +v -0.016441 0.006732 -0.048198 +v -0.020392 0.007259 -0.048198 +v -0.016441 0.007259 0.015036 +v -0.018022 -0.000377 -0.048198 +v -0.020392 0.007259 0.015036 +v -0.018022 -0.000377 0.015036 +v -0.020392 -0.000377 -0.048198 +v -0.016441 0.006732 0.013624 +vt 0.000000 0.000000 +vt 1.000000 0.930991 +vt 0.022318 0.930991 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vn 0.9762 -0.2170 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.9765 -0.2021 0.0755 +usemtl None +s off +f 730/723/727 725/724/727 732/725/727 +f 724/726/728 725/724/728 726/727/728 +f 725/724/729 724/726/729 727/728/729 +f 724/726/730 726/727/730 727/728/730 +f 726/727/728 725/724/728 728/729/728 +f 726/727/731 723/730/731 729/731/731 +f 723/730/732 727/728/732 729/731/732 +f 727/728/730 726/727/730 729/731/730 +f 727/728/732 723/730/732 730/723/732 +f 728/729/727 725/724/727 730/723/727 +f 723/730/733 728/729/733 730/723/733 +f 723/730/731 726/727/731 731/732/731 +f 726/727/728 728/729/728 731/732/728 +f 728/729/733 723/730/733 731/732/733 +f 725/724/729 727/728/729 732/725/729 +f 727/728/734 730/723/734 732/725/734 +o Cup_hull_30 +v 0.017529 0.018321 0.034429 +v 0.008314 0.022795 0.050166 +v 0.008314 0.023587 0.050166 +v 0.021217 0.013580 0.050166 +v 0.018582 0.013580 0.034429 +v 0.008314 0.021480 0.034429 +v 0.015686 0.019899 0.050166 +v 0.009894 0.023322 0.034429 +v 0.019899 0.013580 0.050166 +v 0.021217 0.013844 0.034429 +v 0.019899 0.015687 0.050166 +v 0.012527 0.022006 0.050166 +v 0.013843 0.021216 0.034429 +v 0.008314 0.023587 0.034429 +v 0.008314 0.021480 0.035553 +v 0.009105 0.023587 0.050166 +v 0.008314 0.022533 0.048477 +v 0.017793 0.018057 0.050166 +v 0.019899 0.015687 0.034429 +v 0.018582 0.013580 0.035553 +v 0.021217 0.013580 0.034429 +v 0.015686 0.019899 0.034429 +v 0.021217 0.013844 0.050166 +v 0.018319 0.017530 0.034429 +v 0.012527 0.022006 0.034429 +v 0.014633 0.020688 0.050166 +v 0.010421 0.023059 0.050166 +v 0.009105 0.023587 0.034429 +v 0.018319 0.017530 0.050166 +v 0.020689 0.014634 0.050166 +vt 0.000000 0.897905 +vt 0.000000 1.000000 +vt 0.000000 0.959084 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 1.000000 0.714174 +vt 1.000000 0.795810 +vt 0.000000 0.571359 +vt 1.000000 0.122455 +vt 0.000000 0.897905 +vt 1.000000 1.000000 +vt 0.000000 0.326547 +vt 1.000000 0.428543 +vt 1.000000 0.000000 +vt 0.928543 0.000000 +vt 0.000000 0.061276 +vt 0.107283 0.000000 +vt 0.000000 0.734632 +vt 1.000000 0.897905 +vt 0.928543 0.795810 +vt 1.000000 1.000000 +vt 1.000000 0.571359 +vt 1.000000 0.775450 +vt 1.000000 0.326547 +vt 0.000000 0.489722 +vt 0.000000 0.163273 +vt 1.000000 0.061276 +vt 0.000000 0.775450 +vn 0.0001 0.0000 1.0000 +vn 0.0000 0.0000 1.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.6098 -0.7926 0.0000 +vn 0.0000 1.0000 0.0000 +vn -0.6179 -0.7769 0.1208 +vn -0.6160 -0.7851 0.0640 +vn 0.6581 0.7529 0.0016 +vn -0.6089 -0.7914 0.0549 +vn 1.0000 0.0000 0.0000 +vn 0.6504 0.7596 0.0000 +vn 0.7070 0.7072 -0.0000 +vn 0.7593 0.6508 0.0000 +vn 0.4472 0.8945 0.0000 +vn 0.5144 0.8575 0.0000 +vn 0.5305 0.8477 0.0018 +vn 0.5997 0.8002 0.0000 +vn 0.5816 0.8135 -0.0019 +vn 0.4471 0.8945 0.0000 +vn 0.3723 0.9281 0.0031 +vn 0.3177 0.9482 0.0000 +vn 0.7073 0.7069 0.0000 +vn 0.8001 0.5998 0.0000 +vn 0.8136 0.5814 -0.0019 +vn 0.8316 0.5554 0.0000 +usemtl None +s off +f 743/733/735 755/734/735 762/735/735 +f 735/736/736 734/737/736 736/738/736 +f 734/737/737 735/736/737 738/739/737 +f 733/740/738 737/741/738 738/739/738 +f 735/736/736 736/738/736 739/742/736 +f 733/740/738 738/739/738 740/743/738 +f 736/738/736 734/737/736 741/744/736 +f 737/741/739 736/738/739 741/744/739 +f 737/741/738 733/740/738 742/745/738 +f 739/742/736 736/738/736 743/733/736 +f 735/736/736 739/742/736 744/746/736 +f 733/740/738 740/743/738 745/747/738 +f 738/739/737 735/736/737 746/748/737 +f 740/743/738 738/739/738 746/748/738 +f 734/737/737 738/739/737 747/749/737 +f 738/739/740 737/741/740 747/749/740 +f 735/736/736 744/746/736 748/750/736 +f 746/748/741 735/736/741 748/750/741 +f 741/744/742 734/737/742 749/751/742 +f 734/737/737 747/749/737 749/751/737 +f 747/749/743 741/744/743 749/751/743 +f 733/740/744 739/742/744 750/752/744 +f 739/742/736 743/733/736 750/752/736 +f 742/745/738 733/740/738 751/753/738 +f 737/741/739 741/744/739 752/754/739 +f 747/749/740 737/741/740 752/754/740 +f 741/744/745 747/749/745 752/754/745 +f 736/738/739 737/741/739 753/755/739 +f 742/745/746 736/738/746 753/755/746 +f 737/741/738 742/745/738 753/755/738 +f 739/742/747 733/740/747 754/756/747 +f 733/740/738 745/747/738 754/756/738 +f 736/738/746 742/745/746 755/734/746 +f 743/733/736 736/738/736 755/734/736 +f 733/740/748 750/752/748 756/757/748 +f 743/733/749 751/753/749 756/757/749 +f 751/753/738 733/740/738 756/757/738 +f 740/743/750 744/746/750 757/758/750 +f 745/747/738 740/743/738 757/758/738 +f 744/746/751 745/747/751 757/758/751 +f 744/746/736 739/742/736 758/759/736 +f 745/747/752 744/746/752 758/759/752 +f 739/742/753 754/756/753 758/759/753 +f 754/756/754 745/747/754 758/759/754 +f 744/746/755 740/743/755 759/760/755 +f 748/750/736 744/746/736 759/760/736 +f 740/743/756 748/750/756 759/760/756 +f 740/743/738 746/748/738 760/761/738 +f 748/750/757 740/743/757 760/761/757 +f 746/748/741 748/750/741 760/761/741 +f 750/752/736 743/733/736 761/762/736 +f 756/757/758 750/752/758 761/762/758 +f 743/733/749 756/757/749 761/762/749 +f 751/753/759 743/733/759 762/735/759 +f 742/745/760 751/753/760 762/735/760 +f 755/734/761 742/745/761 762/735/761 +o Cup_hull_31 +v 0.019899 0.015687 0.015038 +v 0.008313 0.021479 0.034427 +v 0.008313 0.023586 0.034427 +v 0.021215 0.013581 0.034427 +v 0.008577 0.015687 0.015038 +v 0.008313 0.023586 0.017568 +v 0.014633 0.020689 0.034427 +v 0.012262 0.013581 0.017568 +v 0.014896 0.020425 0.015038 +v 0.020425 0.013581 0.015038 +v 0.018319 0.013581 0.034143 +v 0.018319 0.017531 0.034427 +v 0.010421 0.023059 0.018129 +v 0.008313 0.020425 0.015038 +v 0.008313 0.016214 0.017006 +v 0.009894 0.023322 0.034427 +v 0.011737 0.013581 0.015038 +v 0.017793 0.018057 0.015038 +v 0.021215 0.013844 0.018410 +v 0.020689 0.014634 0.034427 +v 0.012526 0.022005 0.018129 +v 0.008313 0.021215 0.033862 +v 0.015685 0.019899 0.034427 +v 0.012526 0.022005 0.034427 +v 0.009104 0.023586 0.018129 +v 0.015686 0.019899 0.015038 +v 0.018583 0.013581 0.034427 +v 0.013844 0.021215 0.018410 +v 0.017529 0.018320 0.034427 +v 0.008841 0.022795 0.016725 +v 0.019899 0.015687 0.034427 +v 0.009104 0.023586 0.034427 +v 0.021215 0.013581 0.018410 +v 0.018319 0.017531 0.015038 +v 0.020425 0.014897 0.015038 +v 0.008313 0.015951 0.015038 +v 0.021215 0.013844 0.034427 +vt 0.826057 1.000000 +vt 0.000000 0.959275 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 0.869518 0.000000 +vt 0.000000 0.489868 +vt 1.000000 0.897993 +vt 1.000000 0.020460 +vt 1.000000 0.510230 +vt 1.000000 0.938815 +vt 0.869518 0.306118 +vt 0.014683 0.775526 +vt 0.000000 0.775526 +vt 1.000000 0.000000 +vt 0.898493 0.000000 +vt 0.000000 0.122565 +vt 1.000000 0.265394 +vt 1.000000 0.734802 +vt 0.840544 0.163387 +vt 0.840544 0.326579 +vt 0.029170 0.000000 +vt 0.000000 0.571415 +vt 0.000000 0.326579 +vt 0.840544 0.061282 +vt 1.000000 0.571512 +vt 0.000000 0.795986 +vt 0.826057 0.428683 +vt 0.000000 0.714342 +vt 0.912980 0.040920 +vt 0.000000 0.897993 +vt 0.000000 0.061282 +vt 0.826057 1.000000 +vt 1.000000 0.775526 +vt 1.000000 0.938815 +vt 1.000000 0.000000 +vn 0.8325 0.5541 0.0000 +vn 0.0000 0.0000 1.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.5631 -0.8140 0.1424 +vn -0.5630 -0.8004 0.2057 +vn -0.5511 -0.8266 0.1144 +vn 0.8154 0.5789 -0.0018 +vn 0.4447 0.8885 -0.1132 +vn -0.5754 -0.7414 0.3454 +vn -0.5946 -0.7708 0.2287 +vn 0.4476 0.8943 0.0000 +vn 0.4476 0.8942 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.2744 0.8807 -0.3862 +vn 0.3600 0.9000 -0.2456 +vn 0.3714 0.9285 -0.0030 +vn 0.6002 0.7999 0.0000 +vn -0.5307 -0.6901 0.4921 +vn 0.5196 0.8536 -0.0379 +vn 0.5299 0.8481 0.0018 +vn 0.5140 0.8578 0.0000 +vn 0.5792 0.8152 -0.0017 +vn 0.5537 0.8324 -0.0223 +vn 0.7071 0.7071 0.0000 +vn 0.6583 0.7528 -0.0013 +vn 0.6504 0.7596 0.0000 +vn 0.1198 0.7605 -0.6382 +vn -0.2966 0.5968 -0.7456 +vn 0.0000 0.5799 -0.8147 +vn 0.7592 0.6508 0.0000 +vn 0.7999 0.6001 0.0000 +vn 0.0001 0.0000 1.0000 +vn 0.3161 0.9487 0.0000 +vn 0.9737 0.0000 -0.2279 +vn 1.0000 0.0000 0.0000 +vn 0.7075 0.7067 0.0000 +vn 0.8320 0.5544 -0.0217 +vn -0.7033 -0.7046 0.0943 +usemtl None +s off +f 781/763/762 782/764/762 799/765/762 +f 765/766/763 764/767/763 766/768/763 +f 764/767/764 765/766/764 768/769/764 +f 765/766/763 766/768/763 769/770/763 +f 763/771/765 767/772/765 771/773/765 +f 767/772/765 763/771/765 772/774/765 +f 766/768/766 770/775/766 772/774/766 +f 770/775/766 766/768/766 773/776/766 +f 769/770/763 766/768/763 774/777/763 +f 764/767/764 768/769/764 776/778/764 +f 771/773/765 767/772/765 776/778/765 +f 767/772/767 770/775/767 777/779/767 +f 770/775/768 773/776/768 777/779/768 +f 764/767/764 776/778/764 777/779/764 +f 765/766/763 769/770/763 778/780/763 +f 770/775/769 767/772/769 779/781/769 +f 767/772/765 772/774/765 779/781/765 +f 772/774/766 770/775/766 779/781/766 +f 763/771/765 771/773/765 780/782/765 +f 774/777/763 766/768/763 782/764/763 +f 781/763/770 763/771/770 782/764/770 +f 771/773/771 775/783/771 783/784/771 +f 773/776/772 764/767/772 784/785/772 +f 764/767/764 777/779/764 784/785/764 +f 777/779/773 773/776/773 784/785/773 +f 769/770/763 774/777/763 785/786/763 +f 778/780/763 769/770/763 786/787/763 +f 775/783/774 778/780/774 786/787/774 +f 783/784/775 775/783/775 786/787/775 +f 768/769/776 765/766/776 787/788/776 +f 771/773/777 768/769/777 787/788/777 +f 775/783/778 771/773/778 787/788/778 +f 778/780/779 775/783/779 787/788/779 +f 780/782/765 771/773/765 788/789/765 +f 769/770/780 785/786/780 788/789/780 +f 766/768/763 764/767/763 789/790/763 +f 764/767/781 773/776/781 789/790/781 +f 773/776/766 766/768/766 789/790/766 +f 771/773/782 783/784/782 790/791/782 +f 786/787/783 769/770/783 790/791/783 +f 783/784/784 786/787/784 790/791/784 +f 769/770/785 788/789/785 790/791/785 +f 788/789/786 771/773/786 790/791/786 +f 774/777/787 780/782/787 791/792/787 +f 785/786/763 774/777/763 791/792/763 +f 780/782/788 788/789/788 791/792/788 +f 788/789/789 785/786/789 791/792/789 +f 768/769/790 771/773/790 792/793/790 +f 776/778/791 768/769/791 792/793/791 +f 771/773/792 776/778/792 792/793/792 +f 763/771/793 774/777/793 793/794/793 +f 782/764/794 763/771/794 793/794/794 +f 774/777/795 782/764/795 793/794/795 +f 765/766/763 778/780/763 794/795/763 +f 787/788/776 765/766/776 794/795/776 +f 778/780/796 787/788/796 794/795/796 +f 766/768/766 772/774/766 795/796/766 +f 772/774/797 781/763/797 795/796/797 +f 781/763/798 766/768/798 795/796/798 +f 774/777/793 763/771/793 796/797/793 +f 763/771/765 780/782/765 796/797/765 +f 780/782/799 774/777/799 796/797/799 +f 772/774/765 763/771/765 797/798/765 +f 763/771/800 781/763/800 797/798/800 +f 781/763/797 772/774/797 797/798/797 +f 776/778/765 767/772/765 798/799/765 +f 767/772/801 777/779/801 798/799/801 +f 777/779/764 776/778/764 798/799/764 +f 766/768/798 781/763/798 799/765/798 +f 782/764/763 766/768/763 799/765/763 +o Cup_hull_32 +v 0.004626 -0.019601 -0.043977 +v -0.002221 -0.020391 0.015036 +v 0.001203 -0.020392 -0.005762 +v 0.004626 -0.017495 0.015036 +v -0.002221 -0.017758 -0.048198 +v -0.002221 -0.020391 -0.048198 +v -0.002221 -0.017758 0.014751 +v 0.004626 -0.020392 0.015036 +v 0.004625 -0.017495 -0.048198 +v 0.004625 -0.020392 -0.048198 +v 0.003308 -0.017495 0.013624 +v 0.003308 -0.017495 -0.048198 +v -0.002221 -0.018022 0.015036 +vt 0.000000 1.000000 +vt 0.004503 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 1.000000 0.000000 +vt 0.328896 0.500000 +vt 0.000000 1.000000 +vt 0.933242 1.000000 +vt 1.000000 0.999902 +vt 1.000000 0.999902 +vt 0.022318 0.807557 +vt 1.000000 0.807557 +vn -0.0564 0.7329 0.6780 +vn -1.0000 0.0000 0.0000 +vn -0.0001 -1.0000 0.0000 +vn -0.0000 -1.0000 0.0000 +vn -0.0000 0.0000 1.0000 +vn 1.0000 0.0000 0.0000 +vn 1.0000 0.0003 -0.0000 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 -0.0008 -0.0000 +vn 1.0000 0.0000 -0.0002 +vn -0.0399 0.9985 0.0373 +vn -0.0475 0.9989 0.0000 +vn 0.0000 1.0000 0.0000 +usemtl None +s off +f 803/800/802 806/801/802 812/802/802 +f 801/803/803 804/804/803 805/805/803 +f 802/806/804 801/803/804 805/805/804 +f 804/804/803 801/803/803 806/801/803 +f 801/803/805 802/806/805 807/807/805 +f 803/800/806 801/803/806 807/807/806 +f 800/808/807 803/800/807 807/807/807 +f 803/800/808 800/808/808 808/809/808 +f 805/805/809 804/804/809 808/809/809 +f 802/806/805 805/805/805 809/810/805 +f 807/807/805 802/806/805 809/810/805 +f 800/808/810 807/807/810 809/810/810 +f 808/809/811 800/808/811 809/810/811 +f 805/805/809 808/809/809 809/810/809 +f 806/801/812 803/800/812 810/811/812 +f 804/804/813 806/801/813 810/811/813 +f 803/800/814 808/809/814 810/811/814 +f 810/811/814 808/809/814 811/812/814 +f 808/809/809 804/804/809 811/812/809 +f 804/804/813 810/811/813 811/812/813 +f 801/803/806 803/800/806 812/802/806 +f 806/801/803 801/803/803 812/802/803 +o Cup_hull_33 +v 0.011736 -0.013546 -0.048198 +v 0.004626 -0.020391 0.015036 +v 0.007524 -0.020392 0.007726 +v 0.012262 -0.013282 0.015036 +v 0.012263 -0.020392 -0.048192 +v 0.004626 -0.017231 -0.048198 +v 0.012262 -0.020392 0.015036 +v 0.004626 -0.020391 -0.048198 +v 0.004626 -0.017231 0.014751 +v 0.011999 -0.013282 -0.048192 +v 0.012263 -0.013282 -0.048192 +v 0.011473 -0.013546 0.008289 +v 0.011999 -0.013282 0.015036 +v 0.011473 -0.013546 -0.043420 +v 0.004890 -0.017231 0.015036 +vt 0.000000 0.965446 +vt 0.004503 0.000000 +vt 0.000000 0.034554 +vt 0.000000 0.000000 +vt 0.115603 0.379405 +vt 0.000000 0.999902 +vt 0.000000 0.999902 +vt 0.999902 1.000000 +vt 1.000000 0.000000 +vt 1.000000 0.930991 +vt 1.000000 0.000000 +vt 0.999902 0.965446 +vt 0.999902 1.000000 +vt 0.106695 0.896535 +vt 0.924432 0.896535 +vn -0.4428 0.7971 0.4104 +vn -0.0001 -1.0000 0.0001 +vn 0.0000 0.0000 1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.0002 -1.0000 0.0000 +vn 0.0008 -0.0008 -1.0000 +vn -0.0001 -1.0000 -0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.0000 0.0000 -1.0000 +vn -0.0252 0.0485 -0.9985 +vn 0.0000 1.0000 -0.0000 +vn 0.0118 0.0000 -0.9999 +vn 0.0000 0.0235 -0.9997 +vn -0.4740 0.8805 0.0000 +vn -0.4481 0.8940 0.0000 +vn -0.4722 0.8815 0.0024 +vn -0.4722 0.8815 -0.0034 +vn -0.7321 0.0611 0.6785 +usemtl None +s off +f 825/813/815 821/814/815 827/815/815 +f 814/816/816 815/817/816 819/818/816 +f 816/819/817 814/816/817 819/818/817 +f 817/820/818 816/819/818 819/818/818 +f 815/817/819 817/820/819 819/818/819 +f 815/817/820 814/816/820 820/821/820 +f 813/822/821 817/820/821 820/821/821 +f 817/820/822 815/817/822 820/821/822 +f 814/816/823 818/823/823 820/821/823 +f 818/823/824 813/822/824 820/821/824 +f 818/823/823 814/816/823 821/814/823 +f 813/822/825 818/823/825 822/824/825 +f 822/824/826 816/819/826 823/825/826 +f 817/820/827 813/822/827 823/825/827 +f 816/819/818 817/820/818 823/825/818 +f 813/822/828 822/824/828 823/825/828 +f 818/823/829 821/814/829 824/826/829 +f 822/824/830 824/826/830 825/813/830 +f 814/816/817 816/819/817 825/813/817 +f 816/819/826 822/824/826 825/813/826 +f 824/826/831 821/814/831 825/813/831 +f 822/824/832 818/823/832 826/827/832 +f 818/823/829 824/826/829 826/827/829 +f 824/826/830 822/824/830 826/827/830 +f 821/814/833 814/816/833 827/815/833 +f 814/816/817 825/813/817 827/815/817 diff --git a/cram_3d_world/cram_bullet_reasoning/src/aabb.lisp b/cram_3d_world/cram_bullet_reasoning/src/aabb.lisp index 592439fa71..d98d79c6fc 100644 --- a/cram_3d_world/cram_bullet_reasoning/src/aabb.lisp +++ b/cram_3d_world/cram_bullet_reasoning/src/aabb.lisp @@ -60,10 +60,12 @@ 0.5) :dimensions (cl-transforms:v- new-max new-min)))) + (defmethod aabb ((obj object)) (reduce #'merge-bounding-boxes (mapcar #'aabb (rigid-bodies obj)))) + (defun calculate-object-bottom-pose (object) (let ((bounding-box (aabb object))) (cl-transforms:copy-pose @@ -74,12 +76,22 @@ (/ (cl-transforms:z (bounding-box-dimensions bounding-box)) 2)))))) + (defun calculate-bb-dims (bullet-object) + "Calculates bounding box dimensions, putting the object down flatly, +i.e. if the object has an angle with respect to the horizontal plane, +i.e. an angle around the X or/and Y of the fixed map frame, +removes those angles, such that the object is touching the horizontal plane +with one of its sides." (let ((old-pose (pose bullet-object)) aabb) (unwind-protect (progn - (setf (pose bullet-object) (cl-transforms:make-identity-pose)) + (setf (pose bullet-object) + (cl-transforms:make-pose + (cl-transforms:make-identity-vector) + (cram-tf:map-axis-aligned-orientation + (cl-transforms:orientation (pose bullet-object))))) (setf aabb (cl-bullet:aabb bullet-object))) (setf (pose bullet-object) old-pose)) (cl-bullet:bounding-box-dimensions aabb))) diff --git a/cram_3d_world/cram_bullet_reasoning/src/debug-window.lisp b/cram_3d_world/cram_bullet_reasoning/src/debug-window.lisp index 8a60c4ca3c..1012815295 100644 --- a/cram_3d_world/cram_bullet_reasoning/src/debug-window.lisp +++ b/cram_3d_world/cram_bullet_reasoning/src/debug-window.lisp @@ -34,9 +34,8 @@ (defvar *debug-window-lock* (sb-thread:make-mutex)) (defvar *current-costmap-function* nil "A math function object for visualizing costmaps.") (defvar *current-costmap-sample* nil "A red sphere for visualizing costmap samples.") -(defvar *vis-axis-x* nil "The X axis of an object for visualizing poses.") -(defvar *vis-axis-y* nil "The Y axis of an object for visualizing poses.") -(defvar *vis-axis-z* nil "The Z axis of an object for visualizing poses.") +(defvar *vis-axes* nil "An associative list of ((ID . (X Y Z)) ...) couples, +storing axes of a coordinate frame for visualizing poses.") (defparameter *costmap-z* 0.0) (defparameter *costmap-tilt* (cl-transforms:make-quaternion 0 0 0 1)) @@ -83,14 +82,15 @@ (setf (gl-objects *debug-window*) (remove *current-costmap-sample* (gl-objects *debug-window*))) (setf *current-costmap-sample* nil)) - (when (and *vis-axis-x* *debug-window*) - (setf (gl-objects *debug-window*) - (remove *vis-axis-z* - (remove *vis-axis-y* - (remove *vis-axis-x* (gl-objects *debug-window*))))) - (setf *vis-axis-x* nil - *vis-axis-y* nil - *vis-axis-z* nil)))) + (when (and *vis-axes* *debug-window*) + (mapcar (lambda (id-axes-pair) + (setf (gl-objects *debug-window*) + (reduce (lambda (gl-objects-list axis-object) + (remove axis-object gl-objects-list)) + (cdr id-axes-pair) + :initial-value (gl-objects *debug-window*)))) + *vis-axes*) + (setf *vis-axes* nil)))) @@ -146,21 +146,25 @@ (push *current-costmap-sample* (gl-objects *debug-window*)))))) -(defgeneric add-vis-axis-object (object-or-pose &optional length) +(defgeneric add-vis-axis-object (object-or-pose &key length id) (:documentation "Spawn a coordinate frame at a given pose or at btr:object origin. -It is built from 3 rigid bodies of primitive box shape.") +It is built from 3 rigid bodies of primitive box shape. +`Length' specified the length of a single axis. +`Id' can be used if one wants to visualize multiple frames at the same time.") - (:method ((object-name symbol) &optional (length 0.30)) + (:method ((object-name symbol) &key (length 0.30) (id 0)) (add-vis-axis-object - (btr:pose (btr:object btr:*current-bullet-world* object-name)) length)) + (pose (btr:object *current-bullet-world* object-name)) + :length length :id id)) - (:method ((pose cl-transforms:pose) &optional (length 0.30)) + (:method ((pose cl-transforms:pose) &key (length 0.30) (id 0)) (sb-thread:with-mutex (*debug-window-lock*) - (when (and *vis-axis-x* *debug-window*) + (when (and *vis-axes* *debug-window* (assoc id *vis-axes*)) (setf (gl-objects *debug-window*) - (remove *vis-axis-z* - (remove *vis-axis-y* - (remove *vis-axis-x* (gl-objects *debug-window*)))))) + (reduce (lambda (gl-objects-list axis-object) + (remove axis-object gl-objects-list)) + (cdr (assoc id *vis-axes*)) + :initial-value (gl-objects *debug-window*)))) (let ((length/2 (/ length 2)) (object-transform (cl-transforms:pose->transform pose))) @@ -181,17 +185,26 @@ It is built from 3 rigid bodies of primitive box shape.") half-extents-list) :color color)))) - (setf *vis-axis-x* - (make-axis-rigid-body `(,length/2 0 0) `(,length/2 0.01 0.01) '(0.5 0 0 0.5)) - *vis-axis-y* - (make-axis-rigid-body `(0 ,length/2 0) `(0.01 ,length/2 0.01) '(0 0.5 0 0.5)) - *vis-axis-z* - (make-axis-rigid-body `(0 0 ,length/2) `(0.01 0.01 ,length/2) '(0 0 0.5 0.5)))) + (let ((new-axes-list + (list (make-axis-rigid-body + `(,length/2 0 0) + `(,length/2 0.01 0.01) + '(0.5 0 0 0.5)) + (make-axis-rigid-body + `(0 ,length/2 0) + `(0.01 ,length/2 0.01) + '(0 0.5 0 0.5)) + (make-axis-rigid-body + `(0 0 ,length/2) + `(0.01 0.01 ,length/2) + '(0 0 0.5 0.5))))) + (if (assoc id *vis-axes*) + (rplacd (assoc id *vis-axes*) new-axes-list) + (push (cons id new-axes-list) *vis-axes*)))) (when *debug-window* - (push *vis-axis-x* (gl-objects *debug-window*)) - (push *vis-axis-y* (gl-objects *debug-window*)) - (push *vis-axis-z* (gl-objects *debug-window*))))))) + (mapc (lambda (obj) (push obj (gl-objects *debug-window*))) + (cdr (assoc id *vis-axes*)))))))) diff --git a/cram_3d_world/cram_bullet_reasoning/src/items.lisp b/cram_3d_world/cram_bullet_reasoning/src/items.lisp index f27edfbed8..1d58a7fbd3 100644 --- a/cram_3d_world/cram_bullet_reasoning/src/items.lisp +++ b/cram_3d_world/cram_bullet_reasoning/src/items.lisp @@ -2,6 +2,7 @@ ;;; Copyright (c) 2010, Lorenz Moesenlechner ;;; Gayane Kazhoyan ;;; Thomas Lipps +;;; Jonas Dech ;;; All rights reserved. ;;; ;;; Redistribution and use in source and binary forms, with or without @@ -45,8 +46,8 @@ (:pot "package://cram_bullet_reasoning/resource/pot-ww.stl" nil) (:weisswurst "package://cram_bullet_reasoning/resource/ww.stl" nil) (:bowl-original "package://cram_bullet_reasoning/resource/bowl_original.stl" t) - (:bowl "package://cram_bullet_reasoning/resource/bowl.stl" nil) - (:bowl-compound "package://cram_bullet_reasoning/resource/bowl_compound.dae" nil) + (:bowl-non-compound "package://cram_bullet_reasoning/resource/bowl_non_compound.stl" nil) + (:bowl "package://cram_bullet_reasoning/resource/bowl.dae" nil) (:fork "package://cram_bullet_reasoning/resource/fork.stl" nil) (:knife "package://cram_bullet_reasoning/resource/knife.stl" nil) (:spatula "package://cram_bullet_reasoning/resource/spatula.stl" nil) @@ -68,7 +69,8 @@ The name in the list is a keyword that is created by lispifying the filename." (if (if extension (string-equal object-extension extension) (or (string-equal object-extension "stl") - (string-equal object-extension "dae"))) + (string-equal object-extension "dae") + (string-equal object-extension "obj"))) (let* ((lisp-name (roslisp-utilities:lispify-ros-underscore-name object-filename :keyword)) (new-entry (list lisp-name @@ -95,35 +97,6 @@ The name in the list is a keyword that is created by lispifying the filename." (change-class (call-next-method) 'item :types (item-types object))) -(defgeneric item-dimensions (object) - (:method ((object item)) - (bounding-box-dimensions (aabb object))) - (:method ((object-type symbol)) - (or (cutlery-dimensions object-type) - (let ((mesh-specification (assoc object-type *mesh-files*))) - (assert - mesh-specification () - "Couldn't find a mesh for object type ~a." object-type) - (destructuring-bind (type uri &optional flip-winding-order) - mesh-specification - (declare (ignore type)) - (let ((model-filename (physics-utils:parse-uri uri))) - (with-file-cache - model model-filename (physics-utils:load-3d-model - model-filename - :flip-winding-order flip-winding-order) - (values - (physics-utils:calculate-aabb - (physics-utils:3d-model-vertices model)))))))))) - -(defgeneric cutlery-dimensions (type) - (:method ((type t)) - nil) - (:method ((type (eql :knife))) - (cl-transforms:make-3d-vector 0.1 0.01 0.005)) - (:method ((type (eql :fork))) - (cl-transforms:make-3d-vector 0.1 0.015 0.005))) - (defun make-item (world name types &optional bodies (add-to-world t)) (make-instance 'item :name name @@ -132,57 +105,167 @@ The name in the list is a keyword that is created by lispifying the filename." :add add-to-world :types types)) -(defun make-octagon-prism-shape (radius height) - "Returns a collision shape that is a octagon prism, i.e. that has an - octagon at its base." - (let ((compound-shape (make-instance 'compound-shape))) - (dotimes (i 4) - (add-child-shape compound-shape - (cl-transforms:make-pose - (cl-transforms:make-3d-vector 0 0 0) - (cl-transforms:axis-angle->quaternion - (cl-transforms:make-3d-vector 0 0 1) - (/ (* i pi) - 4))) - (make-instance - 'box-shape - :half-extents (cl-transforms:make-3d-vector - radius (* radius (sin (/ pi 8))) - (/ height 2))))) - compound-shape)) - -(defun make-cup-shape (radius height handle-size) - (let ((collision-shape (make-octagon-prism-shape radius height))) - (add-child-shape collision-shape - (cl-transforms:make-pose - (cl-transforms:make-3d-vector - (+ (* radius (cos (/ pi 8))) - (/ (cl-transforms:x handle-size) - 2)) - 0 0) - (cl-transforms:make-quaternion 0 0 0 1)) - (make-instance - 'box-shape - :half-extents (cl-transforms:v* handle-size 0.5))) - collision-shape)) +(defgeneric item-dimensions (object) + (:method ((object item)) + (calculate-bb-dims object)) + (:method ((object-type symbol)) + (let ((mesh-specification (assoc object-type *mesh-files*))) + (assert + mesh-specification () + "Couldn't find a mesh for object type ~a." object-type) + (destructuring-bind (type uri &optional flip-winding-order) + mesh-specification + (declare (ignore type)) + (let ((model-filename (physics-utils:parse-uri uri))) + (with-file-cache + model model-filename (physics-utils:load-3d-model + model-filename + :flip-winding-order flip-winding-order) + (values + (physics-utils:calculate-aabb + (physics-utils:3d-model-vertices model))))))))) +;;;;;;;;;;;;;;;;;;;;;;;;;; ATTACHMENTS ;;;;;;;;;;;;;;;;;;;;;;;;;; -;;;;;;;;;;;;;;;;;;;;; SPAWNING MESH AND PRIMITIVE-SHAPED ITEMS ;;;;;;;;;;;; +(defmethod attach-object ((other-object item) (object item) + &key attachment-type loose + skip-removing-loose link grasp) + "Attaches `object' to `other-object': adds an attachment to the +attached-objects lists of each other. `attachment-type' is a keyword +that specifies the type of attachment. `loose' specifies if the attachment +is bidirectional (nil) or unidirectional (t). In bidirectional +attachments both objects are attached to each other. In unidirectional/loose +attachments, one object is properly attached, and the other one is +loosely attached. `skip-removing-loose' should be T for attaching more objects +unidirectional. See `attach-object' above." + (declare (ignore link grasp)) ;; used in robot-model.lisp + (when (equal (name object) (name other-object)) + (warn "Cannot attach an object to itself: ~a" (name object)) + (return-from attach-object)) + (let ((existing-attachment + (find (name object) (attached-objects other-object) :key #'car))) + (when existing-attachment + (let ((attachment-struct (caadr existing-attachment))) + (cond + ((and (eql attachment-type (attachment-attachment attachment-struct)) + (eql loose (attachment-loose attachment-struct))) + (warn "Item ~a already attached to ~a. ~ + Ignoring new attachment." + (name object) (name other-object)) + (return-from attach-object)) + ((eql loose T) + (warn "Item ~a already attached to ~a but not loosely. ~ + Ignoring new loose attachment." + (name object) (name other-object)) + (return-from attach-object)) + ((eql loose NIL) + (warn "Item ~a already attached to ~a but loosely. ~ + Deleting old attachment." + (name object) (name other-object)) + (btr:detach-object other-object object)))))) + (unless skip-removing-loose + (remove-loose-attachment-for object)) + (let ((object-collision-information + ;; Since robot objects are not in the attached-objects + ;; list of items, this has to be copied manuelly: + (if (and (get-robot-object) + (object-attached (get-robot-object) object)) + (get-collision-information object (get-robot-object)) + (create-static-collision-information object))) + (other-object-collision-information + (create-static-collision-information other-object))) + (push (cons (name object) + (cons + (list (make-attachment :object (name object) + :attachment attachment-type)) + object-collision-information)) + (slot-value other-object 'attached-objects)) + (push (cons (name other-object) + (cons + (list (make-attachment :object (name other-object) + :loose loose :attachment attachment-type)) + other-object-collision-information)) + (slot-value object 'attached-objects)))) -(defmethod add-object ((world bt-world) (type (eql :generic-cup)) name pose - &key - mass radius height - (handle-size (cl-transforms:make-3d-vector - 0.03 0.01 (* height 0.8)))) - (make-item world name '(generic-cup) - (list - (make-instance - 'rigid-body - :name name :mass mass :pose (ensure-pose pose) - :collision-shape (make-cup-shape radius height handle-size))))) +(defmethod attach-object ((other-objects list) (object item) + &key attachment-type loose) + "Will be used if an attachment should be made from one item to more +than one item. If `loose' T the other attachments have to be made with +`skip-removing-loose' as T to prevent removing loose attachments between +the element before in `other-objects' and `object'." + (if other-objects + (progn + (attach-object (first other-objects) object + :attachment-type attachment-type :loose loose) + (mapcar (lambda (obj) + (attach-object obj object + :attachment-type attachment-type :loose loose + :skip-removing-loose T)) + (cdr other-objects))) + (warn "Trying to attach an object to a NIL."))) -(defmethod add-object ((world bt-world) (type (eql :mug)) name pose &key mass) - (add-object world :mesh name pose :mass mass :mesh :mug)) +(defmethod detach-object ((other-object item) (object item) &key) + "Removes item names from the given arguments in the corresponding +`attached-objects' lists of the given items." + (when (equal (name object) (name other-object)) + (warn "Cannot attach an object to itself: ~a" (name object)) + (return-from detach-object)) + (flet ((get-attachment-object (elem) + (attachment-object (car (second elem))))) + (let ((object-collision-info + (get-collision-information object other-object)) + (other-object-collision-info + (get-collision-information other-object object))) + (setf (slot-value other-object 'attached-objects) + (remove (name object) (attached-objects other-object) + :key #'get-attachment-object :test #'equal)) + (setf (slot-value object 'attached-objects) + (remove (name other-object) (attached-objects object) + :key #'get-attachment-object :test #'equal)) + (reset-collision-information object object-collision-info) + (reset-collision-information other-object other-object-collision-info)))) + +(defmethod detach-all-objects ((object item)) + (with-slots (attached-objects) object + (dolist (attached-object attached-objects) + (let ((object-name (car attached-object))) + (if (object *current-bullet-world* object-name) + (detach-object (name object) object-name)))))) + +(let ((already-moved '())) + (defmethod (setf pose) :around (new-value (object item)) + "Updates the pose of the object and its attached objects: since +the original pose of the object is saved at the time of attaching, +it is possible to change the pose of its attachments when its pose changes." + (if (and (slot-boundp object 'attached-objects) + (> (length (attached-objects object)) 0)) + (let ((carrier-transform + (cl-transforms:transform-diff + (cl-transforms:pose->transform new-value) + (cl-transforms:pose->transform (pose object))))) + ;; If no attached item already moved or wasn't already moved + (unless (and already-moved + (member (name object) already-moved :test #'equal)) + (push (name object) already-moved) + (call-next-method) + (dolist (attachment (remove-if #'attachment-loose + (mapcar #'car + (mapcar #'second + (attached-objects object))))) + (let ((current-attachment-pose + (pose (object *current-bullet-world* (attachment-object attachment))))) + (when (and carrier-transform current-attachment-pose) + (setf (pose (btr:object *current-bullet-world* + (attachment-object attachment))) + (cl-transforms:transform-pose + carrier-transform + current-attachment-pose))))) + ;; If all attachments from root head passed, remove all. + (if (equal (name object) (car (last already-moved))) + (setf already-moved '())))) + (call-next-method)))) + +;;;;;;;;;;;;;;;;;;;;; SPAWNING MESH AND PRIMITIVE-SHAPED ITEMS ;;;;;;;;;;;; (defmethod add-object ((world bt-world) (type (eql :mesh)) name pose &key mass mesh (color '(0.5 0.5 0.5 1.0)) types (scale 1.0) @@ -209,7 +292,8 @@ The name in the list is a keyword that is created by lispifying the filename." (if mesh-files-entry (setf path (second mesh-files-entry) flip-winding-order (third mesh-files-entry)) - (error "[btr add-object] Item ~a is unknown in btr:*mesh-files*." mesh))))) + (error "[btr add-object] Item ~a is unknown ~ + in btr:*mesh-files*." mesh))))) (make-collision-shape-from-mesh path :scale scale @@ -224,17 +308,136 @@ The name in the list is a keyword that is created by lispifying the filename." :name name :mass mass :pose (ensure-pose pose) :collision-shape collision-shape))))) -(defmethod add-object ((world bt-world) (type (eql :cutlery)) name pose - &key mass (color '(0.5 0.5 0.5 1.0)) cutlery-type) - (let ((size (cutlery-dimensions cutlery-type))) - (assert size) - (make-item world name (list type cutlery-type) +(defmethod add-object ((world bt-world) (type (eql :mug)) name pose &key mass) + (add-object world :mesh name pose :mass mass :mesh :mug)) + + +(defmethod add-object ((world bt-world) (type (eql :generic-cup)) name pose + &key + mass radius height + (handle-size (cl-transforms:make-3d-vector + 0.03 0.01 (* height 0.8)))) + + (labels ((make-octagon-prism-shape (radius height) + "Returns a collision shape that is a octagon prism, ~ + i.e. that has an octagon at its base." + (let ((compound-shape (make-instance 'compound-shape))) + (dotimes (i 4) + (add-child-shape + compound-shape + (cl-transforms:make-pose + (cl-transforms:make-3d-vector 0 0 0) + (cl-transforms:axis-angle->quaternion + (cl-transforms:make-3d-vector 0 0 1) + (/ (* i pi) + 4))) + (make-instance 'box-shape + :half-extents (cl-transforms:make-3d-vector + radius (* radius (sin (/ pi 8))) + (/ height 2))))) + compound-shape)) + + (make-cup-shape (radius height handle-size) + (let ((collision-shape (make-octagon-prism-shape radius height))) + (add-child-shape + collision-shape + (cl-transforms:make-pose + (cl-transforms:make-3d-vector + (+ (* radius (cos (/ pi 8))) + (/ (cl-transforms:x handle-size) + 2)) + 0 0) + (cl-transforms:make-quaternion 0 0 0 1)) + (make-instance 'box-shape + :half-extents (cl-transforms:v* handle-size 0.5))) + collision-shape))) + + (make-item world name '(generic-cup) (list (make-instance 'rigid-body :name name :mass mass :pose (ensure-pose pose) - :collision-shape (make-instance 'colored-box-shape - :half-extents size - :color color)))))) + :collision-shape (make-cup-shape radius height handle-size)))))) + + +(defmethod add-object ((world bt-world) (type (eql :basket)) name pose + &key (mass 1.0) length width height (handle-height 0.09)) + "Creates a collision shape in the form of a basket and adds it to the world. +The length, width and height have to be given for the function to work." + (assert length) + (assert width) + (assert height) + ;; have to check if the object with such a name already exists, + ;; otherwise rogue objects will be spawned + (unless (object world name) + (let ((compound-shape (make-instance 'compound-shape))) + ;; Walls + (dotimes (i 2) + (add-child-shape + compound-shape + (cl-transforms:make-pose + (cl-transforms:make-3d-vector (* i width) 0 0) + (cl-transforms:make-quaternion 0 0 0 1)) + (make-instance 'box-shape + :half-extents (cl-transforms:v* + (cl-transforms:make-3d-vector 0.01 length height) + 0.5)))) + (dotimes (i 2) + (add-child-shape + compound-shape + (cl-transforms:make-pose + (cl-transforms:make-3d-vector (/ width 2) + ;; ((i + 1) * -2 + 3) * length/2 + (* (+ (* (+ i 1) -2) 3) (/ length 2)) + 0) + (cl-transforms:make-quaternion 0 0 1 0)) + (make-instance 'box-shape + :half-extents (cl-transforms:v* + (cl-transforms:make-3d-vector width 0.01 height) + 0.5)))) + ;; Bottom + (add-child-shape + compound-shape + (cl-transforms:make-pose + (cl-transforms:make-3d-vector (/ width 2) 0 (- (/ height 2))) + (cl-transforms:make-quaternion 0 0 0 1)) + (make-instance 'box-shape + :half-extents (cl-transforms:v* + (cl-transforms:make-3d-vector width length 0.01) + 0.5))) + ;;; Handle + ;; the handle of the basket is formed like this: + ;; ------------ + ;; | | + ;; | | + ;; | | + ;; The sides + (dotimes (i 2) + (add-child-shape + compound-shape + (cl-transforms:make-pose + (cl-transforms:make-3d-vector (* i width) 0 (/ (+ height handle-height) 2)) + (cl-transforms:make-quaternion 0 0 0 1)) + (make-instance 'box-shape + :half-extents (cl-transforms:v* + (cl-transforms:make-3d-vector 0.005 0.005 handle-height) + 0.5)))) + ;; the top + (add-child-shape + compound-shape + (cl-transforms:make-pose + (cl-transforms:make-3d-vector (/ width 2) 0 (+ handle-height (/ height 2))) + (cl-transforms:make-quaternion 0 0 0 1)) + (make-instance 'box-shape + :half-extents (cl-transforms:v* + (cl-transforms:make-3d-vector width 0.005 0.005) + 0.5))) + ;; Adds the basket to the specified world + (make-item world name (list type) + (list + (make-instance 'rigid-body + :name name :mass mass :pose (ensure-pose pose) + :collision-shape compound-shape)))))) + (defmethod add-object ((world bt-world) (type (eql :pancake-maker)) name pose &key mass (color '(0.5 0.5 0.5 1.0)) size) @@ -302,156 +505,28 @@ The name in the list is a keyword that is created by lispifying the filename." :half-extents (ensure-vector size) :color color))))) -(defmethod btr:add-object ((world bullet:bt-world) (type (eql :box-item)) name pose - &key mass (color '(1.0 0.0 0.0 1.0)) size item-type) +(defmethod add-object ((world bt-world) (type (eql :cylinder-item)) name pose + &key mass (color '(0.5 0.5 0.5 1.0)) size item-type) (assert size) (assert item-type) - (unless (find name (objects *current-bullet-world*) :key #'name) + (unless (object world name) (make-item world name (list item-type) (list (make-instance 'rigid-body - :name name :mass mass :pose (btr:ensure-pose pose) - :collision-shape (make-instance 'bt-vis:colored-box-shape - :half-extents (btr:ensure-vector size) + :name name :mass mass :pose (ensure-pose pose) + :collision-shape (make-instance 'bt-vis:colored-cylinder-shape + :half-extents (ensure-vector size) :color color)))))) - -;;;;;;;;;;;;;;;;;;;;;;;;;; ATTACHMENTS ;;;;;;;;;;;;;;;;;;;;;;;;;; - -(defmethod get-loose-attached-objects ((object item)) - "Returns all objects attached to `object', -where ATTACHMENTs have the keyword LOOSE as not NIL." - (mapcar #'car - (remove-if-not - (alexandria:compose #'attachment-loose #'car #'car #'cdr) - (attached-objects object)))) - -(let ((already-visited '())) - (defmethod remove-loose-attachment-for ((object item)) - "Searches if the `object' was connected unidirectional/loosly to other -objects and removes ALL corresponding attachments if so. -To search through the attached objects ALREADY-VISITED will help to check -if we already checked this object, as this is a recursive function. -In bidirectional attachments both objects are attached to each other. -In unidirectional attachments, one object is properly attached, -and the other one is loosly attached. " - (let ((loose-attached-objects (get-loose-attached-objects object))) - (when loose-attached-objects - ;; Map the following: (detach-object object loosly-attached-object) - (mapcar (alexandria:curry #'detach-object object) - (mapcar (alexandria:curry #'object *current-bullet-world*) - loose-attached-objects)))) - ;; searching recrusivly, if an object with attachments was attached to something - ;; to remove unidirectional/loose objects attachments if they were attached too - (when (and (slot-boundp object 'attached-objects) - (> (length (attached-objects object)) 0)) - (push (name object) already-visited) - (loop for attached-object in (mapcar (lambda (attach) - (object *current-bullet-world* (car attach))) - (attached-objects object)) - do (unless (member (name attached-object) already-visited) - (remove-loose-attachment-for attached-object))) - (if (equal (car (last already-visited)) (name object)) - (setf already-visited '()))))) - -(defmethod attach-object ((other-object item) (object item) - &key attachment-type loose skip-removing-loose link grasp) - "Attaches `object' to `other-object': adds an attachment to the -attached-objects lists of each other. `attachment-type' is a keyword -that specifies the type of attachment. `loose' specifies if the attachment -is bidirectional (nil) or unidirectional (t). `skip-removing-loose' is for -attaching more objects unidirectional and should be for this T. See -`attach-object' above." - (declare (ignore link grasp)) ;; used in robot-model.lisp - (when (equal (name object) (name other-object)) - (warn "Cannot attach an object to itself: ~a" (name object)) - (return-from attach-object)) - (when (member (name object) (attached-objects other-object)) - (warn "Item ~a already attached to ~a. Ignoring new attachment." - (name object) (name other-object)) - (return-from attach-object)) - (unless skip-removing-loose - (remove-loose-attachment-for object)) - (push (cons (name object) - (cons - (list (make-attachment :object (name object) - :attachment attachment-type)) - (create-static-collision-information object))) - (slot-value other-object 'attached-objects)) - (push (cons (name other-object) - (cons - (list (make-attachment :object (name other-object) - :loose loose :attachment attachment-type)) - (create-static-collision-information other-object))) - (slot-value object 'attached-objects))) - -(defmethod attach-object ((other-objects list) (object item) - &key attachment-type loose) - "Will be used if an attachment should be made from one item to more -than one item. If `loose' T the other attachments have to be made with -`skip-removing-loose' as T to prevent removing loose attachments between -the element before in `other-objects' and `object'." - (attach-object (first other-objects) object :attachment-type attachment-type :loose loose) - (mapcar (lambda (obj) - (attach-object obj object - :attachment-type attachment-type :loose loose - :skip-removing-loose T)) - (cdr other-objects))) - -(defmethod detach-object ((other-object item) (object item) &key) - "Removes item names from the given arguments in the corresponding `attached-objects' lists - of the given items." - (when (equal (name object) (name other-object)) - (warn "Cannot attach an object to itself: ~a" (name object)) - (return-from detach-object)) - (flet ((get-attachment-object (elem) - (attachment-object (car (second elem)))) - (get-collision-info (attached obj) - (cdr (cdr (assoc (name attached) (attached-objects obj)))))) - (reset-collision-information object (get-collision-info object other-object)) - (reset-collision-information other-object (get-collision-info other-object object)) - (setf (slot-value other-object 'attached-objects) - (remove (name object) (attached-objects other-object) - :key #'get-attachment-object :test #'equal)) - (setf (slot-value object 'attached-objects) - (remove (name other-object) (attached-objects object) - :key #'get-attachment-object :test #'equal)))) - -(defmethod detach-all-objects ((object item)) - (with-slots (attached-objects) object - (dolist (attached-object attached-objects) - (let ((object-name (car attached-object))) - (if (object *current-bullet-world* object-name) - (detach-object (name object) object-name)))))) - -(let ((already-moved '())) - (defmethod (setf pose) :around (new-value (object item)) - "Since we save the original pose of the object at the time of attaching, -it is possible to change the pose of its attachments when its pose changes." - (if (and (slot-boundp object 'attached-objects) - (> (length (attached-objects object)) 0)) - (let ((carrier-transform - (cl-transforms:transform-diff - (cl-transforms:pose->transform new-value) - (cl-transforms:pose->transform (pose object))))) - ;; If no attached item already moved or wasn't already moved - (unless (and already-moved - (member (name object) already-moved :test #'equal)) - (push (name object) already-moved) - (call-next-method) - (dolist (attachment (remove-if #'attachment-loose - (mapcar #'car - (mapcar #'second - (attached-objects object))))) - (let ((current-attachment-pose - (pose (object *current-bullet-world* (attachment-object attachment))))) - (when (and carrier-transform current-attachment-pose) - (setf (pose (btr:object btr:*current-bullet-world* - (attachment-object attachment))) - (cl-transforms:transform-pose - carrier-transform - current-attachment-pose))))) - ;; If all attachments from root head passed, remove all. - (if (equal (name object) (car (last already-moved))) - (setf already-moved '())))) - (call-next-method)))) +(defmethod add-object ((world bt-world) (type (eql :box-item)) name pose + &key mass (color '(1.0 0.0 0.0 1.0)) size item-type) + (assert size) + (assert item-type) + (unless (object world name) + (make-item world name (list item-type) + (list + (make-instance 'rigid-body + :name name :mass mass :pose (ensure-pose pose) + :collision-shape (make-instance 'bt-vis:colored-box-shape + :half-extents (ensure-vector size) + :color color)))))) diff --git a/cram_3d_world/cram_bullet_reasoning/src/objects.lisp b/cram_3d_world/cram_bullet_reasoning/src/objects.lisp index ea14e79dea..64cd9ba3c5 100644 --- a/cram_3d_world/cram_bullet_reasoning/src/objects.lisp +++ b/cram_3d_world/cram_bullet_reasoning/src/objects.lisp @@ -1,5 +1,6 @@ ;;; ;;; Copyright (c) 2010, Lorenz Moesenlechner +;;; 2019, Thomas Lipps ;;; All rights reserved. ;;; ;;; Redistribution and use in source and binary forms, with or without @@ -33,7 +34,7 @@ (defparameter *all-meshes-as-compound* T) (defclass object () - ((name :initarg :name :reader name) + ((name :initarg :name :reader name :type keyword) (rigid-bodies :initform (make-hash-table :test 'equal)) (pose-reference-body :initarg :pose-reference-body :documentation "The name of the rigid-body @@ -298,19 +299,24 @@ (compound *all-meshes-as-compound*) (flip-winding-order nil)) "Loads and resizes the 3d-model. If `compound' is T we have a list of meshes, instead of one." - (let ((model (multiple-value-list - (physics-utils:load-3d-model (physics-utils:parse-uri mesh-filename) - :compound compound - :flip-winding-order flip-winding-order)))) + (let* ((uri + (physics-utils:parse-uri mesh-filename)) + (mesh-model + (cut:with-file-cache model uri + (multiple-value-list + (physics-utils:load-3d-model + uri :compound compound :flip-winding-order flip-winding-order)) + model))) (cond (scale (mapcar (lambda (model-part) (physics-utils:scale-3d-model model-part scale)) - model)) + mesh-model)) (size (mapcar (lambda (model-part) (physics-utils:resize-3d-model model-part size)) - model)) - (t model)))) + mesh-model)) + (t + mesh-model)))) (defun make-collision-shape-from-mesh (mesh-filename &key (color '(0.8 0.8 0.8 1.0)) (scale nil) (size nil) @@ -338,7 +344,7 @@ (let ((compound-shape (make-instance 'compound-shape)) (id-pose (cl-transforms:make-pose (cl-transforms:make-3d-vector 0 0 0) - (cl-tf:make-identity-rotation)))) + (cl-transforms:make-identity-rotation)))) (mapcar (alexandria:compose (alexandria:curry #'add-child-shape compound-shape id-pose) #'make-ch-mesh-shape) @@ -352,22 +358,81 @@ (defstruct collision-information rigid-body-name flags) -(defmethod create-static-collision-information ((object object)) +(defun get-collision-information (object other-object) + "Collision information about `object' from `other-object', +who is the parent of `object' in the attachment." + (cdr (cdr (assoc (name object) (attached-objects other-object))))) + +(defun create-static-collision-information (object) (if (not (object *current-bullet-world* (name object))) (error "Cannot find object named ~a" (name object)) (loop for body in (rigid-bodies object) collecting (make-collision-information :rigid-body-name (name body) - :flags (collision-flags body)) + :flags (cond (;; If the object does have no + ;; attached objects we take the + ;; current state of it. + (not (attached-objects object)) + (collision-flags body)) + ;; If the object is attached with + ;; other objects we use the saved + ;; collision information from + ;; these objects. If the + ;; collision information of all + ;; these objects is static, this + ;; returns static too. + ((only-static-in-attachments-p object) + '(:cf-static-object)) + (t + NIL))) do (setf (collision-flags body) :cf-static-object)))) -(defmethod reset-collision-information ((object object) collision-information) +(defun only-static-in-attachments-p (object) + "Returns T, if the `object's flags are `cf-static-object' in + the attachments of `object's attached objects." + (declare (type object object)) + (let* ((attached-object-names + (mapcar #'car + (attached-objects + (object + *current-bullet-world* + (name object))))) + (attachments-of-attached-objects + (mapcar + (alexandria:compose + #'attached-objects + (alexandria:curry #'object *current-bullet-world*)) + attached-object-names)) + (attachments-to-object + (mapcar + #'car + (loop for attachments in attachments-of-attached-objects + collecting + (remove-if-not (alexandria:curry + #'equalp + (name object)) + attachments :key #'car)))) + (collision-information-list + (mapcar + #'caddr + (remove-if-not #'identity + attachments-to-object)))) + + (when collision-information-list + (every (alexandria:curry #'equalp '(:cf-static-object)) + (mapcar #'collision-information-flags + collision-information-list))))) + + +(defun reset-collision-information (object collision-information) (loop for collision-data in collision-information for body = (rigid-body object (collision-information-rigid-body-name collision-data)) do (setf (collision-flags body) - (collision-information-flags collision-data)))) + (if (attached-objects object) + '(:cf-static-object) + (collision-information-flags collision-data))))) (defstruct attachment @@ -447,3 +512,40 @@ the names of which are in `object-to-attach-names'." (btr:object *current-bullet-world* object-to-detach-from-name) (when obj-found (detach-all-objects obj)))) + +(defun get-loose-attached-objects (object) + "Returns all objects attached to `object', +where ATTACHMENTs have the keyword LOOSE as not NIL." + (mapcar #'car + (remove-if-not + (alexandria:compose #'attachment-loose #'car #'car #'cdr) + (attached-objects object)))) + +(let ((already-visited '())) + (defun remove-loose-attachment-for (object) + "Searches if the `object' was connected loosely to other +objects and removes ALL corresponding attachments if so. +To search through the attached objects of `object' the variable +ALREADY-VISITED will help to prevent endless loops, as this is a +recursive function." + (let ((loose-attached-objects (get-loose-attached-objects object))) + (when loose-attached-objects + ;; Map the following: (detach-object object loosely-attached-object) + (mapcar (alexandria:curry #'detach-object object) + (mapcar (alexandria:curry #'object *current-bullet-world*) + loose-attached-objects)))) + ;; searching recursivly: + ;; if `object' has attachments, `remove-loose-attachment-for' + ;; gets called with these to remove every indirect loose + ;; attachment: e. g. `object' is not loosely attached but one of + ;; its attached objects is connected loosely to something + (when (and (slot-boundp object 'attached-objects) + (> (length (attached-objects object)) 0)) + (push (name object) already-visited) + (loop for attached-object in (mapcar (lambda (attach) + (object *current-bullet-world* (car attach))) + (attached-objects object)) + do (unless (member (name attached-object) already-visited) + (remove-loose-attachment-for attached-object))) + (if (equal (car (last already-visited)) (name object)) + (setf already-visited '()))))) diff --git a/cram_3d_world/cram_bullet_reasoning/src/package.lisp b/cram_3d_world/cram_bullet_reasoning/src/package.lisp index e01dbaa9ae..3a20f7b1ec 100644 --- a/cram_3d_world/cram_bullet_reasoning/src/package.lisp +++ b/cram_3d_world/cram_bullet_reasoning/src/package.lisp @@ -43,7 +43,7 @@ merge-bounding-boxes aabb calculate-bb-dims with-stored-world *debug-window* add-debug-window add-costmap-function-object add-vis-axis-object - add-costmap-sample-object clear-costmap-vis-object add-vis-axis-object + add-costmap-sample-object clear-costmap-vis-object camera width height fov-y z-near z-far pose gl-execute-with-camera camera-transform look-at-object-rotation @@ -57,14 +57,18 @@ cutlery fork knife mug plate mondamin pot bowl sugar-box apple orange cereal spatula pancake pancake-maker bt-reasoning-world invalidate-object objects object %object - bt-reasoning-world-state robot-object links joint-states + bt-reasoning-world-state + get-world-objects-pose-info restore-world-poses + robot-object links joint-states assert joint-state urdf joint-names joint-state link-names link-pose semantic-map-object ensure-pose ensure-vector object-visibility semantic-map container semantic-map-part semantic-map-part-type semantic-map-part-pose object-visibility-percentage object-visibility-occluding-objects flat-color-object-proxy - calculate-object-visibility object-visible-p + calculate-object-visibility + object-visible-p looking-at-object-p object-in-view-p + looking-at-pose-p occluding-objects simulate find-objects contact-p find-all-contacts find-objects-in-contact object-pose-different @@ -86,6 +90,7 @@ ros-household-object execute open close ;; reach-ik-solution attached attached-objects object-attached attach-object detach-object detach-all-objects detach-all-from-link + get-loose-attached-objects item-dimensions add-objects-to-mesh-list open-object close-object @@ -98,9 +103,9 @@ #:set-robot-state-from-joints #:make-robot-joint-state-msg #:make-joint-state-message - #:calculate-pan-tilt - #:get-robot-object #:get-robot-name - #:get-environment-object + #:calculate-pan-tilt #:looking-in-direction-p + #:robot-converged-to-goal-joint-states + #:get-robot-object #:get-environment-object #:robot-colliding-objects-without-attached #:robot-attached-objects-in-collision ;; temporal-reasoning diff --git a/cram_3d_world/cram_bullet_reasoning/src/reasoning-world.lisp b/cram_3d_world/cram_bullet_reasoning/src/reasoning-world.lisp index 37129cd5e7..4947a24993 100644 --- a/cram_3d_world/cram_bullet_reasoning/src/reasoning-world.lisp +++ b/cram_3d_world/cram_bullet_reasoning/src/reasoning-world.lisp @@ -107,3 +107,37 @@ list from bt-reasoning-world to keep in the current world state."))) obj (copy-object obj world)))) (setf (gethash name objects) obj) (invalidate-object obj)))))))) + +(defun get-world-objects-pose-info (&optional (world *current-bullet-world*)) + "Returns a cons with (name-pose-hash-table . name-joint-states-hash-table)." + (loop with name-pose-tbl = (make-hash-table :test #'equalp) + with name-joint-state-tbl = (make-hash-table :test #'equalp) + for obj in (objects world) + do (let ((obj-name (name obj))) + (setf (gethash obj-name name-pose-tbl) + (pose obj)) + (when (typep obj 'robot-object) + (setf (gethash obj-name name-joint-state-tbl) + (alexandria:copy-hash-table (joint-states obj))))) + finally (return (cons name-pose-tbl name-joint-state-tbl)))) + +(defun restore-world-poses (poses-and-joint-states + &optional (world *current-bullet-world*)) + (destructuring-bind (name-pose-tbl . name-joint-states-tbl) + poses-and-joint-states + (let ((current-names (mapcar #'name (objects *current-bullet-world*))) + (new-names (alexandria:hash-table-keys name-pose-tbl))) + (when (or (set-difference current-names new-names :test #'equalp) + (set-difference new-names current-names :test #'equalp)) + (error "[btr:restore-world-poses] objects in the two worlds + are not the same!~%current world names: ~a~%new world names: ~a~%" + current-names new-names)) + (mapc (lambda (obj) + (let ((obj-name (name obj))) + (setf (pose obj) + (gethash obj-name name-pose-tbl)) + (when (typep obj 'robot-object) + (set-robot-state-from-joints + (gethash obj-name name-joint-states-tbl) + obj)))) + (objects world))))) diff --git a/cram_3d_world/cram_bullet_reasoning/src/robot-model-facts.lisp b/cram_3d_world/cram_bullet_reasoning/src/robot-model-facts.lisp index c6097a5ecb..bbdff172b0 100644 --- a/cram_3d_world/cram_bullet_reasoning/src/robot-model-facts.lisp +++ b/cram_3d_world/cram_bullet_reasoning/src/robot-model-facts.lisp @@ -110,12 +110,14 @@ (and (slot-value ?world disabled-collision-objects ?objects) (or (member (?robot-name ?object-name) ?objects) (member (?object-name ?robot-name) ?objects))) - (gripper-link ?robot-name ?_ ?link))))) + (hand-link ?robot-name ?_ ?link))))) (<- (attached ?world ?robot ?link-name ?object ?grasp) (bullet-world ?world) - (object ?world ?object) (%object ?world ?robot ?robot-instance) + (lisp-fun attached-objects ?robot-instance ?object-attachments-list) + (member (?object . ?_) ?object-attachments-list) + (object ?world ?object) (%object ?world ?object ?object-instance) (lisp-fun multiple-value-list-fun object-attached ?robot-instance ?object-instance (?links ?grasps)) @@ -152,4 +154,4 @@ (forall (member ?arm ?arms) (and (end-effector-link ?robot ?arm ?link) - (not (btr:attached ?_ ?robot ?link ?_)))))) + (not (attached ?_ ?robot ?link ?_)))))) diff --git a/cram_3d_world/cram_bullet_reasoning/src/robot-model-utils.lisp b/cram_3d_world/cram_bullet_reasoning/src/robot-model-utils.lisp index 71855a3578..a5c7a70287 100644 --- a/cram_3d_world/cram_bullet_reasoning/src/robot-model-utils.lisp +++ b/cram_3d_world/cram_bullet_reasoning/src/robot-model-utils.lisp @@ -1,10 +1,10 @@ ;;; ;;; Copyright (c) 2010, Lorenz Moesenlechner ;;; All rights reserved. -;;; +;;; ;;; Redistribution and use in source and binary forms, with or without ;;; modification, are permitted provided that the following conditions are met: -;;; +;;; ;;; * Redistributions of source code must retain the above copyright ;;; notice, this list of conditions and the following disclaimer. ;;; * Redistributions in binary form must reproduce the above copyright @@ -14,7 +14,7 @@ ;;; Technische Universitaet Muenchen nor the names of its contributors ;;; may be used to endorse or promote products derived from this software ;;; without specific prior written permission. -;;; +;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" ;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE ;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE @@ -42,7 +42,9 @@ :time timestamp :timeout *tf-default-timeout*) (transform-stamped-error (error) (roslisp:ros-warn (set-robot-state-from-tf) - "Failed with transform-stamped-error: ~a" error) + "Failed with transform-stamped-error:~% ~a~% ~ + Ignore this warning if no real robot is running." + error) NIL)))) (when robot-transform (setf (link-pose robot root-link) @@ -67,8 +69,8 @@ (defgeneric set-robot-state-from-joints (joint-states robot) (:method ((joint-states sensor_msgs-msg:jointstate) (robot robot-object)) - "Sets the joints of `robot' to the values specified in the -sensor_msgs/JointStates message." + "Sets the joints of `robot' to the values specified in the ~ + sensor_msgs/JointStates message." (roslisp:with-fields ((names name) (positions position)) joint-states @@ -76,12 +78,15 @@ sensor_msgs/JointStates message." (setf (joint-state robot name) state)) names positions))) (:method ((joint-states list) (robot robot-object)) - "Sets the joint states of `robot' to the values specifies in the - list `joint-states'. `joint-states' is a list of the form: - - ([(name value)]*)" + "Sets the joint states of `robot' to the values specifies in the ~ + list `joint-states'. `joint-states' is a list of the form: ([(name value)]*)" (loop for (name value) in joint-states do - (setf (joint-state robot name) value)))) + (setf (joint-state robot name) value))) + (:method ((joint-states hash-table) (robot robot-object)) + "Sets the joint states of `robot' to the values specifies in the ~ + hash table `joint-states'." + (loop for name being the hash-keys in joint-states using (hash-value value) + do (setf (joint-state robot name) value)))) (defun make-robot-joint-state-msg (robot &key joint-names (time 0)) (let ((joint-names (map 'vector #'identity (or joint-names @@ -117,59 +122,116 @@ sensor_msgs/JointStates message." `pose'. Returns (LIST PAN-VALUE TILT-VALUE) Used in desig-check-to-see of btr-visibility-costmap. Should it be taken out and made PR2-specific?" - (let* ((pan-transform (cl-transforms:reference-transform - (link-pose robot pan-link))) - (tilt-transform (cl-transforms:reference-transform - (link-pose robot tilt-link))) - (pose-trans (etypecase pose - (cl-transforms:3d-vector - (cl-transforms:make-transform - pose (cl-transforms:make-quaternion 0 0 0 1))) - (cl-transforms:pose (cl-transforms:reference-transform pose)) - (cl-transforms:transform pose))) - (pose-in-pan (cl-transforms:transform* - (cl-transforms:transform-inv pan-transform) - pose-trans)) - (pose-in-tilt (cl-transforms:transform* - (cl-transforms:transform-inv tilt-transform) - pose-trans)) - (pan-joint-name (cl-urdf:name - (cl-urdf:from-joint - (gethash pan-link (cl-urdf:links (urdf robot)))))) - (tilt-joint-name (cl-urdf:name - (cl-urdf:from-joint - (gethash tilt-link (cl-urdf:links (urdf robot))))))) + (let* ((pan-transform + (cl-transforms:reference-transform (link-pose robot pan-link))) + (tilt-transform + (cl-transforms:reference-transform (link-pose robot tilt-link))) + (pose-trans + (etypecase pose + (cl-transforms:3d-vector + (cl-transforms:make-transform + pose (cl-transforms:make-quaternion 0 0 0 1))) + (cl-transforms:pose (cl-transforms:reference-transform pose)) + (cl-transforms:transform pose))) + (pose-in-pan + (cl-transforms:transform* + (cl-transforms:transform-inv pan-transform) + pose-trans)) + (pose-in-tilt + (cl-transforms:transform* + (cl-transforms:transform-inv tilt-transform) + pose-trans)) + (pan-joint + (cl-urdf:from-joint (gethash pan-link (cl-urdf:links (urdf robot))))) + (pan-joint-name + (cl-urdf:name pan-joint)) + (pan-joint-axis-sign + (cl-transforms:z (cl-urdf:axis pan-joint))) + (tilt-joint + (cl-urdf:from-joint (gethash tilt-link (cl-urdf:links (urdf robot))))) + (tilt-joint-name + (cl-urdf:name tilt-joint)) + (tilt-joint-axis-sign + (cl-transforms:y (cl-urdf:axis tilt-joint)))) (list - (+ (joint-state robot pan-joint-name) - (if (= (cl-transforms:x (cl-transforms:translation pose-in-pan)) 0) - 0.0 - (atan (cl-transforms:y (cl-transforms:translation pose-in-pan)) - (cl-transforms:x (cl-transforms:translation pose-in-pan))))) - (+ (joint-state robot tilt-joint-name) - (if (= (cl-transforms:x (cl-transforms:translation pose-in-tilt)) 0) - 0.0 - (atan (- (cl-transforms:z (cl-transforms:translation pose-in-tilt))) - (+ (expt (cl-transforms:y (cl-transforms:translation pose-in-tilt)) 2) - (expt (cl-transforms:x (cl-transforms:translation pose-in-tilt)) 2)))))))) + (* pan-joint-axis-sign + (+ (joint-state robot pan-joint-name) + (if (= (cl-transforms:x (cl-transforms:translation pose-in-pan)) 0) + 0.0 + (atan (cl-transforms:y (cl-transforms:translation pose-in-pan)) + (cl-transforms:x (cl-transforms:translation pose-in-pan)))))) + (* tilt-joint-axis-sign + (+ (joint-state robot tilt-joint-name) + (if (= (cl-transforms:x (cl-transforms:translation pose-in-tilt)) 0) + 0.0 + (atan (- (cl-transforms:z (cl-transforms:translation pose-in-tilt))) + (+ (expt (cl-transforms:y (cl-transforms:translation pose-in-tilt)) 2) + (expt (cl-transforms:x (cl-transforms:translation pose-in-tilt)) 2))))))))) +(defun looking-in-direction-p (robot camera-frame + angle-horizontal angle-vertical + direction) + (declare (type cl-transforms:3d-vector direction)) + (let* ((camera-pose + (btr:link-pose robot camera-frame)) + (map-T-cam + (cram-tf:pose->transform-stamped + cram-tf:*fixed-frame* camera-frame 0.0 camera-pose)) + (cam-T-cam-up + (cl-transforms-stamped:make-transform-stamped + camera-frame "camera_up" 0.0 + (cl-transforms:make-3d-vector 0 1 0) + (cl-transforms:make-identity-rotation))) + (map-T-cam-up + (cram-tf:multiply-transform-stampeds + cram-tf:*fixed-frame* "camera_up" + map-T-cam cam-T-cam-up)) + (camera-up-in-map-vector + (cl-transforms:v- + (cl-transforms:translation map-T-cam-up) + (cl-transforms:translation map-T-cam))) + (cam-T-cam-left + (cl-transforms-stamped:make-transform-stamped + camera-frame "camera_left" 0.0 + (cl-transforms:make-3d-vector 1 0 0) + (cl-transforms:make-identity-rotation))) + (map-T-cam-left + (cram-tf:multiply-transform-stampeds + cram-tf:*fixed-frame* "camera_left" + map-T-cam cam-T-cam-left)) + (camera-left-in-map-vector + (cl-transforms:v- + (cl-transforms:translation map-T-cam-left) + (cl-transforms:translation map-T-cam))) + (angle-h + (asin (/ (cl-transforms:dot-product camera-left-in-map-vector direction) + (cl-transforms:v-norm direction)))) + (angle-v + (asin (/ (cl-transforms:dot-product camera-up-in-map-vector direction) + (cl-transforms:v-norm direction)))) + (max-angle-h + (/ angle-horizontal 2)) + (max-angle-v + (/ angle-vertical 2))) + (and (< (abs angle-h) max-angle-h) + (< (abs angle-v) max-angle-v)))) + +(defun robot-converged-to-goal-joint-states (goal-states delta) + (let ((arm-joint-names (loop for (name value) in goal-states collect name)) + (goal-values (loop for (name value) in goal-states collect value))) + (cram-tf:values-converged + (mapcar (alexandria:curry 'btr:joint-state (btr:get-robot-object)) + arm-joint-names) + goal-values + delta))) -(defun get-robot-object () - (with-vars-bound (?robot-object) - (lazy-car (prolog `(and (cram-robot-interfaces:robot ?robot-name) - (bullet-world ?world) - (%object ?world ?robot-name ?robot-object)))) - (unless (is-var ?robot-object) - ?robot-object))) -(defun get-robot-name () - (with-vars-bound (?robot) - (lazy-car (prolog `(cram-robot-interfaces:robot ?robot))) - (unless (is-var ?robot) - ?robot))) +(defun get-robot-object () + (object *current-bullet-world* (rob-int:get-robot-name))) (defun get-environment-object () - (object *current-bullet-world* :kitchen)) + (object *current-bullet-world* (rob-int:get-environment-name))) (defun robot-colliding-objects-without-attached (&optional other-objects-to-discard) @@ -186,17 +248,31 @@ Should it be taken out and made PR2-specific?" (list colliding-object-names attached-object-names robot-object-name-list other-objects-to-discard)))) -(defmethod robot-attached-objects-in-collision () +(defun robot-attached-objects-in-collision () "Returns a boolean that says if the objects the robot is holding are colliding with anything in the world, except the robot itself or other objects to which current object is attached." (some #'identity + ;; for each object that is attached to the robot (mapcar (lambda (attachment) - ;; remove if object has attachments, which are then colliding - (remove-if #'attached-objects - ;; remove if robot is colliding - (remove (get-robot-object) - (find-objects-in-contact - *current-bullet-world* - (object *current-bullet-world* (car attachment)))))) + (let* ((this-object-name + (car attachment)) + ;; get a list of objects that this object is colliding with + (colliding-objects + (find-objects-in-contact + *current-bullet-world* + (object *current-bullet-world* this-object-name))) + ;; remove the robot from this list + (colliding-objects-without-robot + (remove (get-robot-object) colliding-objects)) + ;; remove all objects that this object is attached to + (colliding-objects-without-robot-and-attached-objects + (remove-if (lambda (object) + (when (or (typep object 'btr:item) + (typep object 'btr:robot-object)) + (find this-object-name + (btr:attached-objects object) + :key #'car))) + colliding-objects-without-robot))) + colliding-objects-without-robot-and-attached-objects)) (attached-objects (get-robot-object))))) diff --git a/cram_3d_world/cram_bullet_reasoning/src/robot-model.lisp b/cram_3d_world/cram_bullet_reasoning/src/robot-model.lisp index 9f18b80343..5e6df396dc 100644 --- a/cram_3d_world/cram_bullet_reasoning/src/robot-model.lisp +++ b/cram_3d_world/cram_bullet_reasoning/src/robot-model.lisp @@ -1,6 +1,8 @@ ;;; ;;; Copyright (c) 2010, Lorenz Moesenlechner -;;; Copyright (c) 2019, Vanessa Hassouna +;;; 2014, Gayane Kazhoyan +;;; 2019, Vanessa Hassouna +;;; 2019, Thomas Lipps ;;; All rights reserved. ;;; ;;; Redistribution and use in source and binary forms, with or without @@ -159,20 +161,40 @@ Otherwise, the attachment is only used as information but does not affect the wo (error 'simple-error :format-control "Link ~a unknown" :format-arguments (list link))) (with-slots (attached-objects) robot-object - (let ((obj-attachment - (assoc (name obj) attached-objects :test #'equal)) - (new-attachment - (make-attachment - :object (name obj) :link link :loose loose :grasp grasp))) - (cond (obj-attachment - (pushnew new-attachment (car (cdr obj-attachment)) - :test #'equal :key #'attachment-link)) + (let* ((new-attachment + (make-attachment + :object (name obj) :link link :loose loose :grasp grasp)) + (obj-attachment + (assoc (name obj) attached-objects :test #'equal)) + (attachment-struct + (caadr obj-attachment))) + (if obj-attachment + (cond + ((and (string-equal link (attachment-link attachment-struct)) + (eql loose (attachment-loose attachment-struct))) + (warn "Object ~a already attached to ~a. Ignoring new attachment." + (name obj) (name robot-object)) + (return-from attach-object)) + ((and (string-equal link (attachment-link attachment-struct)) + (eql loose T)) + (warn "Object ~a already attached to ~a's link ~a but not loosely. ~ + Ignoring new loose attachment." + (name obj) (name robot-object) link) + (return-from attach-object)) + ((and (string-equal link (attachment-link attachment-struct)) + (eql loose NIL)) + (warn "Object ~a already attached to ~a's link ~a but loosely. ~ + Overwriting with new attachment." + (name obj) (name robot-object) link) + (setf (attachment-loose attachment-struct) NIL)) (t - (push (cons (name obj) - (cons - (list new-attachment) - (create-static-collision-information obj))) - attached-objects)))))) + (pushnew new-attachment (car (cdr obj-attachment)) + :test #'equal :key #'attachment-link))) + (push (cons (name obj) + (cons + (list new-attachment) + (create-static-collision-information obj))) + attached-objects))))) (defmethod detach-object ((robot-object robot-object) (object object) &key link) "Detaches `object' from the set of attached objects. @@ -180,28 +202,29 @@ Otherwise, the attachment is only used as information but does not affect the wo `link'. Otherwise, detaches `object' from all links." (with-slots (attached-objects) robot-object (let ((attachment (assoc (name object) attached-objects))) - (cond (link - (setf (second attachment) - (remove link (second attachment) - :test #'equal :key #'attachment-link)) - (unless (second attachment) - (setf attached-objects (remove (name object) attached-objects - :key #'car)) - (reset-collision-information object (cdr (cdr attachment))))) - (t (setf attached-objects (remove (name object) attached-objects - :key #'car)) - (reset-collision-information object (cdr (cdr attachment)))))))) + (when attachment + (cond (link + (setf (second attachment) + (remove link (second attachment) + :test #'equal :key #'attachment-link)) + (unless (second attachment) + (setf attached-objects (remove (name object) attached-objects + :key #'car)) + (reset-collision-information object (cdr (cdr attachment))))) + (t (setf attached-objects (remove (name object) attached-objects + :key #'car)) + (reset-collision-information object (cdr (cdr attachment))))))))) (defmethod detach-all-from-link ((robot-object robot-object) link) "Removes all objects form the given `link' of `robot-object'." (with-slots (attached-objects) robot-object (dolist (attachment attached-objects) (let* ((object-name (car attachment)) - (object-instance (object btr:*current-bullet-world* object-name))) + (object-instance (object *current-bullet-world* object-name))) (if object-instance (let ((attached-to-links (object-attached robot-object object-instance))) (when (find link attached-to-links :test #'equalp) - (btr:detach-object robot-object object-instance :link link))) + (detach-object robot-object object-instance :link link))) (setf attached-objects (remove object-name attached-objects :key #'car))))))) (defmethod detach-all-objects ((robot-object robot-object)) @@ -353,32 +376,41 @@ Otherwise, the attachment is only used as information but does not affect the wo :collision-mask collision-mask :compound compound)) -(defvar *updated-attachments* (make-hash-table) - "Saves the already updated attached objects and the traversed links of it") +(let ((updated-attachments (make-hash-table))) + ;; Stores the already updated attached objects and the corresponding traversed links + + (defun get-updated-attachments () + "This getter exists only for testing `updated-link-in-attachment' +in the unit tests." + updated-attachments) -(defun updated-link-in-attachment (link attachment) - "Returns if the pose of the attached object behind the `attachment' + (defun updated-link-in-attachment (link attachment) + "Returns if the pose of the attached object behind the `attachment' was updated by checking if `link' was already updated. The already -updated links are saved under the attachment name in `*updated-attachments*'. +updated links are saved under the attachment name in `updated-attachments'. If all links of an attachment were updated the entry under the attachment -name in `*updated-attachments*' gets deleted." - (let ((links-attached-to (mapcar #'btr::attachment-link (car (cdr attachment)))) - (ret T)) - (when (and link (member (cl-urdf:name link) links-attached-to :test #'string-equal)) - (if (gethash (car attachment) *updated-attachments*) - (setf (gethash (car attachment) *updated-attachments*) - (push (cl-urdf:name link) (gethash (car attachment) *updated-attachments*))) - (progn - (setf (gethash (car attachment) *updated-attachments*) (list (cl-urdf:name link))) - (setf ret NIL))) - (when (equal ;; checks if the list of links in attachment and the already visited links are equal - (length links-attached-to) - (length - (intersection - (gethash (car attachment) *updated-attachments*) - links-attached-to :test #'string-equal))) - (remhash (car attachment) *updated-attachments*)) - (return-from updated-link-in-attachment ret)))) +name in `updated-attachments' gets deleted." + (let ((links-to-update (mapcar #'attachment-link + (remove-if #'attachment-loose + (car (cdr attachment))))) + (ret T)) + (when (and link (member (cl-urdf:name link) links-to-update :test #'string-equal)) + (if (gethash (car attachment) updated-attachments) + (setf (gethash (car attachment) updated-attachments) + (push (cl-urdf:name link) (gethash (car attachment) updated-attachments))) + (setf (gethash (car attachment) updated-attachments) + (list (cl-urdf:name link)) + ret + NIL)) + ;; checks if the list of links in attachment and the already visited links are equal + (when (equal + (length links-to-update) + (length + (intersection + (gethash (car attachment) updated-attachments) + links-to-update :test #'string-equal))) + (remhash (car attachment) updated-attachments)) + (return-from updated-link-in-attachment ret))))) (defun update-attached-object-poses (robot-object link pose) "Updates the poses of all objects that are attached to @@ -497,15 +529,16 @@ current joint states" child-body-to-its-link-transform))) (case (cl-urdf:joint-type urdf-joint) ((:revolute :continuous) - (multiple-value-bind (angle axis) - (cl-transforms:angle-between-quaternions - (cl-transforms:rotation map-to-urdf-joint-transform) - (cl-transforms:rotation map-to-child-link-transform)) - (if (< (cl-transforms:dot-product - axis (cl-urdf:axis urdf-joint)) - 0) - (* angle -1) - angle))) + (cl-transforms:normalize-angle + (multiple-value-bind (angle axis) + (cl-transforms:angle-between-quaternions + (cl-transforms:rotation map-to-urdf-joint-transform) + (cl-transforms:rotation map-to-child-link-transform)) + (if (< (cl-transforms:dot-product + axis (cl-urdf:axis urdf-joint)) + 0) + (* angle -1) + angle)))) (:prismatic (let ((urdf-joint-to-child-link-transform (cl-transforms:transform* @@ -535,7 +568,8 @@ current joint states" (setf (gethash name links) (rigid-body obj (name body)))) (loop for name being the hash-keys in joint-states do - (setf (gethash name joint-states) (or (calculate-joint-state obj name) 0.0d0))))) + (setf (gethash name joint-states) + (or (calculate-joint-state obj name) 0.0d0))))) (defmethod joint-state ((obj robot-object) name) (nth-value 0 (gethash name (joint-states obj)))) @@ -548,13 +582,14 @@ current joint states" (joint (gethash name (cl-urdf:joints urdf))) (parent (cl-urdf:parent joint)) (parent-pose (find-parent-pose obj name)) - (limits (cl-urdf:limits joint)) + (limits (when (slot-boundp joint 'cl-urdf:limits) + (cl-urdf:limits joint))) (joint-type (cl-urdf:joint-type joint))) (when (and limits (not (eq joint-type :continuous))) (when (eq joint-type :revolute) (setf new-value (cl-transforms:normalize-angle new-value))) - (unless (and (<= new-value (cl-urdf:upper limits)) - (>= new-value (cl-urdf:lower limits))) + (unless (and (<= new-value (+ (cl-urdf:upper limits) 0.0000001)) + (>= new-value (- (cl-urdf:lower limits) 0.0000001))) (setf new-value (min (max new-value (cl-urdf:lower limits)) (cl-urdf:upper limits))) (warn "Trying to assert joint value for ~a to ~a but limits are (~a; ~a)" diff --git a/cram_3d_world/cram_bullet_reasoning/src/visibility-reasoning.lisp b/cram_3d_world/cram_bullet_reasoning/src/visibility-reasoning.lisp index 40605f5f22..2d5e4b8541 100644 --- a/cram_3d_world/cram_bullet_reasoning/src/visibility-reasoning.lisp +++ b/cram_3d_world/cram_bullet_reasoning/src/visibility-reasoning.lisp @@ -1,20 +1,21 @@ ;;; ;;; Copyright (c) 2010, Lorenz Moesenlechner +;;; 2020, Christopher Pollok ;;; All rights reserved. -;;; +;;; ;;; Redistribution and use in source and binary forms, with or without ;;; modification, are permitted provided that the following conditions are met: -;;; +;;; ;;; * Redistributions of source code must retain the above copyright ;;; notice, this list of conditions and the following disclaimer. ;;; * Redistributions in binary form must reproduce the above copyright ;;; notice, this list of conditions and the following disclaimer in the ;;; documentation and/or other materials provided with the distribution. ;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software ;;; without specific prior written permission. -;;; +;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" ;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE ;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE @@ -31,11 +32,27 @@ (in-package :btr) (defvar *rendering-context* nil) -(defvar *visibility-threshold* 0.9) +(defparameter *visibility-threshold* 0.9 + "Percentage of object pixels that has to be in the rendered image +to consider the object as visible.") +(defparameter *pose-visibility-threshold* 0.2 + "Percentage of a 5cm radius sphere's pixels that has to be in the rendered image +to consider the pose at the center of the sphere as visible.") +(defparameter *total-pixel-threshold* 5 + "The minimum number of pixels that have to be in the rendered image +to consider the object as in the camera view.") + +(defparameter *visibility-sphere-name* :visibility-sphere + "The name of the bullet object to spawn for testing for pose visibility.") +(defparameter *visibility-sphere-default-pose* '((0 0 -1) (0 0 0 1)) + "Deleting and spawning the visibility sphere is awkward, because if a failure +happens, it will just stay there. So instead we can also just hide it.") (defstruct object-visibility percentage - occluding-objects) + occluding-objects + percentage-without-occlusion + total-object-pixels) (defclass flat-color-object-proxy () ((object :initarg :object :reader proxied-object) @@ -101,8 +118,8 @@ :pose camera-centered :width width :height height)))) (camera (make-instance 'camera - :pose camera-pose - :width width :height height)) + :pose camera-pose + :width width :height height)) (object-buffer (car (render-to-framebuffer rendering-context object camera))) (obj-ref-color nil) @@ -115,9 +132,9 @@ for obj in objects for i from step by step for obj-proxy = (make-instance - 'flat-color-object-proxy - :object obj - :color `(,i ,i ,i 1)) + 'flat-color-object-proxy + :object obj + :color `(,i ,i ,i 1)) when (eq object obj) do (setf obj-ref-color i) collecting obj-proxy)) @@ -135,6 +152,7 @@ (loop for i below (* (width camera) (height camera) 3) by 3 with object-total-pixels = 0 with object-visible-pixels = 0 + with object-visible-pixels-without-occlusion = 0 with occluding-object-colors = nil ;; threshold since colors are float values and not ;; always exactly what they should be @@ -144,6 +162,8 @@ reasoning-world)))) when (> (aref object-total-buffer i) 0.0) do (incf object-total-pixels) + when (> (aref object-buffer i) 0.0) + do (incf object-visible-pixels-without-occlusion) if (< (abs (- (aref scene-buffer i) obj-ref-color)) object-color-threshold) do (incf object-visible-pixels) @@ -152,40 +172,89 @@ (pushnew (aref scene-buffer i) occluding-object-colors)) finally (return (make-object-visibility - :percentage (cond ((> object-visible-pixels - object-total-pixels) - 1.0) - ((> object-total-pixels - 0) - (coerce - (/ object-visible-pixels - object-total-pixels) - 'single-float)) - (t 0.0)) + :percentage + (cond ((> object-visible-pixels + object-total-pixels) + 1.0) + ((> object-total-pixels + 0) + (coerce + (/ object-visible-pixels + object-total-pixels) + 'single-float)) + (t 0.0)) :occluding-objects (mapcar #'proxied-object (remove-if-not (lambda (o) (block block-check - (loop for col-occ in occluding-object-colors - with col-pr = (car (slot-value - o 'color)) - when (< (abs (- col-occ - col-pr)) - object-color-threshold) - do (return-from block-check - T)))) - object-proxies)))))))))))) - -(defun object-visible-p (world camera-pose object &optional(threshold *visibility-threshold*)) - "Returns T if at least `threshold' of the object is visible" + (loop for col-occ in occluding-object-colors + with col-pr = (car (slot-value + o 'color)) + when (< (abs (- col-occ + col-pr)) + object-color-threshold) + do (return-from block-check + T)))) + object-proxies)) + :percentage-without-occlusion + (cond ((> object-visible-pixels-without-occlusion + object-total-pixels) + 1.0) + ((> object-total-pixels + 0) + (coerce + (/ object-visible-pixels-without-occlusion + object-total-pixels) + 'single-float)) + (t 0.0)) + :total-object-pixels + object-total-pixels)))))))))) + +(defun object-visible-p (world camera-pose object + &optional (threshold *visibility-threshold*)) + "Returns T if at least `threshold' percent of the `object' pixels are visible." (let ((visibility (calculate-object-visibility world camera-pose object))) (>= (object-visibility-percentage visibility) threshold))) -(defun occluding-objects (world camera-pose object &optional (threshold *visibility-threshold*)) - "Returns the list of occluding objects if less than `threshold' of `object' is visible" +(defun occluding-objects (world camera-pose object + &optional (threshold *visibility-threshold*)) + "Returns the list of occluding objects if less than `threshold' percent +of `object' pixels are visible." (let ((visibility (calculate-object-visibility world camera-pose object))) (when (< (object-visibility-percentage visibility) threshold) (object-visibility-occluding-objects visibility)))) + +(defun looking-at-object-p (world camera-pose object + &optional (threshold *visibility-threshold*)) + "Returns T if at least `threshold' of the `object' is +within the robot's view frame. Even if the `object' is occluded, if the camera +is directed towards the `object', the predicate will be T. +If a part of the `object', visible or occluded, is clipped in the image, +the predicate is NIL." + (let ((visibility (calculate-object-visibility world camera-pose object))) + (>= (object-visibility-percentage-without-occlusion visibility) + threshold))) + +(defun object-in-view-p (world camera-pose object + &optional (threshold *total-pixel-threshold*)) + "Returns T if at least `threshold' pixels of the `object' are visible +in the robot's view frame. Even if the `object' is fully occluded, +if a couple of pixels are in the view, this predicate is T." + (let ((visibility (calculate-object-visibility world camera-pose object))) + (>= (object-visibility-total-object-pixels visibility) + threshold))) + +(defun looking-at-pose-p (world camera-pose pose + &optional (threshold *pose-visibility-threshold*)) + (unwind-protect + (let ((sphere + (or (object world *visibility-sphere-name*) + (add-object world :sphere *visibility-sphere-name* pose + :radius 0.05 :mass 0.0 :color '(1.0 0.0 0.0))))) + (looking-at-object-p world camera-pose sphere threshold)) + (when (object world *visibility-sphere-name*) + (setf (pose (object world *visibility-sphere-name*)) + (ensure-pose *visibility-sphere-default-pose*))))) diff --git a/cram_3d_world/cram_bullet_reasoning/src/world-facts.lisp b/cram_3d_world/cram_bullet_reasoning/src/world-facts.lisp index 316a7ba846..270c24f5cd 100644 --- a/cram_3d_world/cram_bullet_reasoning/src/world-facts.lisp +++ b/cram_3d_world/cram_bullet_reasoning/src/world-facts.lisp @@ -105,7 +105,18 @@ (lisp-type ?object-instance item) (get-slot-value ?object-instance types ?types) (member ?type ?types)) - + + (<- (item ?world ?name) + (bullet-world ?world) + (-> (bound ?name) + (and (or (lisp-type ?name symbol) + (lisp-type ?name string)) + (lisp-fun object ?world ?name ?item) + (lisp-type ?item item)) + (and (lisp-fun find-items ?world ?items) + (member ?item ?items) + (lisp-fun name ?item ?name)))) + (<- (%object ?world ?name ?obj) (bound ?name) (or (lisp-type ?name symbol) @@ -128,7 +139,7 @@ (lisp-fun find-objects ?world ?objs) (member ?obj ?objs) (lisp-fun name ?obj ?name)) - + ;; Performs one simulation step in the world (<- (step ?world) (step ?world 0.01)) diff --git a/cram_3d_world/cram_bullet_reasoning/src/world-utils.lisp b/cram_3d_world/cram_bullet_reasoning/src/world-utils.lisp index 940f6b7df2..e0ef3179c0 100644 --- a/cram_3d_world/cram_bullet_reasoning/src/world-utils.lisp +++ b/cram_3d_world/cram_bullet_reasoning/src/world-utils.lisp @@ -50,8 +50,10 @@ (defun find-objects (world &optional (pred (constantly t))) "Finds all objects that match the predicate" - (remove-if-not - pred (objects world))) + (remove-if-not pred (objects world))) + +(defun find-items (world) + (find-objects world (lambda (obj) (typep obj 'item)))) (defun contact-p (world obj-1 obj-2) "Returns T if obj-1 and obj-2 are in contact" diff --git a/cram_3d_world/cram_bullet_reasoning/tests/compound-meshes-tests.lisp b/cram_3d_world/cram_bullet_reasoning/tests/compound-meshes-tests.lisp index 7a73cf6f6d..834518cab6 100644 --- a/cram_3d_world/cram_bullet_reasoning/tests/compound-meshes-tests.lisp +++ b/cram_3d_world/cram_bullet_reasoning/tests/compound-meshes-tests.lisp @@ -48,30 +48,38 @@ :normal (0 0 1) :constant 0)))) (loop until (object btr:*current-bullet-world* :floor)) - (labels ((spawn-stack (y-offset name-prefix mesh) - (loop for id below plate-num - for plate-id = (intern (format nil "~a~a" name-prefix id) :keyword) - do (prolog:prolog - `(and - (btr:bullet-world ?world) - (assert (btr:object ?world :mesh - ,plate-id - ((0 - ,y-offset - ,(+ 0.1 (* (coerce id 'float) 0.1))) - (0 0 0 1)) - :mass 0.2 - :color (1 0 0) - :scale 5 - :mesh ,mesh)) - (btr:simulate ?world ,simulation-interval))))) - (z-coord (obj-name) - (cl-transforms:z - (cl-transforms:origin - (btr:pose (btr:object btr:*current-bullet-world* obj-name)))))) + (flet ((spawn-stack (y-offset name-prefix mesh) + (loop for id below plate-num + for plate-id = (intern (format nil "~a~a" name-prefix id) :keyword) + do (prolog:prolog + `(and + (btr:bullet-world ?world) + (assert (btr:object ?world :mesh + ,plate-id + ((0 + ,y-offset + ,(+ 0.1 (* (coerce id 'float) 0.1))) + (0 0 0 1)) + :mass 0.2 + :color (1 0 0) + :scale 5 + :mesh ,mesh)) + (btr:simulate ?world ,simulation-interval))))) + (kill-stack (name-prefix) + (loop for id below plate-num + for plate-id = (intern (format nil "~a~a" name-prefix id) + :keyword) + do (btr:remove-object btr:*current-bullet-world* plate-id))) + (z-coord (obj-name) + (cl-transforms:z + (cl-transforms:origin + (btr:pose (btr:object btr:*current-bullet-world* obj-name)))))) (spawn-stack 0.0 "PLATE-COMPOUND-" :plate-compound) (spawn-stack 2.0 "PLATE-" :plate) (btr:simulate btr:*current-bullet-world* 100) (lisp-unit:assert-true (< (z-coord :plate-compound-4) - (z-coord :plate-4))))) + (z-coord :plate-4))) + ;; delete plates + (kill-stack "PLATE-COMPOUND-") + (kill-stack "PLATE-"))) (setf btr:*all-meshes-as-compound* old-all-meshes-as-compound)))) diff --git a/cram_3d_world/cram_bullet_reasoning/tests/items-tests.lisp b/cram_3d_world/cram_bullet_reasoning/tests/items-tests.lisp index b6eb4f1a83..2ea14c7817 100644 --- a/cram_3d_world/cram_bullet_reasoning/tests/items-tests.lisp +++ b/cram_3d_world/cram_bullet_reasoning/tests/items-tests.lisp @@ -31,7 +31,9 @@ (define-test attach-object-bidirectional-and-attachment-type - ;; Attaches two objects and check their attached objects and the attachment-type of these + ;; Attaches two objects and check their attached objects and the + ;; attachment-type of these + (spawn-robot) (btr-utils:spawn-object 'o1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (btr-utils:spawn-object 'o2 :mug :pose @@ -42,21 +44,26 @@ (btr:object btr:*current-bullet-world* 'o2) :attachment-type :test-type) ;; these are connected: o1 <-> o2 - (lisp-unit:assert-equal 'o2 (car (assoc 'o2 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o1))))) - (lisp-unit:assert-equal 'o1 (car (assoc 'o1 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o2))))) + (lisp-unit:assert-equal 'o2 (car (assoc 'o2 (btr:attached-objects (btr:object + btr:*current-bullet-world* 'o1))))) + (lisp-unit:assert-equal 'o1 (car (assoc 'o1 (btr:attached-objects (btr:object + btr:*current-bullet-world* 'o2))))) ;; and the attachment-type fits too (lisp-unit:assert-equal :test-type (btr::attachment-attachment - (first (car (cdr (assoc 'o2 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o1)))))))) + (first (car (cdr (assoc 'o2 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'o1)))))))) (lisp-unit:assert-equal :test-type (btr::attachment-attachment - (first (car (cdr (assoc 'o1 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o2)))))))) + (first (car (cdr (assoc 'o1 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'o2)))))))) ;; recreate begin state for next test case (btr:remove-object btr:*current-bullet-world* 'o1) (btr:remove-object btr:*current-bullet-world* 'o2)) (define-test attach-object-bidirectional-more-than-two-objects ;; Attaches three objects and 'o1 is connected with both objects + (spawn-robot) (btr-utils:spawn-object 'o1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (btr-utils:spawn-object 'o2 :mug :pose @@ -71,13 +78,19 @@ (btr:object btr:*current-bullet-world* 'o3)) ;;these are connected o2 <-> o1 <-> o3 - (lisp-unit:assert-equal 'o2 (car (assoc 'o2 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o1))))) - (lisp-unit:assert-equal 'o3 (car (assoc 'o3 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o1))))) - (lisp-unit:assert-equal 'o1 (car (assoc 'o1 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o2))))) - (lisp-unit:assert-equal 'o1 (car (assoc 'o1 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o3))))) + (lisp-unit:assert-equal 'o2 (car (assoc 'o2 (btr:attached-objects (btr:object + btr:*current-bullet-world* 'o1))))) + (lisp-unit:assert-equal 'o3 (car (assoc 'o3 (btr:attached-objects (btr:object + btr:*current-bullet-world* 'o1))))) + (lisp-unit:assert-equal 'o1 (car (assoc 'o1 (btr:attached-objects (btr:object + btr:*current-bullet-world* 'o2))))) + (lisp-unit:assert-equal 'o1 (car (assoc 'o1 (btr:attached-objects (btr:object + btr:*current-bullet-world* 'o3))))) ;;these are not connected to each other: o2 o3 - (lisp-unit:assert-false (equal 'o2 (car (assoc 'o2 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o3)))))) - (lisp-unit:assert-false (equal 'o3 (car (assoc 'o3 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o2)))))) + (lisp-unit:assert-false (equal 'o2 (car (assoc 'o2 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'o3)))))) + (lisp-unit:assert-false (equal 'o3 (car (assoc 'o3 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'o2)))))) ;; recreate begin state for next test case (btr:remove-object btr:*current-bullet-world* 'o1) @@ -85,7 +98,9 @@ (btr:remove-object btr:*current-bullet-world* 'o3)) (define-test attach-object-more-objects-connected-bidirectional-to-one-object-in-one-call - ;; Attaches three objects and 'o1 is connected with both objects in one call + ;; Attaches three objects and 'o1 is connected with both objects in + ;; one call + (spawn-robot) (btr-utils:spawn-object 'o1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (btr-utils:spawn-object 'o2 :mug :pose @@ -100,13 +115,19 @@ (btr:object btr:*current-bullet-world* 'o1)) ;;these are connected o2 <-> o1 <-> o3 - (lisp-unit:assert-equal 'o2 (car (assoc 'o2 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o1))))) - (lisp-unit:assert-equal 'o3 (car (assoc 'o3 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o1))))) - (lisp-unit:assert-equal 'o1 (car (assoc 'o1 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o2))))) - (lisp-unit:assert-equal 'o1 (car (assoc 'o1 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o3))))) + (lisp-unit:assert-equal 'o2 (car (assoc 'o2 (btr:attached-objects (btr:object + btr:*current-bullet-world* 'o1))))) + (lisp-unit:assert-equal 'o3 (car (assoc 'o3 (btr:attached-objects (btr:object + btr:*current-bullet-world* 'o1))))) + (lisp-unit:assert-equal 'o1 (car (assoc 'o1 (btr:attached-objects (btr:object + btr:*current-bullet-world* 'o2))))) + (lisp-unit:assert-equal 'o1 (car (assoc 'o1 (btr:attached-objects (btr:object + btr:*current-bullet-world* 'o3))))) ;;these are not connected to each other: o2 o3 - (lisp-unit:assert-false (equal 'o2 (car (assoc 'o2 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o3)))))) - (lisp-unit:assert-false (equal 'o3 (car (assoc 'o3 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o2)))))) + (lisp-unit:assert-false (equal 'o2 (car (assoc 'o2 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'o3)))))) + (lisp-unit:assert-false (equal 'o3 (car (assoc 'o3 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'o2)))))) ;; recreate begin state for next test case (btr:remove-object btr:*current-bullet-world* 'o1) @@ -114,7 +135,9 @@ (btr:remove-object btr:*current-bullet-world* 'o3)) (define-test attach-object-more-objects-connected-unidirectional-to-one-object-in-one-call - ;; Attaches three objects and 'o1 is connected loose with both objects in one call + ;; Attaches three objects and 'o1 is connected loose with both + ;; objects in one call + (spawn-robot) (btr-utils:spawn-object 'o1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (btr-utils:spawn-object 'o2 :mug :pose @@ -132,22 +155,28 @@ ;;object 'o2 is normal attached to 'o1, so not loose attached. (lisp-unit:assert-equal nil (btr::attachment-loose - (first (car (cdr (assoc 'o1 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o2)))))))) + (first (car (cdr (assoc 'o1 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'o2)))))))) ;;object 'o1 is loose attached to 'o2 (lisp-unit:assert-equal T (btr::attachment-loose - (first (car (cdr (assoc 'o2 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o1)))))))) + (first (car (cdr (assoc 'o2 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'o1)))))))) ;;object 'o3 is normal attached to 'o1, so not loose attached. (lisp-unit:assert-equal nil (btr::attachment-loose - (first (car (cdr (assoc 'o1 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o3)))))))) + (first (car (cdr (assoc 'o1 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'o3)))))))) ;;object 'o1 is loose attached to 'o3 (lisp-unit:assert-equal T (btr::attachment-loose - (first (car (cdr (assoc 'o3 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o1)))))))) + (first (car (cdr (assoc 'o3 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'o1)))))))) ;;these are not connected to each other: o2 o3 - (lisp-unit:assert-false (equal 'o2 (car (assoc 'o2 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o3)))))) - (lisp-unit:assert-false (equal 'o3 (car (assoc 'o3 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o2)))))) + (lisp-unit:assert-false (equal 'o2 (car (assoc 'o2 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'o3)))))) + (lisp-unit:assert-false (equal 'o3 (car (assoc 'o3 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'o2)))))) ;; recreate begin state for next test case (btr:remove-object btr:*current-bullet-world* 'o1) @@ -155,7 +184,9 @@ (btr:remove-object btr:*current-bullet-world* 'o3)) (define-test attach-object-unidirectional - ;; Attaches two objects unidirectional and check if loose attachment was properly saved in the attachment + ;; Attaches two objects unidirectional and check if loose attachment + ;; was properly saved in the attachment + (spawn-robot) (btr-utils:spawn-object 'o1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (btr-utils:spawn-object 'o2 :mug :pose @@ -168,11 +199,13 @@ ;;object 'o1 is normal attached to 'o2, so not loose attached. (lisp-unit:assert-equal nil (btr::attachment-loose - (first (car (cdr (assoc 'o2 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o1)))))))) + (first (car (cdr (assoc 'o2 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'o1)))))))) ;;object 'o2 is loose attached to 'o1 (lisp-unit:assert-equal T (btr::attachment-loose - (first (car (cdr (assoc 'o1 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o2)))))))) + (first (car (cdr (assoc 'o1 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'o2)))))))) ;; recreate begin state for next test case (btr:remove-object btr:*current-bullet-world* 'o1) @@ -187,6 +220,7 @@ ;; bidirectional with the mug and attach it loose to a hook. Therefore the loose attachment of ;; the mug and tray-1 should be removed and the hook and handle should be in an loose ;; connection. + (spawn-robot) (btr-utils:spawn-object 'handle :mug :pose ;; '((-1 0.0 0.92)(0 0 0 1))) ;; (btr-utils:spawn-object 'mug :mug :pose ;; (X) @@ -195,38 +229,46 @@ '((-1 0.0 0.92)(0 0 0 1))) ;; | move handle to hook | | (btr-utils:spawn-object 'hook :mug :pose ;; tray_1 tray_1 hook '((-1 0.0 0.92)(0 0 0 1))) ;; - ;; WITH ATTACHING THE HANDLE TO THE HOOK THE MARKED LOOSE ATTACHMENT SHOULD BE REMOVED + ;; WITH ATTACHING THE HANDLE TO THE HOOK THE MARKED LOOSE ATTACHMENT SHOULD BE REMOVED (btr:attach-object 'handle 'mug) (btr:attach-object 'tray-1 'mug :loose T) ;; tray-1 -> mug ;;object 'mug is normal attached to 'handle, so not loose attached. (lisp-unit:assert-equal nil (btr::attachment-loose - (first (car (cdr (assoc 'mug (btr:attached-objects (btr:object btr:*current-bullet-world* 'handle)))))))) + (first (car (cdr (assoc 'mug (btr:attached-objects + (btr:object btr:*current-bullet-world* 'handle)))))))) (lisp-unit:assert-equal nil (btr::attachment-loose - (first (car (cdr (assoc 'handle (btr:attached-objects (btr:object btr:*current-bullet-world* 'mug)))))))) + (first (car (cdr (assoc 'handle (btr:attached-objects + (btr:object btr:*current-bullet-world* 'mug)))))))) ;;object 'mug is loose attached to 'tray-1 (lisp-unit:assert-equal T (btr::attachment-loose - (first (car (cdr (assoc 'tray-1 (btr:attached-objects (btr:object btr:*current-bullet-world* 'mug)))))))) + (first (car (cdr (assoc 'tray-1 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'mug)))))))) (lisp-unit:assert-equal nil (btr::attachment-loose - (first (car (cdr (assoc 'mug (btr:attached-objects (btr:object btr:*current-bullet-world* 'tray-1)))))))) + (first (car (cdr (assoc 'mug (btr:attached-objects + (btr:object btr:*current-bullet-world* 'tray-1)))))))) ;;now we put the handle on the hook (btr:attach-object 'hook 'handle :loose T) ;;so the connection between 'mug and 'tray-1 is gone - (lisp-unit:assert-false (car (assoc 'tray-1 (btr:attached-objects (btr:object btr:*current-bullet-world* 'mug))))) - (lisp-unit:assert-false (car (assoc 'mug (btr:attached-objects (btr:object btr:*current-bullet-world* 'tray-1))))) + (lisp-unit:assert-false (car (assoc 'tray-1 (btr:attached-objects (btr:object + btr:*current-bullet-world* 'mug))))) + (lisp-unit:assert-false (car (assoc 'mug (btr:attached-objects (btr:object + btr:*current-bullet-world* 'tray-1))))) ;;handle is loose attached to 'hook (lisp-unit:assert-equal T (btr::attachment-loose - (first (car (cdr (assoc 'hook (btr:attached-objects (btr:object btr:*current-bullet-world* 'handle)))))))) + (first (car (cdr (assoc 'hook (btr:attached-objects + (btr:object btr:*current-bullet-world* 'handle)))))))) (lisp-unit:assert-equal nil (btr::attachment-loose - (first (car (cdr (assoc 'handle (btr:attached-objects (btr:object btr:*current-bullet-world* 'hook)))))))) + (first (car (cdr (assoc 'handle (btr:attached-objects + (btr:object btr:*current-bullet-world* 'hook)))))))) ;; recreate begin state for next test case (btr:remove-object btr:*current-bullet-world* 'mug) @@ -235,29 +277,36 @@ (btr:remove-object btr:*current-bullet-world* 'hook)) (define-test detach-object-simple-and-bidirectional-attachments - ;; Detaches two bidirectional conntected objects + ;; Detaches two bidirectional conntected objects + (spawn-robot) (btr-utils:spawn-object 'oo1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (btr-utils:spawn-object 'oo2 :mug :pose '((-1 0.75 0.92)(0 0 0 1))) - + (btr:attach-object (btr:object btr:*current-bullet-world* 'oo1) (btr:object btr:*current-bullet-world* 'oo2)) ;; oo1 and oo2 are connected like this: oo1 <-> oo2 - (lisp-unit:assert-equal 'oo2 (car (assoc 'oo2 (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo1))))) - (lisp-unit:assert-equal 'oo1 (car (assoc 'oo1 (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo2))))) + (lisp-unit:assert-equal 'oo2 (car (assoc 'oo2 (btr:attached-objects (btr:object + btr:*current-bullet-world* 'oo1))))) + (lisp-unit:assert-equal 'oo1 (car (assoc 'oo1 (btr:attached-objects (btr:object + btr:*current-bullet-world* 'oo2))))) ;; detach oo1 and oo2 (btr:detach-object (btr:object btr:*current-bullet-world* 'oo1) (btr:object btr:*current-bullet-world* 'oo2)) - (lisp-unit:assert-false (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo1))) - (lisp-unit:assert-false (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo2))) + (lisp-unit:assert-false (btr:attached-objects (btr:object btr:*current-bullet-world* + 'oo1))) + (lisp-unit:assert-false (btr:attached-objects (btr:object btr:*current-bullet-world* + 'oo2))) ;; recreate begin state for next test case (btr:remove-object btr:*current-bullet-world* 'oo1) (btr:remove-object btr:*current-bullet-world* 'oo2)) + (define-test detach-object-dont-remove-other-attachments-and-unidirectional - ;; Detaches two objects where one object has one attached object + ;; Detaches two objects where one object has one attached object + (spawn-robot) (btr-utils:spawn-object 'oo1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (btr-utils:spawn-object 'oo2 :mug :pose @@ -275,20 +324,27 @@ ;;object 'oo1 is normal attached to 'oo2, so not loose attached. (lisp-unit:assert-equal nil (btr::attachment-loose - (first (car (cdr (assoc 'oo2 (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo1)))))))) + (first (car (cdr (assoc 'oo2 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'oo1)))))))) ;;object 'oo2 is loose attached to 'oo1 (lisp-unit:assert-equal T (btr::attachment-loose - (first (car (cdr (assoc 'oo1 (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo2)))))))) + (first (car (cdr (assoc 'oo1 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'oo2)))))))) ;; detach oo1 and oo2 (btr:detach-object (btr:object btr:*current-bullet-world* 'oo1) (btr:object btr:*current-bullet-world* 'oo2)) ;; 'oo1 and 'oo2 should be attached anymore, but oo3 and oo1 still - (lisp-unit:assert-false (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo2))) - (lisp-unit:assert-equal 'oo3 (car (assoc 'oo3 (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo1))))) - (lisp-unit:assert-number-equal 1 (list-length (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo1)))) - (lisp-unit:assert-equal 'oo1 (car (assoc 'oo1 (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo3))))) - (lisp-unit:assert-number-equal 1 (list-length (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo3)))) + (lisp-unit:assert-false (btr:attached-objects (btr:object btr:*current-bullet-world* + 'oo2))) + (lisp-unit:assert-equal 'oo3 (car (assoc 'oo3 (btr:attached-objects (btr:object + btr:*current-bullet-world* 'oo1))))) + (lisp-unit:assert-number-equal 1 (list-length (btr:attached-objects (btr:object + btr:*current-bullet-world* 'oo1)))) + (lisp-unit:assert-equal 'oo1 (car (assoc 'oo1 (btr:attached-objects (btr:object + btr:*current-bullet-world* 'oo3))))) + (lisp-unit:assert-number-equal 1 (list-length (btr:attached-objects (btr:object + btr:*current-bullet-world* 'oo3)))) ;; recreate begin state for next test case (btr:remove-object btr:*current-bullet-world* 'oo1) @@ -296,9 +352,9 @@ (btr:remove-object btr:*current-bullet-world* 'oo3)) - (define-test detach-all-objects-star-connection - ;; Detaches all attachments of one object x and check if the attachments of attached objects from x still exists + ;; Detaches all attachments of one object x and check if the + ;; attachments of attached objects from x still exists (btr-utils:spawn-object 'oo1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (btr-utils:spawn-object 'oo2 :mug :pose @@ -316,20 +372,27 @@ ;; v ;; oo4 ;; - ;; the marked attachments (x) should be removed after calling detach-all-objects with oo1 + ;; the marked attachments (x) should be removed after calling + ;; detach-all-objects with oo1 (btr:attach-object 'oo1 'oo2) (btr:attach-object 'oo1 'oo3) (btr:attach-object 'oo1 'oo4) (btr:attach-object 'oo2 'oo5) - (lisp-unit:assert-number-equal 3 (list-length (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo1)))) + (lisp-unit:assert-number-equal 3 (list-length (btr:attached-objects (btr:object + btr:*current-bullet-world* 'oo1)))) ;; Detaches 'oo1 with objects oo2, oo3 and oo4, but not oo5 (btr:detach-all-objects (btr:object btr:*current-bullet-world* 'oo1)) - (lisp-unit:assert-number-equal 0 (list-length (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo1)))) - (lisp-unit:assert-number-equal 1 (list-length (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo2)))) - (lisp-unit:assert-equal 'oo5 (car (assoc 'oo5 (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo2))))) - (lisp-unit:assert-equal 'oo2 (car (assoc 'oo2 (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo5))))) - (lisp-unit:assert-number-equal 0 (list-length (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo3)))) + (lisp-unit:assert-number-equal 0 (list-length (btr:attached-objects (btr:object + btr:*current-bullet-world* 'oo1)))) + (lisp-unit:assert-number-equal 1 (list-length (btr:attached-objects (btr:object + btr:*current-bullet-world* 'oo2)))) + (lisp-unit:assert-equal 'oo5 (car (assoc 'oo5 (btr:attached-objects (btr:object + btr:*current-bullet-world* 'oo2))))) + (lisp-unit:assert-equal 'oo2 (car (assoc 'oo2 (btr:attached-objects (btr:object + btr:*current-bullet-world* 'oo5))))) + (lisp-unit:assert-number-equal 0 (list-length (btr:attached-objects (btr:object + btr:*current-bullet-world* 'oo3)))) ;; recreate begin state for next test case (btr:remove-object btr:*current-bullet-world* 'oo1) @@ -338,8 +401,585 @@ (btr:remove-object btr:*current-bullet-world* 'oo4) (btr:remove-object btr:*current-bullet-world* 'oo5)) +(define-test attach-object-with-static-objects-correct-collision-information + (spawn-robot) + (btr-utils:spawn-object 'oo1 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (btr-utils:spawn-object 'oo2 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (btr-utils:spawn-object 'oo3 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (loop for body in (apply 'concatenate 'list + (list (btr:rigid-bodies (btr:object + btr:*current-bullet-world* + 'oo1)) + (btr:rigid-bodies (btr:object + btr:*current-bullet-world* + 'oo2)) + (btr:rigid-bodies (btr:object + btr:*current-bullet-world* + 'oo3)))) + do + (setf + (btr::collision-flags body) + :CF-STATIC-OBJECT)) + (btr:attach-object 'oo1 'oo2) + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'oo1)))))) + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'oo2)))))) + (assert-equal + :CF-STATIC-OBJECT + (car + (btr::collision-information-flags + (caddr + (find 'oo1 + (btr:attached-objects + (btr:object + btr:*current-bullet-world* + 'oo2)) + :key #'car))))) + (assert-equal + :CF-STATIC-OBJECT + (car + (btr::collision-information-flags + (caddr + (find 'oo2 + (btr:attached-objects + (btr:object + btr:*current-bullet-world* + 'oo1)) + :key #'car))))) + (btr:attach-object 'oo1 'oo3) + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'oo1)))))) + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'oo3)))))) + (assert-equal + :CF-STATIC-OBJECT + (car + (btr::collision-information-flags + (caddr + (find 'oo3 + (btr:attached-objects + (btr:object + btr:*current-bullet-world* + 'oo1)) + :key #'car))))) + (assert-equal + :CF-STATIC-OBJECT + (car + (btr::collision-information-flags + (caddr + (find 'oo1 + (btr:attached-objects + (btr:object + btr:*current-bullet-world* + 'oo3)) + :key #'car))))) + (assert-equal + :CF-STATIC-OBJECT + (car + (btr::collision-information-flags + (caddr + (find 'oo1 + (btr:attached-objects + (btr:object + btr:*current-bullet-world* + 'oo2)) + :key #'car))))) + (assert-equal + :CF-STATIC-OBJECT + (car + (btr::collision-information-flags + (caddr + (find 'oo2 + (btr:attached-objects + (btr:object + btr:*current-bullet-world* + 'oo1)) + :key #'car))))) + (btr:remove-object btr:*current-bullet-world* 'oo1) + (btr:remove-object btr:*current-bullet-world* 'oo2) + (btr:remove-object btr:*current-bullet-world* 'oo3)) + +(define-test attach-object-correct-collision-information + (spawn-robot) + (btr-utils:spawn-object 'oo1 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (btr-utils:spawn-object 'oo2 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (btr-utils:spawn-object 'oo3 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (btr:attach-object 'oo1 'oo2) + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'oo1)))))) + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'oo2)))))) + (assert-equal + NIL + (car + (btr::collision-information-flags + (caddr + (find 'oo1 + (btr:attached-objects + (btr:object + btr:*current-bullet-world* + 'oo2)) + :key #'car))))) + (assert-equal + NIL + (car + (btr::collision-information-flags + (caddr + (find 'oo2 + (btr:attached-objects + (btr:object + btr:*current-bullet-world* + 'oo1)) + :key #'car))))) + (btr:attach-object 'oo1 'oo3) + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'oo1)))))) + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'oo3)))))) + (assert-equal + NIL + (car + (btr::collision-information-flags + (caddr + (find 'oo3 + (btr:attached-objects + (btr:object + btr:*current-bullet-world* + 'oo1)) + :key #'car))))) + (assert-equal + NIL + (car + (btr::collision-information-flags + (caddr + (find 'oo1 + (btr:attached-objects + (btr:object + btr:*current-bullet-world* + 'oo3)) + :key #'car))))) + (assert-equal + NIL + (car + (btr::collision-information-flags + (caddr + (find 'oo1 + (btr:attached-objects + (btr:object + btr:*current-bullet-world* + 'oo2)) + :key #'car))))) + (assert-equal + NIL + (car + (btr::collision-information-flags + (caddr + (find 'oo2 + (btr:attached-objects + (btr:object + btr:*current-bullet-world* + 'oo1)) + :key #'car))))) + (btr:remove-object btr:*current-bullet-world* 'oo1) + (btr:remove-object btr:*current-bullet-world* 'oo2) + (btr:remove-object btr:*current-bullet-world* 'oo3)) + +(define-test detach-object-correct-collision-information + (spawn-robot) + (btr-utils:spawn-object 'oo1 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (btr-utils:spawn-object 'oo2 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (btr-utils:spawn-object 'oo3 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (btr:attach-object 'oo1 'oo2) + (btr:attach-object 'oo1 'oo3) + (btr:detach-object 'oo1 'oo2) + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'oo1)))))) + (assert-equal + NIL + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'oo2)))))) + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'oo3)))))) + (assert-equal + NIL + (car + (btr::collision-information-flags + (caddr + (find 'oo3 + (btr:attached-objects + (btr:object + btr:*current-bullet-world* + 'oo1)) + :key #'car))))) + (assert-equal + NIL + (car + (btr::collision-information-flags + (caddr + (find 'oo1 + (btr:attached-objects + (btr:object + btr:*current-bullet-world* + 'oo3)) + :key #'car))))) + (assert-false + (btr:attached-objects + (btr:object + btr:*current-bullet-world* + 'oo2))) + (btr:remove-object btr:*current-bullet-world* 'oo1) + (btr:remove-object btr:*current-bullet-world* 'oo2) + (btr:remove-object btr:*current-bullet-world* 'oo3)) + +(define-test detach-object-with-static-objects-correct-collision-information + (spawn-robot) + (btr-utils:spawn-object 'oo1 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (btr-utils:spawn-object 'oo2 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (btr-utils:spawn-object 'oo3 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (loop for body in (apply 'concatenate 'list + (list (btr:rigid-bodies (btr:object + btr:*current-bullet-world* + 'oo1)) + (btr:rigid-bodies (btr:object + btr:*current-bullet-world* + 'oo2)) + (btr:rigid-bodies (btr:object + btr:*current-bullet-world* + 'oo3)))) + do + (setf + (btr::collision-flags body) + :CF-STATIC-OBJECT)) + (btr:attach-object 'oo1 'oo2) + (btr:attach-object 'oo1 'oo3) + (btr:detach-object 'oo1 'oo2) + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'oo1)))))) + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'oo2)))))) + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'oo3)))))) + (assert-equal + :CF-STATIC-OBJECT + (car + (btr::collision-information-flags + (caddr + (find 'oo3 + (btr:attached-objects + (btr:object + btr:*current-bullet-world* + 'oo1)) + :key #'car))))) + (assert-equal + :CF-STATIC-OBJECT + (car + (btr::collision-information-flags + (caddr + (find 'oo1 + (btr:attached-objects + (btr:object + btr:*current-bullet-world* + 'oo3)) + :key #'car))))) + (assert-false + (btr:attached-objects + (btr:object + btr:*current-bullet-world* + 'oo2))) + (btr:remove-object btr:*current-bullet-world* 'oo1) + (btr:remove-object btr:*current-bullet-world* 'oo2) + (btr:remove-object btr:*current-bullet-world* 'oo3)) + +(define-test attach-object-and-detach-object-shopping-demo-collision-flags + (spawn-robot) + (spawn-environment) + (btr-utils:spawn-object 'basket :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (btr-utils:spawn-object 'oo1 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + ;; Attach object to environment and basket to the robot + (btr:attach-object (btr:get-robot-object) + (btr:object btr:*current-bullet-world* 'basket) + :link "r_wrist_roll_link" :loose nil :grasp :front) + (btr:attach-object (btr:get-environment-object) + (btr:object btr:*current-bullet-world* 'oo1 ) + :link "sink_area_surface") + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'basket)))))) + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'basket)))))) + ;; Robot grasps the object + ;; 1. detached from the env + (btr:detach-object (btr:get-environment-object) + (btr:object btr:*current-bullet-world* 'oo1)) + (assert-equal + NIL + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'oo1)))))) + ;; 2. attached to the robot + (btr:attach-object (btr:get-robot-object) + (btr:object btr:*current-bullet-world* 'oo1) + :link "l_wrist_roll_link" :loose nil :grasp :front) + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'oo1)))))) + ;; Place object into the basket + (btr:detach-object (btr:get-robot-object) + (btr:object btr:*current-bullet-world* 'oo1) + :link "l_wrist_roll_link") + ;; Object oo1 falls in the basket + (assert-equal + NIL + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'oo1)))))) + ;; Attach object to the basket + (btr:attach-object 'basket 'oo1) + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'basket)))))) + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'oo1)))))) + (btr:remove-object btr:*current-bullet-world* 'oo1) + (btr:remove-object btr:*current-bullet-world* 'basket) + (btr:detach-all-objects (btr:get-robot-object)) + (btr:detach-all-objects (btr:get-environment-object))) + +(define-test attach-object-and-detach-static-object-shopping-demo-collision-flags + (spawn-robot) + (spawn-environment) + (btr-utils:spawn-object 'basket :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (btr-utils:spawn-object 'oo1 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (loop for body in (apply 'concatenate 'list + (list (btr:rigid-bodies (btr:object + btr:*current-bullet-world* + 'oo1)) + (btr:rigid-bodies (btr:object + btr:*current-bullet-world* + 'basket)))) + do + (setf + (btr::collision-flags body) + :CF-STATIC-OBJECT)) + ;; Attach object to environment and basket to the robot + (btr:attach-object (btr:get-robot-object) + (btr:object btr:*current-bullet-world* 'basket) + :link "r_wrist_roll_link" :loose nil :grasp :front) + (btr:attach-object (btr:get-environment-object) + (btr:object btr:*current-bullet-world* 'oo1 ) + :link "sink_area_surface") + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'basket)))))) + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'basket)))))) + ;; Robot grasps the object + ;; 1. detached from the env + (btr:detach-object (btr:get-environment-object) + (btr:object btr:*current-bullet-world* 'oo1)) + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'oo1)))))) + ;; 2. attached to the robot + (btr:attach-object (btr:get-robot-object) + (btr:object btr:*current-bullet-world* 'oo1) + :link "l_wrist_roll_link" :loose nil :grasp :front) + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'oo1)))))) + ;; Place object into the basket + (btr:detach-object (btr:get-robot-object) + (btr:object btr:*current-bullet-world* 'oo1) + :link "l_wrist_roll_link") + ;; Object oo1 falls in the basket + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'oo1)))))) + ;; Attach object to the basket + (btr:attach-object 'basket 'oo1) + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'basket)))))) + (assert-equal + :CF-STATIC-OBJECT + (car (btr::collision-flags + (car + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'oo1)))))) + (btr:remove-object btr:*current-bullet-world* 'oo1) + (btr:remove-object btr:*current-bullet-world* 'basket) + (btr:detach-all-objects (btr:get-robot-object)) + (btr:detach-all-objects (btr:get-environment-object))) + + (define-test get-loose-attached-objects-simple ;; Returns the loose attachments of an object + (spawn-robot) (btr-utils:spawn-object 'oo1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (btr-utils:spawn-object 'oo2 :mug :pose @@ -366,10 +1006,12 @@ (btr:attach-object 'oo1 'oo2 :loose T) (btr:attach-object 'oo2 'oo3) (btr:attach-object 'oo2 'oo4) - (btr:attach-object 'oo5 'oo2 :loose T :skip-removing-loose T) ;; the :skip-removing-loose key is used so the loose attachement between - ;; 'oo2 and 'oo1 won't get removed + (btr:attach-object 'oo5 'oo2 :loose T :skip-removing-loose T) + ;; the :skip-removing-loose key is used so the loose attachement + ;; between 'oo2 and 'oo1 won't get removed - (let ((loose-attached-obj-names (btr::get-loose-attached-objects (btr:object btr:*current-bullet-world* 'oo2)))) + (let ((loose-attached-obj-names (btr::get-loose-attached-objects (btr:object + btr:*current-bullet-world* 'oo2)))) (lisp-unit:assert-equal 'oo5 (first loose-attached-obj-names)) (lisp-unit:assert-equal 'oo1 (second loose-attached-obj-names))) @@ -381,6 +1023,7 @@ (define-test remove-loose-attachment-for-simple ;; Removes the loose attachments of an object + (spawn-robot) (btr-utils:spawn-object 'oo1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (btr-utils:spawn-object 'oo2 :mug :pose @@ -407,13 +1050,18 @@ (btr:attach-object 'oo1 'oo2 :loose T) (btr:attach-object 'oo2 'oo3) (btr:attach-object 'oo2 'oo4) - (btr:attach-object 'oo5 'oo2 :loose T :skip-removing-loose T) ;; the :skip-removing-loose key is used so the loose attachement between - ;; 'oo2 and 'oo1 won't get removed + (btr:attach-object 'oo5 'oo2 :loose T :skip-removing-loose T) + ;; the :skip-removing-loose key is used so the loose attachement + ;; between 'oo2 and 'oo1 won't get removed - (btr::remove-loose-attachment-for (btr:object btr:*current-bullet-world* 'oo2)) - (lisp-unit:assert-equal 'oo3 (car (assoc 'oo3 (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo2))))) - (lisp-unit:assert-equal 'oo4 (car (assoc 'oo4 (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo2))))) - (lisp-unit:assert-number-equal 2 (list-length (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo2)))) + (btr::remove-loose-attachment-for (btr:object btr:*current-bullet-world* + 'oo2)) + (lisp-unit:assert-equal 'oo3 (car (assoc 'oo3 (btr:attached-objects (btr:object + btr:*current-bullet-world* 'oo2))))) + (lisp-unit:assert-equal 'oo4 (car (assoc 'oo4 (btr:attached-objects (btr:object + btr:*current-bullet-world* 'oo2))))) + (lisp-unit:assert-number-equal 2 (list-length (btr:attached-objects (btr:object + btr:*current-bullet-world* 'oo2)))) (btr:remove-object btr:*current-bullet-world* 'oo1) (btr:remove-object btr:*current-bullet-world* 'oo2) @@ -425,6 +1073,7 @@ ;; Attaches a new pose to an item with attached items, ;; so the pose of the attached items should change relative to the ;; item they are attached to too. + (spawn-robot) (btr-utils:spawn-object 'oo1 :mug :pose '((-1 0.0 0.9)(0 0 0 1))) (btr-utils:spawn-object 'oo2 :mug :pose @@ -440,27 +1089,38 @@ ;;set new pose to 'oo1: move 'oo1 0.1m upwards (setf (btr:pose (btr:object btr:*current-bullet-world* 'oo1)) (cl-transforms:make-pose - (cl-transforms:make-3d-vector -1 0.0 1) + (cl-transforms:make-3d-vector + -1 0.0 1) (cl-transforms:make-identity-rotation))) - (sleep 0.1) ;; idk why, but else the position of any attachment are not set yet + (sleep 0.1) + ;; idk why, but else the positions of any attachment are not set yet ;; new position of the item 'oo1 is set properly - (lisp-unit:assert-number-equal -1.0d0 (cl-tf:x (cl-tf:origin (btr:pose (btr:object btr:*current-bullet-world* 'oo1))))) - (lisp-unit:assert-number-equal 0.0d0 (cl-tf:y (cl-tf:origin (btr:pose (btr:object btr:*current-bullet-world* 'oo1))))) - (lisp-unit:assert-number-equal 1.0d0 (cl-tf:z (cl-tf:origin (btr:pose (btr:object btr:*current-bullet-world* 'oo1))))) + (lisp-unit:assert-number-equal -1.0d0 (cl-transforms:x (cl-transforms:origin (btr:pose + (btr:object btr:*current-bullet-world* 'oo1))))) + (lisp-unit:assert-number-equal 0.0d0 (cl-transforms:y (cl-transforms:origin (btr:pose + (btr:object btr:*current-bullet-world* 'oo1))))) + (lisp-unit:assert-number-equal 1.0d0 (cl-transforms:z (cl-transforms:origin (btr:pose + (btr:object btr:*current-bullet-world* 'oo1))))) ;; Changed values of z in the position of the attached items: ;; z_oo2 + 0.1 = 0.9 - (lisp-unit:assert-number-equal 0.9d0 (cl-tf:z (cl-tf:origin (btr:pose (btr:object btr:*current-bullet-world* 'oo2))))) + (lisp-unit:assert-number-equal 0.9d0 (cl-transforms:z (cl-transforms:origin (btr:pose + (btr:object btr:*current-bullet-world* 'oo2))))) ;; z_oo3 + 0.1 = 0.8 - (lisp-unit:assert-number-equal 0.8d0 (cl-tf:z (cl-tf:origin (btr:pose (btr:object btr:*current-bullet-world* 'oo3))))) + (lisp-unit:assert-number-equal 0.8d0 (cl-transforms:z (cl-transforms:origin (btr:pose + (btr:object btr:*current-bullet-world* 'oo3))))) ;; Still the same values x,y in the position of the attached items: ;; x - (lisp-unit:assert-number-equal -1.0d0 (cl-tf:x (cl-tf:origin (btr:pose (btr:object btr:*current-bullet-world* 'oo2))))) - (lisp-unit:assert-number-equal -1.0d0 (cl-tf:x (cl-tf:origin (btr:pose (btr:object btr:*current-bullet-world* 'oo3))))) + (lisp-unit:assert-number-equal -1.0d0 (cl-transforms:x (cl-transforms:origin (btr:pose + (btr:object btr:*current-bullet-world* 'oo2))))) + (lisp-unit:assert-number-equal -1.0d0 (cl-transforms:x (cl-transforms:origin (btr:pose + (btr:object btr:*current-bullet-world* 'oo3))))) ;; y - (lisp-unit:assert-number-equal 0.0d0 (cl-tf:y (cl-tf:origin (btr:pose (btr:object btr:*current-bullet-world* 'oo2))))) - (lisp-unit:assert-number-equal 0.0d0 (cl-tf:y (cl-tf:origin (btr:pose (btr:object btr:*current-bullet-world* 'oo3))))) + (lisp-unit:assert-number-equal 0.0d0 (cl-transforms:y (cl-transforms:origin (btr:pose + (btr:object btr:*current-bullet-world* 'oo2))))) + (lisp-unit:assert-number-equal 0.0d0 (cl-transforms:y (cl-transforms:origin (btr:pose + (btr:object btr:*current-bullet-world* 'oo3))))) (btr:remove-object btr:*current-bullet-world* 'oo1) (btr:remove-object btr:*current-bullet-world* 'oo2) diff --git a/cram_3d_world/cram_bullet_reasoning/tests/objects-tests.lisp b/cram_3d_world/cram_bullet_reasoning/tests/objects-tests.lisp index 88067d3640..1aded1f65b 100644 --- a/cram_3d_world/cram_bullet_reasoning/tests/objects-tests.lisp +++ b/cram_3d_world/cram_bullet_reasoning/tests/objects-tests.lisp @@ -29,7 +29,8 @@ (in-package :btr-tests) -;; Help functions to convert objects to lists, so these can be compared with equals +;; Help functions to convert objects to lists, so these can be +;; compared with equals (defun orientation->list (orient) (list (cl-transforms:w orient) (cl-transforms:x orient) @@ -49,154 +50,487 @@ (equal (pose->list pose) (pose->list other-pose))) +(defun spawn-robot () + (setf rob-int:*robot-urdf* + (cl-urdf:parse-urdf + (roslisp:get-param rob-int:*robot-description-parameter*))) + (prolog:prolog + `(and (btr:bullet-world ?world) + (rob-int:robot ?robot) + (assert (btr:object ?world :urdf ?robot ((0 0 0) (0 0 0 1)) + :urdf ,rob-int::*robot-urdf*)) + (assert (btr:joint-state ?world ?robot (("torso_lift_joint" + 0.15d0)))))) + (btr:detach-all-objects (btr:get-robot-object))) + +(defun spawn-environment () + (assert + (setf rob-int:*environment-urdf* + (cl-urdf:parse-urdf + (roslisp:get-param rob-int:*environment-description-parameter*)))) + (prolog:prolog + `(and (btr:bullet-world ?w) + (prolog:-> (rob-int:environment-name ?environment-name) + (btr:assert ?w (btr:object :urdf ?environment-name + ((0 0 0) (0 0 0 1)) + :collision-group :static-filter + :collision-mask (:default-filter + :character-filter) + :urdf ,rob-int:*environment-urdf* + :compound T)) + (warn "ROB-INT:ENVIRONMENT-NAME was not defined. ~ + Have you loaded an environment knowledge package?")))) + (clrhash (btr::get-updated-attachments)) + (btr:detach-all-objects (btr:get-robot-object))) (define-test create-static-collision-information-works - ;; Tests if the collision information is properly saved and if it has an effect on - ;; the object by simulating the bullet world - (btr-utils:spawn-object 'o1 :mug :pose + ;; Tests if the collision information is properly saved and if it + ;; has an effect on the object by simulating the bullet world + (btr-utils:spawn-object 'o1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (let* ((pose-o1 (btr:pose (btr:object btr:*current-bullet-world* 'o1)))) - - (btr::create-static-collision-information (btr:object btr:*current-bullet-world* 'o1)) + + (btr::create-static-collision-information + (btr:object btr:*current-bullet-world* 'o1)) (lisp-unit:assert-equal :CF-STATIC-OBJECT (car (cl-bullet:collision-flags (first - (btr:rigid-bodies (btr:object btr:*current-bullet-world* 'o1)))))) + (btr:rigid-bodies (btr:object + btr:*current-bullet-world* 'o1)))))) (btr:simulate btr:*current-bullet-world* 1) - (let ((new-pose-o1 (btr:pose (btr:object btr:*current-bullet-world* 'o1)))) - + (let ((new-pose-o1 + (btr:pose (btr:object btr:*current-bullet-world* 'o1)))) (lisp-unit:assert-true (pose-equal pose-o1 new-pose-o1)))) ;; recreate begin state for next test case (btr:remove-object btr:*current-bullet-world* 'o1)) +(define-test create-static-collision-information-works-with-more-objects + ;; Tests if the collision information is properly saved and if it + ;; has an effect on the object by simulating the bullet world + (btr-utils:spawn-object 'o1 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (btr-utils:spawn-object 'o2 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (let* ((pose-o1 (btr:pose (btr:object btr:*current-bullet-world* 'o1))) + (pose-o2 (btr:pose (btr:object btr:*current-bullet-world* 'o2)))) + + (lisp-unit:assert-equal + NIL + (car + (btr::collision-information-flags + (car + (btr::create-static-collision-information + (btr:object btr:*current-bullet-world* 'o1)))))) + (lisp-unit:assert-equal :CF-STATIC-OBJECT (car + (cl-bullet:collision-flags + (first + (btr:rigid-bodies (btr:object + btr:*current-bullet-world* 'o1)))))) + (lisp-unit:assert-equal + NIL + (car + (btr::collision-information-flags + (car + (btr::create-static-collision-information + (btr:object btr:*current-bullet-world* 'o2)))))) + (lisp-unit:assert-equal :CF-STATIC-OBJECT (car + (cl-bullet:collision-flags + (first + (btr:rigid-bodies (btr:object + btr:*current-bullet-world* 'o2)))))) + (btr:simulate btr:*current-bullet-world* 1) + (let ((new-pose-o1 + (btr:pose (btr:object btr:*current-bullet-world* 'o1))) + (new-pose-o2 + (btr:pose (btr:object btr:*current-bullet-world* 'o2)))) + (lisp-unit:assert-true (pose-equal pose-o1 new-pose-o1)) + (lisp-unit:assert-true (pose-equal pose-o2 new-pose-o2)))) + + ;; recreate begin state for next test case + (btr:remove-object btr:*current-bullet-world* 'o1) + (btr:remove-object btr:*current-bullet-world* 'o2)) + +(define-test create-static-collision-information-works-with-attached-objects + ;; Tests if the collision information is properly saved and if it + ;; has an effect on the object by simulating the bullet world + (spawn-robot) + (btr-utils:spawn-object 'o1 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (btr-utils:spawn-object 'o2 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (btr-utils:spawn-object 'o3 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (btr:attach-object 'o1 'o3) + (let* ((pose-o1 (btr:pose (btr:object btr:*current-bullet-world* 'o1))) + (pose-o2 (btr:pose (btr:object btr:*current-bullet-world* 'o2)))) + + (lisp-unit:assert-equal + NIL + (car + (btr::collision-information-flags + (car + (btr::create-static-collision-information + (btr:object btr:*current-bullet-world* 'o1)))))) + (lisp-unit:assert-equal :CF-STATIC-OBJECT (car + (cl-bullet:collision-flags + (first + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'o1)))))) + (lisp-unit:assert-equal + NIL + (car + (btr::collision-information-flags + (car + (btr::create-static-collision-information + (btr:object btr:*current-bullet-world* 'o2)))))) + (lisp-unit:assert-equal :CF-STATIC-OBJECT (car + (cl-bullet:collision-flags + (first + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'o2)))))) + (btr:simulate btr:*current-bullet-world* 1) + (let ((new-pose-o1 + (btr:pose (btr:object btr:*current-bullet-world* 'o1))) + (new-pose-o2 + (btr:pose (btr:object btr:*current-bullet-world* 'o2)))) + (lisp-unit:assert-true (pose-equal pose-o1 new-pose-o1)) + (lisp-unit:assert-true (pose-equal pose-o2 new-pose-o2)))) + ;; recreate begin state for next test case + (btr:remove-object btr:*current-bullet-world* 'o1) + (btr:remove-object btr:*current-bullet-world* 'o2) + (btr:remove-object btr:*current-bullet-world* 'o3)) -(define-test reset-collision-information-works - ;; Tests if the collision information is properly reseted and if it has an effect on - ;; the object by simulating the bullet world - (btr-utils:spawn-object 'o1 :mug :pose +(define-test create-static-collision-information-works-with-static-objects + ;; Tests if the collision information is properly saved and if it + ;; has an effect on the object by simulating the bullet world + (btr-utils:spawn-object 'o1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) - (btr-utils:spawn-object 'o2 :mug :pose + (btr-utils:spawn-object 'o2 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) + (loop for body in (apply 'concatenate 'list + (list (btr:rigid-bodies (btr:object + btr:*current-bullet-world* + 'o1)) + (btr:rigid-bodies (btr:object + btr:*current-bullet-world* + 'o2)))) + do + (setf + (btr::collision-flags body) + :CF-STATIC-OBJECT)) + (let* ((pose-o1 (btr:pose (btr:object btr:*current-bullet-world* 'o1))) + (pose-o2 (btr:pose (btr:object btr:*current-bullet-world* 'o2)))) + + (lisp-unit:assert-equal + :CF-STATIC-OBJECT + (car + (btr::collision-information-flags + (car + (btr::create-static-collision-information + (btr:object btr:*current-bullet-world* 'o1)))))) + (lisp-unit:assert-equal :CF-STATIC-OBJECT (car + (cl-bullet:collision-flags + (first + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'o1)))))) + (lisp-unit:assert-equal + :CF-STATIC-OBJECT + (car + (btr::collision-information-flags + (car + (btr::create-static-collision-information + (btr:object btr:*current-bullet-world* 'o2)))))) + (lisp-unit:assert-equal :CF-STATIC-OBJECT (car + (cl-bullet:collision-flags + (first + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'o2)))))) + (btr:simulate btr:*current-bullet-world* 1) + (let ((new-pose-o1 + (btr:pose (btr:object btr:*current-bullet-world* 'o1))) + (new-pose-o2 + (btr:pose (btr:object btr:*current-bullet-world* 'o2)))) + (lisp-unit:assert-true (pose-equal pose-o1 new-pose-o1)) + (lisp-unit:assert-true (pose-equal pose-o2 new-pose-o2)))) + ;; recreate begin state for next test case + (btr:remove-object btr:*current-bullet-world* 'o1) + (btr:remove-object btr:*current-bullet-world* 'o2)) + +(define-test create-static-collision-information-works-with-attached-static-objects + ;; Tests if the collision information is properly saved and if it + ;; has an effect on the object by simulating the bullet world + (spawn-robot) + (btr-utils:spawn-object 'o1 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (btr-utils:spawn-object 'o2 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (btr-utils:spawn-object 'o3 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (loop for body in (apply 'concatenate 'list + (list (btr:rigid-bodies (btr:object + btr:*current-bullet-world* + 'o1)) + (btr:rigid-bodies (btr:object + btr:*current-bullet-world* + 'o2)) + (btr:rigid-bodies (btr:object + btr:*current-bullet-world* + 'o3)))) + do + (setf + (btr::collision-flags body) + :CF-STATIC-OBJECT)) + (btr:attach-object (btr:object btr:*current-bullet-world* 'o1) + (btr:object btr:*current-bullet-world* 'o3)) + (let* ((pose-o1 (btr:pose (btr:object btr:*current-bullet-world* 'o1))) + (pose-o2 (btr:pose (btr:object btr:*current-bullet-world* 'o2)))) + + (lisp-unit:assert-equal + :CF-STATIC-OBJECT + (car + (btr::collision-information-flags + (car + (btr::create-static-collision-information + (btr:object btr:*current-bullet-world* 'o1)))))) + (lisp-unit:assert-equal :CF-STATIC-OBJECT (car + (cl-bullet:collision-flags + (first + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'o1)))))) + (lisp-unit:assert-equal + :CF-STATIC-OBJECT + (car + (btr::collision-information-flags + (car + (btr::create-static-collision-information + (btr:object btr:*current-bullet-world* 'o2)))))) + (lisp-unit:assert-equal :CF-STATIC-OBJECT (car + (cl-bullet:collision-flags + (first + (btr:rigid-bodies + (btr:object + btr:*current-bullet-world* + 'o2)))))) + (btr:simulate btr:*current-bullet-world* 1) + (let ((new-pose-o1 + (btr:pose (btr:object btr:*current-bullet-world* 'o1))) + (new-pose-o2 + (btr:pose (btr:object btr:*current-bullet-world* 'o2)))) + (lisp-unit:assert-true (pose-equal pose-o1 new-pose-o1)) + (lisp-unit:assert-true (pose-equal pose-o2 new-pose-o2)))) + ;; recreate begin state for next test case + (btr:remove-object btr:*current-bullet-world* 'o1) + (btr:remove-object btr:*current-bullet-world* 'o2) + (btr:remove-object btr:*current-bullet-world* 'o3)) + + +(define-test reset-collision-information-works-with-attached-objects + ;; Tests if the collision information is properly reseted and if it has + ;; an effect on the object by simulating the bullet world + (spawn-robot) + (btr-utils:spawn-object 'o1 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (btr-utils:spawn-object 'o2 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (let* ((pose-o1 (btr:pose (btr:object btr:*current-bullet-world* 'o1)))) (btr:attach-object 'o1 'o2) + ;;simulate detachment + (setf (slot-value (btr:object btr:*current-bullet-world* 'o1) 'attached-objects) + nil) (btr::reset-collision-information (btr:object btr:*current-bullet-world* 'o1) - (list (btr::make-collision-information :rigid-body-name 'o1 :flags NIL))) + (list (btr::make-collision-information + :rigid-body-name 'o1 :flags NIL))) (lisp-unit:assert-equal NIL (car (cl-bullet:collision-flags (first - (btr:rigid-bodies (btr:object btr:*current-bullet-world* 'o1)))))) + (btr:rigid-bodies + (btr:object btr:*current-bullet-world* 'o1)))))) (btr:simulate btr:*current-bullet-world* 1) - (let ((new-pose-o1 (btr:pose (btr:object btr:*current-bullet-world* 'o1)))) + (let ((new-pose-o1 + (btr:pose (btr:object btr:*current-bullet-world* 'o1)))) (lisp-unit:assert-false (pose-equal pose-o1 new-pose-o1)))) - + ;; recreate begin state for next test case (btr:remove-object btr:*current-bullet-world* 'o1) (btr:remove-object btr:*current-bullet-world* 'o2)) (define-test reset-collision-information-fails ;; Tests if nothing happens if nil is passed - (btr-utils:spawn-object 'o1 :mug :pose + (btr-utils:spawn-object 'o1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) - (lisp-unit:assert-false (btr::reset-collision-information (btr:object btr:*current-bullet-world* 'o1) nil)) + (lisp-unit:assert-false (btr::reset-collision-information + (btr:object btr:*current-bullet-world* 'o1) nil)) (btr:remove-object btr:*current-bullet-world* 'o1)) (define-test attach-object-called-with-item-symbols - ;; Tests if the attach-object function gets properly called if it was called with the object item names - (btr-utils:spawn-object 'oo1 :mug :pose + ;; Tests if the attach-object function gets properly called if it was + ;; called with the object item names + (spawn-robot) + (btr-utils:spawn-object 'oo1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) - (btr-utils:spawn-object 'oo2 :mug :pose - '((-1 0.0 0.92)(0 0 0 1))) - + (btr-utils:spawn-object 'oo2 :mug :pose + '((-1 0.0 0.92)(0 0 0 1))) + (btr:attach-object 'oo1 'oo2) - (lisp-unit:assert-equal 'oo1 (car (assoc 'oo1 (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo2))))) - (lisp-unit:assert-equal 'oo2 (car (assoc 'oo2 (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo1))))) - + (lisp-unit:assert-equal + 'oo1 + (car (assoc 'oo1 + (btr:attached-objects + (btr:object btr:*current-bullet-world* 'oo2))))) + (lisp-unit:assert-equal + 'oo2 + (car (assoc 'oo2 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'oo1))))) + (btr:remove-object btr:*current-bullet-world* 'oo1) (btr:remove-object btr:*current-bullet-world* 'oo2)) (define-test attach-object-called-with-more-items-connecting-to-one-item-in-one-call - ;; Attaches three objects and 'o1 is connected with both objects in one call - (btr-utils:spawn-object 'o1 :mug :pose + ;; Attaches three objects and 'o1 is connected with both objects in + ;; one call + (btr-utils:spawn-object 'o1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) - (btr-utils:spawn-object 'o2 :mug :pose + (btr-utils:spawn-object 'o2 :mug :pose '((-1 0.75 0.92)(0 0 0 1))) - (btr-utils:spawn-object 'o3 :mug :pose + (btr-utils:spawn-object 'o3 :mug :pose '((-1 0.75 0.92)(0 0 0 1))) ;;connect objects o2 <-> o1 <-> o3 (btr:attach-object (list 'o2 'o3) 'o1) - + ;;these are connected o2 <-> o1 <-> o3 - (lisp-unit:assert-equal 'o2 (car (assoc 'o2 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o1))))) - (lisp-unit:assert-equal 'o3 (car (assoc 'o3 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o1))))) - (lisp-unit:assert-equal 'o1 (car (assoc 'o1 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o2))))) - (lisp-unit:assert-equal 'o1 (car (assoc 'o1 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o3))))) + (lisp-unit:assert-equal + 'o2 + (car (assoc 'o2 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'o1))))) + (lisp-unit:assert-equal + 'o3 + (car (assoc 'o3 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'o1))))) + (lisp-unit:assert-equal + 'o1 + (car (assoc 'o1 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'o2))))) + (lisp-unit:assert-equal + 'o1 + (car (assoc 'o1 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'o3))))) ;;these are not connected to each other: o2 o3 - (lisp-unit:assert-false (equal 'o2 (car (assoc 'o2 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o3)))))) - (lisp-unit:assert-false (equal 'o3 (car (assoc 'o3 (btr:attached-objects (btr:object btr:*current-bullet-world* 'o2)))))) - - ;; recreate begin state for next test case + (lisp-unit:assert-false + (equal 'o2 (car (assoc 'o2 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'o3)))))) + (lisp-unit:assert-false + (equal 'o3 (car (assoc 'o3 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'o2)))))) + + ;; attach-object-more-objects-connected-bidirectional-to-one-object-in-one-call begin state for next test case (btr:remove-object btr:*current-bullet-world* 'o1) (btr:remove-object btr:*current-bullet-world* 'o2) (btr:remove-object btr:*current-bullet-world* 'o3)) (define-test attach-object-called-with-item-symbol-and-nil-as-parameter - ;; Tests if the attach-object function does nothing if called with nil and an valid item object - (btr-utils:spawn-object 'oo1 :mug :pose + ;; Tests if the attach-object function does nothing if called with + ;; nil and an valid item object + (btr-utils:spawn-object 'oo1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (lisp-unit:assert-false (btr:attach-object 'oo1 nil)) - (lisp-unit:assert-number-equal 0 (list-length (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo1)))) + (lisp-unit:assert-number-equal + 0 + (list-length (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo1)))) (lisp-unit:assert-false (btr:attach-object nil 'oo1)) - (lisp-unit:assert-number-equal 0 (list-length (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo1)))) + (lisp-unit:assert-number-equal + 0 + (list-length (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo1)))) (lisp-unit:assert-false (btr:attach-object nil nil)) - + (btr:remove-object btr:*current-bullet-world* 'oo1)) (define-test detach-object-called-with-item-symbols - ;; Tests if the detach-object function gets properly called if it was called with the object item names - (btr-utils:spawn-object 'oo1 :mug :pose + ;; Tests if the detach-object function gets properly called if it + ;; was called with the object item names + (btr-utils:spawn-object 'oo1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) - (btr-utils:spawn-object 'oo2 :mug :pose + (btr-utils:spawn-object 'oo2 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (btr:attach-object 'oo1 'oo2) - (lisp-unit:assert-equal 'oo1 (car (assoc 'oo1 (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo2))))) - (lisp-unit:assert-equal 'oo2 (car (assoc 'oo2 (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo1))))) + (lisp-unit:assert-equal + 'oo1 + (car (assoc 'oo1 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'oo2))))) + (lisp-unit:assert-equal + 'oo2 + (car (assoc 'oo2 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'oo1))))) (btr:detach-object 'oo1 'oo2) - (lisp-unit:assert-false (equal 'oo2 (car (assoc 'oo2 (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo1)))))) - (lisp-unit:assert-false (equal 'oo1 (car (assoc 'oo1 (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo2)))))) + (lisp-unit:assert-false + (equal 'oo2 (car (assoc 'oo2 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'oo1)))))) + (lisp-unit:assert-false + (equal 'oo1 (car (assoc 'oo1 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'oo2)))))) (btr:remove-object btr:*current-bullet-world* 'oo1) (btr:remove-object btr:*current-bullet-world* 'oo2)) (define-test detach-object-called-with-item-symbol-and-nil-as-parameter - ;; Tests if the detach-object function does nothing if called with nil and an valid item object - (btr-utils:spawn-object 'oo1 :mug :pose + ;; Tests if the detach-object function does nothing if called with + ;; nil and an valid item object + (btr-utils:spawn-object 'oo1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) - (btr-utils:spawn-object 'oo2 :mug :pose + (btr-utils:spawn-object 'oo2 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (btr:attach-object 'oo1 'oo2) - (lisp-unit:assert-equal 'oo1 (car (assoc 'oo1 (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo2))))) - (lisp-unit:assert-equal 'oo2 (car (assoc 'oo2 (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo1))))) + (lisp-unit:assert-equal + 'oo1 + (car (assoc 'oo1 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'oo2))))) + (lisp-unit:assert-equal + 'oo2 + (car (assoc 'oo2 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'oo1))))) (lisp-unit:assert-false (btr:detach-object nil 'oo1)) - (lisp-unit:assert-equal 'oo1 (car (assoc 'oo1 (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo2))))) - (lisp-unit:assert-equal 'oo2 (car (assoc 'oo2 (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo1))))) + (lisp-unit:assert-equal + 'oo1 + (car (assoc 'oo1 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'oo2))))) + (lisp-unit:assert-equal + 'oo2 + (car (assoc 'oo2 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'oo1))))) (lisp-unit:assert-false (btr:detach-object 'oo1 nil)) - (lisp-unit:assert-equal 'oo1 (car (assoc 'oo1 (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo2))))) - (lisp-unit:assert-equal 'oo2 (car (assoc 'oo2 (btr:attached-objects (btr:object btr:*current-bullet-world* 'oo1))))) + (lisp-unit:assert-equal + 'oo1 + (car (assoc 'oo1 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'oo2))))) + (lisp-unit:assert-equal + 'oo2 + (car (assoc 'oo2 (btr:attached-objects + (btr:object btr:*current-bullet-world* 'oo1))))) (lisp-unit:assert-false (btr:detach-object nil nil)) (btr:remove-object btr:*current-bullet-world* 'oo1) (btr:remove-object btr:*current-bullet-world* 'oo2)) - + diff --git a/cram_3d_world/cram_bullet_reasoning/tests/robot-model-tests.lisp b/cram_3d_world/cram_bullet_reasoning/tests/robot-model-tests.lisp index 50a5a5fb7e..3d45ff6e20 100644 --- a/cram_3d_world/cram_bullet_reasoning/tests/robot-model-tests.lisp +++ b/cram_3d_world/cram_bullet_reasoning/tests/robot-model-tests.lisp @@ -26,42 +26,50 @@ ;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE ;;; POSSIBILITY OF SUCH DAMAGE. + (in-package :btr-tests) (defun setup-world () (setf rob-int:*robot-urdf* - (cl-urdf:parse-urdf (roslisp:get-param "robot_description"))) + (cl-urdf:parse-urdf + (roslisp:get-param rob-int:*robot-description-parameter*))) (prolog:prolog `(and (btr:bullet-world ?world) (rob-int:robot ?robot) (assert (btr:object ?world :urdf ?robot ((0 0 0) (0 0 0 1)) :urdf ,rob-int:*robot-urdf*)))) - (clrhash btr::*updated-attachments*) + (clrhash (btr::get-updated-attachments)) (btr:detach-all-objects (btr:get-robot-object))) (define-test attach-object-unknown-link - ;; Tries to attach an item to an unkown link of the robot. This should fail. + ;; Tries to attach an item to an unkown link of the robot. This + ;; should fail. (setup-world) - (btr-utils:spawn-object 'o1 :mug :pose + (btr-utils:spawn-object 'o1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (lisp-unit:assert-error 'simple-error - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o1))) + (btr:attach-object (btr:get-robot-object) (btr:object + btr:*current-bullet-world* 'o1))) (lisp-unit:assert-error 'simple-error - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o1)) + (btr:attach-object (btr:get-robot-object) (btr:object + btr:*current-bullet-world* 'o1)) :link "asdasdasd1") (btr:remove-object btr:*current-bullet-world* 'o1)) (define-test attach-object-same-object-to-two-links - ;; Attaches one object to two links of the robot and checks if it is saved properly - ;; in the list under the name of the item attached. The collision information is therefore - ;; shared between the attachments. + ;; Attaches one object to two links of the robot and checks if it is + ;; saved properly in the list under the name of the item + ;; attached. The collision information is therefore shared between + ;; the attachments. (setup-world) - (btr-utils:spawn-object 'o1 :mug :pose + (btr-utils:spawn-object 'o1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (let ((link1 "base_link") (link2 "base_footprint")) - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o1) :link link1) - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o1) :link link2) + (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* + 'o1) :link link1) + (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* + 'o1) :link link2) ;;'((o1 ;; (list of attachments) <- link1, link2 ;; collision-info of o1)) @@ -76,17 +84,19 @@ (btr:remove-object btr:*current-bullet-world* 'o1))) (define-test attach-object-different-objects-to-two-links - ;; Attaches two object to two links of the robot and checks if it is saved properly - ;; in the list under the name of the item attached. + ;; Attaches two object to two links of the robot and checks if it is + ;; saved properly in the list under the name of the item attached. (setup-world) - (btr-utils:spawn-object 'o1 :mug :pose + (btr-utils:spawn-object 'o1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) - (btr-utils:spawn-object 'o2 :mug :pose + (btr-utils:spawn-object 'o2 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (let ((link1 "base_link") (link2 "base_footprint")) - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o1) :link link1) - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o2) :link link2) + (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* + 'o1) :link link1) + (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* + 'o2) :link link2) ;;'((o1 ;; (list of attachments) <- link1 ;; collision-info of o1) @@ -105,16 +115,18 @@ (btr:remove-object btr:*current-bullet-world* 'o2))) (define-test attach-object-different-objects-to-same-link - ;; Attaches two objects to one link of the robot and checks if it is saved properly - ;; in the list under the name of the item attached. + ;; Attaches two objects to one link of the robot and checks if it is + ;; saved properly in the list under the name of the item attached. (setup-world) - (btr-utils:spawn-object 'o1 :mug :pose + (btr-utils:spawn-object 'o1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) - (btr-utils:spawn-object 'o2 :mug :pose + (btr-utils:spawn-object 'o2 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (let ((link "base_link")) - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o1) :link link) - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o2) :link link) + (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* + 'o1) :link link) + (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* + 'o2) :link link) ;;'((o1 ;; (list of attachments) <- link ;; collision-info of o1) @@ -123,37 +135,42 @@ ;; collision-info of o2)) (lisp-unit:assert-true (find link (car (cdr - (assoc 'o1 (btr:attached-objects (btr:get-robot-object))))) + (assoc 'o1 (btr:attached-objects (btr:get-robot-object))))) :key #'btr::attachment-link :test #'equal)) (lisp-unit:assert-true (find link (car (cdr - (assoc 'o2 (btr:attached-objects (btr:get-robot-object))))) + (assoc 'o2 (btr:attached-objects (btr:get-robot-object))))) :key #'btr::attachment-link :test #'equal)) (btr:remove-object btr:*current-bullet-world* 'o1) (btr:remove-object btr:*current-bullet-world* 'o2))) (define-test detach-object-completly-same-object-to-two-links - ;; Detaches object which was attached to two links of the robot and checks if it is removed properly - ;; in the list under the name of the item attached. Moreover, it should not touch other object attachments. + ;; Detaches object which was attached to two links of the robot and + ;; checks if it is removed properly in the list under the name of + ;; the item attached. Moreover, it should not touch other object attachments. (setup-world) - (btr-utils:spawn-object 'o1 :mug :pose + (btr-utils:spawn-object 'o1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) - (btr-utils:spawn-object 'o2 :mug :pose + (btr-utils:spawn-object 'o2 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (let ((link1 "base_link") (link2 "base_footprint")) - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o1) :link link1) - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o1) :link link2) - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o2) :link link1) + (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* + 'o1) :link link1) + (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* + 'o1) :link link2) + (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* + 'o2) :link link1) ;;'((o1 - ;; (list of attachments) <- link1 (x), link2 (x) + ;; (list of attachments) <- link1 (x), link2 (x) ;; collision-info of o1) ;; (o2 ;; (list of attachments) <- link1 ;; collision-info of o2)) ;; ;; marked (x) should be removed - (btr:detach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o1)) + (btr:detach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* + 'o1)) (lisp-unit:assert-false (assoc 'o1 (btr:attached-objects (btr:get-robot-object)))) (lisp-unit:assert-true @@ -164,27 +181,32 @@ (btr:remove-object btr:*current-bullet-world* 'o2))) (define-test detach-object-partially-same-object-to-two-links - ;; Detaches object which was attached to two links partially of the robot and checks if it is removed properly - ;; in the list under the name of the item attached. Moreover, it should not touch other object attachments. + ;; Detaches object which was attached to two links partially of the robot + ;; and checks if it is removed properly in the list under the name + ;; of the item attached. Moreover, it should not touch other object attachments. (setup-world) - (btr-utils:spawn-object 'o1 :mug :pose + (btr-utils:spawn-object 'o1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) - (btr-utils:spawn-object 'o2 :mug :pose + (btr-utils:spawn-object 'o2 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (let ((link1 "base_link") (link2 "base_footprint")) - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o1) :link link1) - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o1) :link link2) - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o2) :link link1) + (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* + 'o1) :link link1) + (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* + 'o1) :link link2) + (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* + 'o2) :link link1) ;;'((o1 - ;; (list of attachments) <- link1 (x), link2 + ;; (list of attachments) <- link1 (x), link2 ;; collision-info of o1) ;; (o2 ;; (list of attachments) <- link1 ;; collision-info of o2)) ;; ;; marked (x) should be removed - (btr:detach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o1) :link link1) + (btr:detach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* + 'o1) :link link1) (lisp-unit:assert-false (find link1 (car (cdr (assoc 'o1 (btr:attached-objects (btr:get-robot-object))))) @@ -201,33 +223,38 @@ (btr:remove-object btr:*current-bullet-world* 'o2))) (define-test updated-link-in-attachment-with-attachment-attached-to-one-link - ;; Tests if the function updated-link-in-attachment work as the doc of it explains + ;; Tests if the function updated-link-in-attachment work as the doc of + ;; it explains (setup-world) - (btr-utils:spawn-object 'o1 :mug :pose + (btr-utils:spawn-object 'o1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (let ((link "base_link")) - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o1) :link link) + (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* + 'o1) :link link) ;;'((o1 - ;; (list of attachments) <- link1, link2 + ;; (list of attachments) <- link1, link2 ;; collision-info of o1)) (lisp-unit:assert-false (btr::updated-link-in-attachment (gethash link (cl-urdf:links (btr:urdf (btr:get-robot-object)))) (first (btr::attached-objects (btr:get-robot-object))))) - (lisp-unit:assert-number-equal 0 (length (gethash 'o1 btr::*updated-attachments*))) - (lisp-unit:assert-false (gethash 'o1 btr::*updated-attachments*)) - + (lisp-unit:assert-number-equal 0 (length (gethash 'o1 (btr::get-updated-attachments)))) + (lisp-unit:assert-false (gethash 'o1 (btr::get-updated-attachments))) + (btr:remove-object btr:*current-bullet-world* 'o1))) (define-test updated-link-in-attachment-with-attachment-attached-to-two-links - ;; Tests if the function updated-link-in-attachment work as the doc of it explains + ;; Tests if the function updated-link-in-attachment work as the doc of + ;; it explains (setup-world) - (btr-utils:spawn-object 'o1 :mug :pose + (btr-utils:spawn-object 'o1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (let ((link1 "base_link") (link2 "base_footprint")) - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o1) :link link1) - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o1) :link link2) + (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* + 'o1) :link link1) + (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* + 'o1) :link link2) ;;'((o1 ;; (list of attachments) <- link1, link2 ;; collision-info of o1)) @@ -235,26 +262,29 @@ (btr::updated-link-in-attachment (gethash link1 (cl-urdf:links (btr:urdf (btr:get-robot-object)))) (first (btr::attached-objects (btr:get-robot-object))))) - (lisp-unit:assert-number-equal 1 (length (gethash 'o1 btr::*updated-attachments*))) - (lisp-unit:assert-equal link1 (first (gethash 'o1 btr::*updated-attachments*))) - + (lisp-unit:assert-number-equal 1 (length (gethash 'o1 (btr::get-updated-attachments)))) + (lisp-unit:assert-equal link1 (first (gethash 'o1 (btr::get-updated-attachments)))) + (lisp-unit:assert-true (btr::updated-link-in-attachment (gethash link2 (cl-urdf:links (btr:urdf (btr:get-robot-object)))) (first (btr::attached-objects (btr:get-robot-object))))) - (lisp-unit:assert-false (gethash 'o1 btr::*updated-attachments*)) - + (lisp-unit:assert-false (gethash 'o1 (btr::get-updated-attachments))) + (btr:remove-object btr:*current-bullet-world* 'o1))) (define-test updated-link-in-attachment-negative - ;; Tests if the function updated-link-in-attachment work if it gets invalid input + ;; Tests if the function updated-link-in-attachment work if it gets + ;; invalid input (setup-world) - (btr-utils:spawn-object 'o1 :mug :pose + (btr-utils:spawn-object 'o1 :mug :pose '((-1 0.0 0.92)(0 0 0 1))) (let ((link1 "base_link") (link2 "base_footprint")) - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o1) :link link1) - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o1) :link link2) + (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* + 'o1) :link link1) + (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* + 'o1) :link link2) ;;'((o1 ;; (list of attachments) <- link1, link2 ;; collision-info of o1)) @@ -262,61 +292,72 @@ (btr::updated-link-in-attachment (gethash "asdasdasd" (cl-urdf:links (btr:urdf (btr:get-robot-object)))) (first (btr::attached-objects (btr:get-robot-object))))) - (lisp-unit:assert-false (gethash 'o1 btr::*updated-attachments*)) - + (lisp-unit:assert-false (gethash 'o1 (btr::get-updated-attachments))) + (btr:remove-object btr:*current-bullet-world* 'o1))) (define-test setf-pose-robot-object-with-one-attached-object-to-one-link - ;; Tests if the attached object gets properly positioned if it is attached to two links - ;; and the robot moves and rotates + ;; Tests if the attached object gets properly positioned if it is + ;; attached to two links and the robot moves and rotates (setup-world) (setf (pose (btr:get-robot-object)) (cl-transforms:make-pose - (cl-tf:make-3d-vector 0 0 0) - (cl-transforms:make-quaternion 0 0 0 1))) - (btr-utils:spawn-object 'o1 :mug :pose + (cl-transforms:make-3d-vector 0 0 0) + (cl-transforms:make-quaternion + 0 0 0 1))) + (btr-utils:spawn-object 'o1 :mug :pose '((0.2 0.0 0.9)(0 0 0 1))) (let ((link "base_link")) - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o1) :link link) + (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* + 'o1) :link link) ;;'((o1 - ;; (list of attachments) <- link1, link2 + ;; (list of attachments) <- link1, link2 ;; collision-info of o1)) (setf (pose (btr:get-robot-object)) (cl-transforms:make-pose - (cl-tf:make-3d-vector 0.2 0 0) - (cl-transforms:make-quaternion 0 0 1 1))) + (cl-transforms:make-3d-vector 0.2 0 0) + (cl-transforms:make-quaternion + 0 0 1 1))) (lisp-unit:assert-equal (list 0.2d0 0.2d0 0.9d0) - (vector->list (cl-transforms:origin (pose (object *current-bullet-world* 'o1))))) + (vector->list (cl-transforms:origin (pose (object *current-bullet-world* + 'o1))))) (lisp-unit:assert-equal (list 0.7071067690849304d0 0.0d0 0.0d0 0.7071067690849304d0) - (orientation->list (cl-transforms:orientation (pose (object *current-bullet-world* 'o1))))) - + (orientation->list (cl-transforms:orientation (pose (object *current-bullet-world* + 'o1))))) + (btr:remove-object btr:*current-bullet-world* 'o1))) (define-test setf-pose-robot-object-with-one-attached-object-to-two-different-links - ;; Tests if the attached object gets properly positioned if it is attached to two links - ;; and the robot moves and rotates + ;; Tests if the attached object gets properly positioned if it is + ;; attached to two links and the robot moves and rotates (setup-world) (setf (pose (btr:get-robot-object)) (cl-transforms:make-pose - (cl-tf:make-3d-vector 0 0 0) - (cl-transforms:make-quaternion 0 0 0 1))) - (btr-utils:spawn-object 'o1 :mug :pose + (cl-transforms:make-3d-vector 0 0 0) + (cl-transforms:make-quaternion + 0 0 0 1))) + (btr-utils:spawn-object 'o1 :mug :pose '((0.2 0.0 0.9)(0 0 0 1))) (let ((link1 "base_link") (link2 "base_footprint")) - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o1) :link link1) - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o1) :link link2) + (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* + 'o1) :link link1) + (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* + 'o1) :link link2) ;;'((o1 - ;; (list of attachments) <- link1, link2 + ;; (list of attachments) <- link1, link2 ;; collision-info of o1)) (setf (pose (btr:get-robot-object)) (cl-transforms:make-pose - (cl-tf:make-3d-vector 0.2 0 0) - (cl-transforms:make-quaternion 0 0 1 1))) + (cl-transforms:make-3d-vector 0.2 0 0) + (cl-transforms:make-quaternion + 0 0 1 1))) (lisp-unit:assert-equal (list 0.2d0 0.2d0 0.9d0) - (vector->list (cl-transforms:origin (pose (object *current-bullet-world* 'o1))))) + (vector->list (cl-transforms:origin (pose (object *current-bullet-world* + 'o1))))) (lisp-unit:assert-equal (list 0.7071067690849304d0 0.0d0 0.0d0 0.7071067690849304d0) - (orientation->list (cl-transforms:orientation (pose (object *current-bullet-world* 'o1))))) - + (orientation->list (cl-transforms:orientation (pose (object *current-bullet-world* + 'o1))))) + (btr:remove-object btr:*current-bullet-world* 'o1))) diff --git a/cram_3d_world/cram_bullet_reasoning/tests/robot-model-utils-tests.lisp b/cram_3d_world/cram_bullet_reasoning/tests/robot-model-utils-tests.lisp index e209b337e0..318168192b 100644 --- a/cram_3d_world/cram_bullet_reasoning/tests/robot-model-utils-tests.lisp +++ b/cram_3d_world/cram_bullet_reasoning/tests/robot-model-utils-tests.lisp @@ -30,37 +30,124 @@ (in-package :btr-tests) (defun clean-environment (from) - (mapcar (lambda (name) (btr:remove-object btr:*current-bullet-world* name)) from)) + (mapcar (lambda (name) + (btr:remove-object btr:*current-bullet-world* name)) + from)) (defun spawn-objects-with-same-pose (names) - (mapcar (lambda (name) (btr-utils:spawn-object name :mug :pose '((0 0 0) (0 0 0 1)))) names)) - + (mapcar (lambda (name) + (btr-utils:spawn-object name :mug :pose '((0 0 2.0) (0 0 0 1)))) + names)) + (define-test robot-attached-objects-in-collision-negative - ;; Tests if the function returns nil since not one object is attached to - ;; a robot link. + ;; Tests if the function returns nil since not one object is attached + ;; to a robot link. (setup-world) (spawn-objects-with-same-pose '(o oo)) (assert-false (btr:robot-attached-objects-in-collision)) ;; -> no collision (clean-environment '(o oo))) (define-test robot-attached-objects-in-collision-positive - ;; Tests if the function registers a collision since one of the objects is - ;; attached to the robot and the other is in collision to the attached object. + ;; Tests if the function registers a collision since one of the objects + ;; is attached to the robot and the other is in collision to the + ;; attached object. (setup-world) (spawn-objects-with-same-pose '(o oo)) - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o) :link "base_footprint") + (btr:attach-object (btr:get-robot-object) + (btr:object btr:*current-bullet-world* 'o) + :link "base_footprint") (assert-true (btr:robot-attached-objects-in-collision)) ;; -> collision (clean-environment '(o oo))) (define-test robot-attached-objects-in-collision-negative-because-of-attachment - ;; Since the robot can attach things made of items attached to each other, there should not be - ;; a collision if the robot attaches one of these things. Even if the items in the "thing" are - ;; in collision to each other. + ;; Since the robot can attach things made of items attached to each other, + ;; there should not be a collision if the robot attaches one of + ;; these things. Even if the items in the "thing" are in collision + ;; to each other. (setup-world) (spawn-objects-with-same-pose '(o oo)) - ;; "thing" 'o: 'oo is attached to 'o with the same pose, therefore they are in collision. + ;; "thing" 'o: 'oo is attached to 'o with the same pose, therefore + ;; they are in collision. (btr:attach-object 'o 'oo) ;; attach "thing" 'o to a robot link - (btr:attach-object (btr:get-robot-object) (btr:object btr:*current-bullet-world* 'o) :link "base_footprint") + (btr:attach-object (btr:get-robot-object) + (btr:object btr:*current-bullet-world* 'o) + :link "base_footprint") (assert-false (btr:robot-attached-objects-in-collision)) ;; -> no collision (clean-environment '(o oo))) + +(define-test robot-attached-objects-in-collision-positive-colliding-with-floor + (setup-world) + (btr-utils:kill-all-objects) + (btr:detach-all-objects (btr:get-robot-object)) + (btr:detach-all-objects (btr:get-environment-object)) + ;; spawn plate intersecting the floor + (btr-utils:spawn-object :plate-1 :plate :pose '((0.9 0 0.0) (0.7 0 0 0.7)) :mass 1.0) + ;; attach plate to the robot + (btr:attach-object (btr:get-robot-object) + (btr:object btr:*current-bullet-world* :plate-1) + :link "r_wrist_roll_link" :loose nil :grasp :front) + ;; check for collisions + (assert-equal '(:FLOOR) (mapcar #'btr:name (btr::robot-attached-objects-in-collision))) + (clean-environment '(:plate-1))) + +(define-test robot-attached-objects-in-collision-positive-environment-collisions + (setup-world) + (spawn-robot) + (spawn-environment) + (btr-utils:kill-all-objects) + (btr:detach-all-objects (btr:get-robot-object)) + (btr:detach-all-objects (btr:get-environment-object)) + ;; spawn basket which is in collision with the environment + (btr:add-object btr:*current-bullet-world* :basket + :basket-1 + '((1.2 0 0.8) (0.0 0 0 1.0)) + :length 0.2 :width 0.2 :height 0.2) + ;; attach basket to robot + (btr:attach-object (btr:get-robot-object) + (btr:object btr:*current-bullet-world* :basket-1) + :link "r_wrist_roll_link" :loose nil :grasp :front) + ;; check for collision + (assert-equal (list (rob-int:get-environment-name)) + (mapcar #'btr:name (btr::robot-attached-objects-in-collision))) + ;; spawn plate on sink area surface ... + (btr-utils:spawn-object :plate-1 :plate :pose '((1.5 0.5 0.9) (0.0 0 0 1.0))) + ;; ... and attach it to the environment + (btr:attach-object (btr:get-environment-object) + (btr:object btr:*current-bullet-world* + :plate-1) + :link "sink_area_surface") + ;; and check for collisions again + (assert-equal (list (rob-int:get-environment-name)) + (mapcar #'btr:name (btr::robot-attached-objects-in-collision))) + (clean-environment '(:basket-1 :plate-1))) + +(define-test robot-attached-objects-in-collision-negative-environment-collisions + (setup-world) + (spawn-robot) + (spawn-environment) + (btr-utils:kill-all-objects) + (btr:detach-all-objects (btr:get-robot-object)) + (btr:detach-all-objects (btr:get-environment-object)) + ;; spawn basket which is in collision with the environment + (btr:add-object btr:*current-bullet-world* :basket + :basket-1 + '((1.2 0 0.8) (0.0 0 0 1.0)) + :length 0.2 :width 0.2 :height 0.2) + ;; attach basket to robot + (btr:attach-object (btr:get-robot-object) + (btr:object btr:*current-bullet-world* :basket-1) + :link "r_wrist_roll_link" :loose nil :grasp :front) + ;; spawn plate on sink area surface ... + (btr-utils:spawn-object :plate-1 :plate :pose '((1.5 0.5 0.9) (0.0 0 0 1.0))) + ;; ... and attach it to the environment + (btr:attach-object (btr:get-environment-object) + (btr:object btr:*current-bullet-world* :plate-1) + :link "sink_area_surface") + ;; attach basket to the environment + (btr:attach-object (btr:get-environment-object) + (btr:object btr:*current-bullet-world* :basket-1) + :link "sink_area_surface") + ;; check collisions again + (assert-false (mapcar #'btr:name (btr::robot-attached-objects-in-collision))) + (clean-environment '(:basket-1 :plate-1))) diff --git a/cram_3d_world/cram_bullet_reasoning_belief_state/cram-bullet-reasoning-belief-state.asd b/cram_3d_world/cram_bullet_reasoning_belief_state/cram-bullet-reasoning-belief-state.asd index 11e7b58d55..25d63d5a26 100644 --- a/cram_3d_world/cram_bullet_reasoning_belief_state/cram-bullet-reasoning-belief-state.asd +++ b/cram_3d_world/cram_bullet_reasoning_belief_state/cram-bullet-reasoning-belief-state.asd @@ -30,27 +30,32 @@ :author "Lorenz Moesenlechner" :license "BSD" - :depends-on (cram-prolog + :depends-on (roslisp + roslisp-utilities ; for ros-init-function-s for time + + cl-transforms + cl-transforms-stamped + cl-tf ; for tf broadcaster and for setting transforms from bullet to tf + + cram-prolog cram-utilities cram-projection cram-designators cram-process-modules ; for world-state-detecting motion + cram-occasions-events + cram-language ; for DEFINE-TASK-VARIABLE in utitlities + + cram-tf cram-common-designators ; for world-state-detecting motion cram-common-failures ; for world-state-detecting motion - cram-bullet-reasoning - cram-occasions-events cram-plan-occasions-events - cram-language ; for DEFINE-TASK-VARIABLE in utitlities - cram-physics-utils ; for object designator mesh stuff - ;; ros-init-function-s for time - roslisp-utilities - roslisp cram-robot-interfaces - cram-tf - cl-tf ; for tf broadcaster and for setting transforms from bullet to tf - cl-transforms-stamped - cl-transforms + cram-manipulation-interfaces + + cram-physics-utils ; for object designator mesh stuff cl-bullet + cram-bullet-reasoning + tf2_msgs-msg geometry_msgs-msg shape_msgs-msg) @@ -65,5 +70,7 @@ (:file "environment-joint-publisher" :depends-on ("package")) (:file "object-perceptions" :depends-on ("package")) (:file "occasions" :depends-on ("package" "object-perceptions")) - (:file "event-handlers" :depends-on ("package" "object-perceptions")) - (:file "process-modules" :depends-on ("package")))))) + (:file "world-state-detecting" :depends-on ("package")) + (:file "event-handlers" :depends-on ("package" + "object-perceptions" + "world-state-detecting")))))) diff --git a/cram_3d_world/cram_bullet_reasoning_belief_state/package.xml b/cram_3d_world/cram_bullet_reasoning_belief_state/package.xml index e4af15f9fe..e7c20e867c 100644 --- a/cram_3d_world/cram_bullet_reasoning_belief_state/package.xml +++ b/cram_3d_world/cram_bullet_reasoning_belief_state/package.xml @@ -15,30 +15,35 @@ catkin + roslisp + roslisp_utilities + + cl_transforms + cl_transforms_stamped + cl_tf + cram_prolog cram_utilities cram_projection cram_designators cram_process_modules + cram_occasions_events + cram_language + + cram_tf cram_common_designators cram_common_failures - cram_bullet_reasoning - cram_occasions_events cram_plan_occasions_events - cram_language - cram_physics_utils - roslisp_utilities - roslisp cram_robot_interfaces - cram_tf - cl_tf - cl_transforms_stamped - cl_transforms + cram_manipulation_interfaces + + cram_physics_utils cl_bullet + cram_bullet_reasoning + tf2_msgs geometry_msgs shape_msgs - diff --git a/cram_3d_world/cram_bullet_reasoning_belief_state/src/belief-state.lisp b/cram_3d_world/cram_bullet_reasoning_belief_state/src/belief-state.lisp index 531fd13a40..b2b30055b9 100644 --- a/cram_3d_world/cram_bullet_reasoning_belief_state/src/belief-state.lisp +++ b/cram_3d_world/cram_bullet_reasoning_belief_state/src/belief-state.lisp @@ -1,19 +1,19 @@ ;;; Copyright (c) 2012, Lorenz Moesenlechner ;;; All rights reserved. -;;; +;;; ;;; Redistribution and use in source and binary forms, with or without ;;; modification, are permitted provided that the following conditions are met: -;;; +;;; ;;; * Redistributions of source code must retain the above copyright ;;; notice, this list of conditions and the following disclaimer. ;;; * Redistributions in binary form must reproduce the above copyright ;;; notice, this list of conditions and the following disclaimer in the ;;; documentation and/or other materials provided with the distribution. ;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software ;;; without specific prior written permission. -;;; +;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" ;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE ;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE @@ -28,90 +28,108 @@ (in-package :cram-bullet-reasoning-belief-state) -(defvar *kitchen-urdf* nil) -(defparameter *robot-parameter* "robot_description") -(defparameter *kitchen-parameter* "kitchen_description") (defparameter *spawn-debug-window* t "If the debug window should be spawned when belief state is set up.") -(defun replace-all (string part replacement &key (test #'char=)) - "Returns a new string in which all the occurences of the part -is replaced with replacement. - Taken from Common Lisp Cookbook." - (with-output-to-string (out) - (loop with part-length = (length part) - for old-pos = 0 then (+ pos part-length) - for pos = (search part string - :start2 old-pos - :test test) - do (write-string string out - :start old-pos - :end (or pos (length string))) - when pos do (write-string replacement out) - while pos))) - (defun average (min max) (+ min (/ (- max min) 2))) (defun setup-world-database () - (let ((robot (or rob-int:*robot-urdf* - (setf rob-int:*robot-urdf* - (cl-urdf:parse-urdf - (replace-all (roslisp:get-param *robot-parameter*) "\\" " "))))) - ;; TODO get rid of replace-all and instead fix the URDF of our real PR2 - (kitchen (or *kitchen-urdf* - (let ((kitchen-urdf-string - (roslisp:get-param *kitchen-parameter* nil))) - (when kitchen-urdf-string - (setf *kitchen-urdf* (cl-urdf:parse-urdf - kitchen-urdf-string))))))) + ;; make a clean world instance + (setf btr:*current-bullet-world* (make-instance 'btr:bt-reasoning-world)) - ;; set robot's URDF root link to *robot-base-frame* as that's how going actions works - (setf (slot-value rob-int:*robot-urdf* 'cl-urdf:root-link) - (or (gethash cram-tf:*robot-base-frame* - (cl-urdf:links rob-int:*robot-urdf*)) - (error "[setup-bullet-world] cram-tf:*robot-base-frame* was undefined or smt."))) + ;; get the environment URDF from the ROS parameter server + (let ((kitchen-urdf-string + (roslisp:get-param rob-int:*environment-description-parameter* nil))) + (when kitchen-urdf-string + (setf rob-int:*environment-urdf* (cl-urdf:parse-urdf kitchen-urdf-string)))) - (assert - (cut:force-ll - (prolog `(and - (btr:bullet-world ?w) - ,@(when *spawn-debug-window* - '((btr:debug-window ?w))) - (btr:assert ?w (btr:object :static-plane :floor ((0 0 0) (0 0 0 1)) - :normal (0 0 1) :constant 0 - :collision-mask (:default-filter))) - (btr:assert ?w (btr:object :urdf :kitchen ((0 0 0) (0 0 0 1)) - :collision-group :static-filter - :collision-mask (:default-filter - :character-filter) - ,@(when kitchen - `(:urdf ,kitchen)) - :compound T)) - (-> (rob-int:robot ?robot) - (and (btr:assert ?w (btr:object :urdf ?robot ((0 0 0) (0 0 0 1)) - ;; :color (0.9 0.9 0.9 1.0) - :urdf ,robot)) - (rob-int:robot-joint-states ?robot :arm :left :park ?left-joint-states) - (assert (btr:joint-state ?world ?robot ?left-joint-states)) - (rob-int:robot-joint-states ?robot :arm :right :park ?right-joint-states) - (assert (btr:joint-state ?world ?robot ?right-joint-states)) - (rob-int:robot-torso-link-joint ?robot ?_ ?torso-joint) - (rob-int:joint-lower-limit ?robot ?torso-joint ?lower-limit) - (rob-int:joint-upper-limit ?robot ?torso-joint ?upper-limit) - (lisp-fun average ?lower-limit ?upper-limit ?average-joint-value) - (assert (btr:joint-state ?world ?robot - ((?torso-joint ?average-joint-value))))) - (warn "ROBOT was not defined. Have you loaded a robot package?")))))))) + ;; get the robot URDF from the ROS parameter server + ;; TODO get rid of replace-all and instead fix the URDF of our real PR2 + (setf rob-int:*robot-urdf* + (cl-urdf:parse-urdf + (cut:replace-all + (roslisp:get-param rob-int:*robot-description-parameter*) + "\\" " "))) + ;; set robot's URDF root link to *robot-base-frame*, not odom + ;; because that's required for going actions + ;; otherwise lots of problems concerning object-pose in bullet happen + (setf (slot-value rob-int:*robot-urdf* 'cl-urdf:root-link) + (or (gethash cram-tf:*robot-base-frame* + (cl-urdf:links rob-int:*robot-urdf*)) + (error "[setup-bullet-world] cram-tf:*robot-base-frame* ~ + was undefined or smt."))) -(defmethod cram-occasions-events:clear-belief cram-bullet-reasoning-belief-state () - (setf btr:*current-bullet-world* (make-instance 'btr:bt-reasoning-world)) - (setup-world-database) + ;; if root link doesn't have a collision geometry, create a 1 mm box + (unless (cl-urdf:collision (cl-urdf:root-link rob-int:*robot-urdf*)) + (with-slots (cl-urdf:collision) + (cl-urdf:root-link rob-int:*robot-urdf*) + (setf cl-urdf:collision + (let* ((origin-transform + (cl-transforms:make-transform + (cl-transforms:make-3d-vector 0 0 0.001) + (cl-transforms:make-identity-rotation))) + (box-geometry + (make-instance + 'cl-urdf:box + :size (cl-transforms:make-3d-vector 0.001 0.001 0.001))) + (collision + (make-instance + 'cl-urdf:collision + :geometry box-geometry + :origin origin-transform))) + collision)))) + + ;; spawn the floor, the robot and the environment + (assert + (cut:force-ll + (prolog `(and + (btr:bullet-world ?w) + ,@(when *spawn-debug-window* + '((btr:debug-window ?w))) + (btr:assert ?w (btr:object :static-plane :floor ((0 0 0) (0 0 0 1)) + :normal (0 0 1) :constant 0 + :collision-mask (:default-filter))) + (-> (rob-int:environment-name ?environment-name) + (btr:assert ?w (btr:object :urdf ?environment-name + ((0 0 0) (0 0 0 1)) + :collision-group :static-filter + :collision-mask (:default-filter + :character-filter) + ,@(when rob-int:*environment-urdf* + `(:urdf ,rob-int:*environment-urdf*)) + :compound T)) + (warn "ROB-INT:ENVIRONMENT-NAME was not defined. ~ + Have you loaded an environment knowledge package?")) + (-> (rob-int:robot ?robot) + (and (btr:assert ?w (btr:object :urdf ?robot ((0 0 0) (0 0 0 1)) + ;; :color (0.9 0.9 0.9 1.0) + :urdf ,rob-int:*robot-urdf*)) + (-> (rob-int:robot-joint-states ?robot :arm :left :park ?left-joint-states) + (assert (btr:joint-state ?world ?robot ?left-joint-states)) + (true)) + (-> (rob-int:robot-joint-states ?robot :arm :right :park ?right-joint-states) + (assert (btr:joint-state ?world ?robot ?right-joint-states)) + (true)) + (rob-int:robot-torso-link-joint ?robot ?_ ?torso-joint) + (rob-int:joint-lower-limit ?robot ?torso-joint ?lower-limit) + (rob-int:joint-upper-limit ?robot ?torso-joint ?upper-limit) + (lisp-fun average ?lower-limit ?upper-limit ?average-joint-value) + (assert (btr:joint-state ?world ?robot + ((?torso-joint ?average-joint-value))))) + (warn "ROB-INT:ROBOT was not defined. ~ + Have you loaded a robot package?")))))) + + ;; update robot from TF in case we have a real robot (let ((robot-object (btr:get-robot-object))) (if robot-object (btr:set-robot-state-from-tf cram-tf:*transformer* robot-object) (warn "ROBOT was not defined. Have you loaded a robot package?")))) +(defmethod cram-occasions-events:clear-belief cram-bullet-reasoning-belief-state () + (setup-world-database)) + + (defun vary-kitchen-urdf (&optional (new-joint-states ;; '(("sink_area_footprint_joint" @@ -134,7 +152,7 @@ is replaced with replacement. ((-2.30d0 0.5d0 0.0d0) (0 0 0.5 0.5))) ("table_area_main_joint" ((1.6d0 -1.0d0 0.0d0) (0 0 0.5 0.5)))))) - (let ((kitchen-urdf-joints (cl-urdf:joints *kitchen-urdf*))) + (let ((kitchen-urdf-joints (cl-urdf:joints rob-int:*environment-urdf*))) (mapc (lambda (joint-name-poses-list-pair) (destructuring-bind (joint-name poses-list) joint-name-poses-list-pair diff --git a/cram_3d_world/cram_bullet_reasoning_belief_state/src/broadcaster.lisp b/cram_3d_world/cram_bullet_reasoning_belief_state/src/broadcaster.lisp index b63ab3f6c8..ad82beaf16 100644 --- a/cram_3d_world/cram_bullet_reasoning_belief_state/src/broadcaster.lisp +++ b/cram_3d_world/cram_bullet_reasoning_belief_state/src/broadcaster.lisp @@ -31,11 +31,10 @@ (defun get-bullet-object-transforms () (let ((item-name-pose-list - (cut:force-ll - (cut:lazy-mapcar - (lambda (bindings) - (list (cut:var-value '?item-name bindings) - (cut:var-value '?item-pose bindings))) + (mapcar (lambda (bindings) + (list (cut:var-value '?item-name bindings) + (cut:var-value '?item-pose bindings))) + (cut:force-ll (prolog:prolog `(and (btr:bullet-world ?world) (btr:item-type ?world ?item-name ?item-type) (btr:%object ?world ?item-name ?item-instance) @@ -44,7 +43,8 @@ (loop for item-name-pose in item-name-pose-list collect (cram-tf:pose->transform-stamped cram-tf:*fixed-frame* - (roslisp-utilities:rosify-underscores-lisp-name (first item-name-pose)) + (roslisp-utilities:rosify-underscores-lisp-name + (first item-name-pose)) time (second item-name-pose))))) diff --git a/cram_3d_world/cram_bullet_reasoning_belief_state/src/event-handlers.lisp b/cram_3d_world/cram_bullet_reasoning_belief_state/src/event-handlers.lisp index edd79a5e2b..08389bcca7 100644 --- a/cram_3d_world/cram_bullet_reasoning_belief_state/src/event-handlers.lisp +++ b/cram_3d_world/cram_bullet_reasoning_belief_state/src/event-handlers.lisp @@ -30,63 +30,203 @@ (in-package :cram-bullet-reasoning-belief-state) +(defun update-object-designator-location (object-designator location-designator) + (desig:make-designator + :object + `((:location ,location-designator) + ,@(remove :location (desig:properties object-designator) :key #'car)) + object-designator)) + +(defun remove-object-designator-location (object-designator) + (desig:make-designator + :object + (remove :location (desig:properties object-designator) :key #'car) + object-designator)) + +(defun make-location-in-attachment (?robot-name ?link) + (desig:a location (in (desig:an object + (type robot) + (name ?robot-name) + (part-of ?robot-name) + (urdf-name ?link))))) + +(defun update-object-designator-with-attachment (object-designator robot-name link) + "Changes the LOCATION key of the designator to a location on robot +and renames POSE into OLD-POSE." + (let* ((properties (desig:properties object-designator)) + (pose-pair (find :pose properties :key #'car)) + (location-in-hand (make-location-in-attachment robot-name link))) + (desig:make-designator + :object + (append (remove pose-pair + (remove :location + (remove :old-pose properties :key #'car) + :key #'car)) + `((:old-pose ,@(rest pose-pair)) + (:location ,location-in-hand))) + object-designator))) + + + +(defmethod cram-occasions-events:on-event object-perceived 2 ((event cpoe:object-perceived-event)) + (if cram-projection:*projection-environment* + ;; if in projection, only add the object name to perceived designators list + (let ((object-data (desig:reference (cpoe:event-object-designator event)))) + (or + (gethash (desig:object-identifier object-data) + *object-identifier-to-instance-mappings*) + (setf (gethash (desig:object-identifier object-data) + *object-identifier-to-instance-mappings*) + (desig:object-identifier object-data)))) + ;; otherwise, spawn a new object in the bullet world + (progn + (register-object-designator-data + (desig:reference (cpoe:event-object-designator event)) + :type (desig:desig-prop-value (cpoe:event-object-designator event) :type)) + ;; after having spawned the object, update the designator to get the + ;; new simulated pose + (desig:equate + (cpoe:event-object-designator event) + (detect-new-object-pose-from-btr (cpoe:event-object-designator event)))))) + + + +(defmethod cram-occasions-events:on-event btr-belief ((event cpoe:object-location-changed)) + ;; update the designator to get the new location + (update-object-designator-location + (cpoe:event-object-designator event) + (cpoe:event-location-designator event))) + + + +(defmethod cram-occasions-events:on-event robot-moved ((event cpoe:robot-state-changed)) + (unless cram-projection:*projection-environment* + (let ((robot (btr:get-robot-object))) + (when robot + (btr:set-robot-state-from-tf + cram-tf:*transformer* + robot + ;; :timestamp (cram-occasions-events:event-timestamp event) + ))))) + + + (defmethod cram-occasions-events:on-event btr-attach-object 2 ((event cpoe:object-attached-robot)) "2 means this method has to be ordered based on integer qualifiers. It could have been 1 but 1 is reserved in case somebody has to be even more urgently executed before everyone else. If there is no other method with 1 as qualifier, this method will be executed always first." - (let* ((robot-object (btr:get-robot-object)) + (let* ((robot-object-name (or (cpoe:event-other-object-name event) + (rob-int:get-robot-name))) + (robot-object (btr:object btr:*current-bullet-world* robot-object-name)) (environment-object (btr:get-environment-object)) (btr-object-name (cpoe:event-object-name event)) (btr-object (btr:object btr:*current-bullet-world* btr-object-name)) - (link (cut:var-value - '?ee-link - (car (prolog:prolog - `(and (cram-robot-interfaces:robot ?robot) - (cram-robot-interfaces:end-effector-link ?robot ,(cpoe:event-arm event) - ?ee-link)))))) - (grasp (cpoe:event-grasp event))) - (when (cut:is-var link) (error "[BTR-BELIEF OBJECT-ATTACHED] Couldn't find robot's EE link.")) + (arm (cpoe:event-arm event)) + (link (if arm + (cut:var-value + '?ee-link + (car (prolog:prolog + `(and (rob-int:robot ?robot) + (rob-int:end-effector-link ?robot ,arm ?ee-link))))) + (if (cpoe:event-link event) + (cpoe:event-link event) + (error "[BTR-BELIEF OBJECT-ATTACHED] either link or arm ~ + in object-attached-robot event had to be given...")))) + (grasp (cpoe:event-grasp event)) + (object-designator (cpoe:event-object-designator event))) + (when (cut:is-var link) + (error "[BTR-BELIEF OBJECT-ATTACHED] Couldn't find robot's EE link.")) ;; first detach from environment in case it is attached (when (and (typep environment-object 'btr:robot-object) (btr:object-attached environment-object btr-object)) (btr:detach-object environment-object btr-object)) + ;; also detach the object from other items in case they are attached, + ;; but only detach the loose attachments, because those are the attachments + ;; with the supporting objects. do not destroy the normal attachments, + ;; as those are attachments to the supported objects and we want the + ;; supported objects to still stay with our grasped object + (mapcar (lambda (other-object-name) + (btr:detach-object + btr-object (btr:object btr:*current-bullet-world* other-object-name))) + (btr:get-loose-attached-objects btr-object)) ;; now attach to the robot-object (when btr-object - (if (btr:object-attached robot-object btr-object) - (btr:attach-object robot-object btr-object :link link :loose t :grasp grasp) - (btr:attach-object robot-object btr-object :link link :loose nil :grasp grasp))))) + ;; if the object is already attached to some other robot link + ;; make the old attachment loose, + ;; because the new attachment will take precedence now + (multiple-value-bind (links grasps) + (btr:object-attached robot-object btr-object) + (when links + (mapc (lambda (attached-link grasp) + ;; detach and attach again with loose attachment + (btr:detach-object robot-object btr-object :link attached-link) + (btr:attach-object robot-object btr-object :link attached-link + :loose t + :grasp grasp)) + links grasps))) + ;; attach + (btr:attach-object robot-object btr-object :link link :loose nil :grasp grasp) + ;; invalidate the pose in the designator + (when object-designator + (update-object-designator-with-attachment + object-designator robot-object-name link))))) (defmethod cram-occasions-events:on-event btr-detach-object 2 ((event cpoe:object-detached-robot)) (let* ((robot-object (btr:get-robot-object)) + (environment-object (btr:get-environment-object)) (btr-object-name (cpoe:event-object-name event)) - (link (cut:var-value - '?ee-link - (car (prolog:prolog - `(and (cram-robot-interfaces:robot ?robot) - (cram-robot-interfaces:end-effector-link ?robot ,(cpoe:event-arm event) - ?ee-link))))))) + (arm (cpoe:event-arm event)) + (link (if arm + (cut:var-value + '?ee-link + (car (prolog:prolog + `(and (cram-robot-interfaces:robot ?robot) + (cram-robot-interfaces:end-effector-link ?robot ,arm + ?ee-link))))) + (if (cpoe:event-link event) + (cpoe:event-link event) + (error "[BTR-BELIEF OBJECT-DETACHED] either link or arm ~ + in object-attached-robot even had to be given..."))))) (when (cut:is-var link) (error "[BTR-BELIEF OBJECT-DETACHED] Couldn't find robot's EE link.")) (if btr-object-name + ;; if btr-object-name was given, detach it from the robot link (let ((btr-object (btr:object btr:*current-bullet-world* btr-object-name))) (when btr-object (btr:detach-object robot-object btr-object :link link) (btr:simulate btr:*current-bullet-world* 10) - ;; finding the link that supports the object now - ;; TODO: This part seems to be buggy, needs more testing. - ;; The part that fails is the environment link, sometimes it gets weird values. - ;; (let ((environment-object (btr:get-environment-object)) - ;; (environment-link (cut:var-value - ;; '?env-link - ;; (car (prolog:prolog - ;; `(and (btr:bullet-world ?world) - ;; (btr:supported-by - ;; ?world ,btr-object-name ?env-name ?env-link))))))) - ;; ;; attaching the link to the object if it finds one. - ;; (unless (cut:is-var environment-link) - ;; (btr:attach-object environment-object btr-object - ;; :link environment-link))) - )) + ;; find the links and items that support the object + ;; and attach the object to them. + ;; links get proper attachments and items loose attachments + (let ((contacting-links + (remove-duplicates + (mapcar + #'cdr + (remove-if-not + ;; filter all the links contacting items to our specific item + (lambda (item-and-link-name-cons) + (equal + (btr:name (car item-and-link-name-cons)) + btr-object-name)) + ;; get all links contacting items in the environment + (btr:link-contacts environment-object))) + :test #'equal)) + (contacting-items + (remove-if-not + (lambda (c) (typep c 'btr:item)) + (btr:find-objects-in-contact btr:*current-bullet-world* btr-object)))) + ;; If a link contacting btr-object was found, btr-object + ;; will be attached to it + ;; also, if btr-object is in contact with an item, + ;; it will be attached loose. + (mapcar (lambda (link-name) + (btr:attach-object environment-object btr-object :link link-name)) + contacting-links) + (mapcar (lambda (item-object) + (when item-object + (btr:attach-object item-object btr-object :loose T))) + contacting-items)))) + ;; if btr-object-name was not given, detach all objects from the robot link (progn (btr:detach-all-from-link robot-object link) (btr:simulate btr:*current-bullet-world* 10))))) @@ -97,7 +237,7 @@ If there is no other method with 1 as qualifier, this method will be executed al (btr-other-object-name (cpoe:event-other-object-name event)) (btr-other-object (btr:object btr:*current-bullet-world* btr-other-object-name)) (attachment-type (cpoe:event-attachment-type event))) - (when (and btr-object btr-other-object) + (when (and btr-object btr-other-object attachment-type) (let* ((btr-object-type (car (slot-value btr-object 'btr::types))) (btr-other-object-type @@ -128,29 +268,12 @@ If there is no other method with 1 as qualifier, this method will be executed al (cram-tf:strip-transform-stamped map-to-object-transform))) (setf (btr:pose btr-object) object-in-map-pose)) - (if (and attachment-type - (prolog `(man-int:unidirectional-attachment ,attachment-type))) + (if (prolog `(man-int:unidirectional-attachment ,attachment-type)) (btr:attach-object btr-other-object btr-object :loose T) (btr:attach-object btr-other-object btr-object))))) -(defmethod cram-occasions-events:on-event robot-moved ((event cpoe:robot-state-changed)) - (unless cram-projection:*projection-environment* - (let ((robot (btr:get-robot-object))) - (when robot - (btr:set-robot-state-from-tf - cram-tf:*transformer* - robot - :timestamp (cram-occasions-events:event-timestamp event))))) - (btr:timeline-advance - btr:*current-timeline* - (btr:make-event - btr:*current-bullet-world* - `(location-change robot)))) - - - (defun move-joint-by-event (event open-or-close) (let* ((joint-name (cpoe:environment-event-joint-name event)) (object (cpoe:environment-event-object event)) @@ -190,79 +313,8 @@ If there is no other method with 1 as qualifier, this method will be executed al -(defmethod cram-occasions-events:on-event object-perceived 2 ((event cpoe:object-perceived-event)) - (if cram-projection:*projection-environment* - ;; if in projection, only add the object name to perceived designators list - (let ((object-data (desig:reference (cpoe:event-object-designator event)))) - (or - (gethash (desig:object-identifier object-data) - *object-identifier-to-instance-mappings*) - (setf (gethash (desig:object-identifier object-data) - *object-identifier-to-instance-mappings*) - (desig:object-identifier object-data)))) - ;; otherwise, spawn a new object in the bullet world - (register-object-designator-data - (desig:reference (cpoe:event-object-designator event)) - :type (desig:desig-prop-value (cpoe:event-object-designator event) :type)))) - - - #+old-Lorenzs-stuff-currently-not-used-but-maybe-in-the-future ( - ;; Utility functions - (defun update-object-designator-location (object-designator location-designator) - (desig:make-designator - :object - `((:at ,location-designator) - ,@(remove :at (desig:properties object-designator) :key #'car)) - object-designator)) - - (defun get-supporting-object-bounding-box (object-name) - (cut:with-vars-bound (?supporting-name ?supporting-link) - (cut:lazy-car (prolog - `(or (btr:supported-by ?_ ,object-name ?supporting-name ?supporting-link) - (btr:supported-by ?_ ,object-name ?supporting-name)))) - (unless (cut:is-var ?supporting-name) - (if (cut:is-var ?supporting-link) - (btr:aabb (btr:object btr:*current-bullet-world* ?supporting-name)) - (btr:aabb (gethash - ?supporting-link - (btr:links (btr:object btr:*current-bullet-world* ?supporting-name)))))))) - - (defun make-object-location (object-name) - (let ((object (btr:object btr:*current-bullet-world* object-name))) - (assert object) - (desig:make-designator - :location - `((:pose ,(cl-transforms-stamped:pose->pose-stamped - cram-tf:*fixed-frame* - (cut:current-timestamp) - (cl-bullet:pose object))))))) - - (defun make-object-location-in-gripper (object gripper-link) - "Returns a new location designator that indicates a location in the - robot's gripper." - (declare (type btr:object object)) - (let* ((object-pose (cl-transforms-stamped:pose->pose-stamped - cram-tf:*fixed-frame* - 0.0 - (btr:pose object))) - (robot (btr:get-robot-object))) - (assert (member gripper-link (btr:object-attached robot object) :test #'equal)) - (let ((supporting-bounding-box (get-supporting-object-bounding-box (btr:name object)))) - (desig:make-designator - :location - `((:in :gripper) (:pose ,(object-pose-in-frame object gripper-link)) - (:z-offset ,(cond (supporting-bounding-box - (- (cl-transforms:z (cl-transforms:origin object-pose)) - (+ (cl-transforms:z - (cl-bullet:bounding-box-center supporting-bounding-box)) - (/ (cl-transforms:z - (cl-bullet:bounding-box-dimensions - supporting-bounding-box)) - 2)))) - (t 0.0)))))))) - (defun object-pose-in-frame (object frame) (declare (type btr:object object) (type string frame)) @@ -276,76 +328,20 @@ If there is no other method with 1 as qualifier, this method will be executed al :target-frame frame :timeout cram-tf:*tf-default-timeout*) :stamp 0.0)) - - - - ;; Additionally changing the object designator of the object - (defmethod cram-occasions-events:on-event attach-objects ((event cpoe:object-attached)) - (let* ((robot (btr:get-robot-object)) - (current-event-object (desig:current-desig (cpoe:event-object event))) - (object (get-designator-object current-event-object))) - (when object - (cond ((btr:object-attached robot object) - ;; If the object is already attached, it is already in - ;; the gripper. In that case, we update the designator - ;; location designator by extending the current location - ;; by a second pose in the gripper. - (btr:attach-object robot object :link (cpoe:event-link event) :loose t) - (desig:with-desig-props (at) current-event-object - (assert (eql (desig:desig-prop-value at :in) :gripper)) - (update-object-designator-location - current-event-object - (desig:extend-designator-properties - at `((:pose ,(object-pose-in-frame object (cpoe:event-link event)))))))) - (t - (btr:attach-object robot object :link (cpoe:event-link event) :loose nil) - (update-object-designator-location - current-event-object - (desig:extend-designator-properties - (make-object-location-in-gripper object (cpoe:event-link event)) - `((:pose ,(object-pose-in-frame object cram-tf:*robot-base-frame*)))))))) - (btr:timeline-advance - btr:*current-timeline* - (btr:make-event - btr:*current-bullet-world* - `(pick-up ,(cpoe:event-object event) ,(cpoe:event-side event)))))) - (defmethod cram-occasions-events:on-event detach-objects ((event cpoe:object-detached-robot)) - (let ((robot (btr:get-robot-object)) - (object (get-designator-object (cpoe:event-object event)))) - (when object - (btr:detach-object robot object :link (cpoe:event-link event)) - (btr:simulate btr:*current-bullet-world* 10) - (update-object-designator-location - (desig:current-desig (cpoe:event-object event)) - (make-object-location (get-designator-object-name (cpoe:event-object event))))) - (btr:timeline-advance - btr:*current-timeline* - (btr:make-event - btr:*current-bullet-world* - `(put-down ,(cpoe:event-object event) ,(cpoe:event-side event)))) - (btr:timeline-advance - btr:*current-timeline* - (btr:make-event - btr:*current-bullet-world* - `(location-change ,(cpoe:event-object event)))))) - - - ;; Additionally updating the semantic map - (defmethod cram-occasions-events:on-event open-or-close-object - ((event cpoe:object-articulation-event)) - (with-slots (cpoe:object-designator cpoe:opening-distance) event - (let ((perceived-object (desig:reference - (desig:newest-effective-designator cpoe:object-designator))) - (semantic-map-object - (cut:with-vars-strictly-bound (?semantic-map) - (cut:lazy-car - (prolog `(and - (btr:bullet-world ?world) - (btr:semantic-map ?world ?semantic-map-name) - (btr:%object ?world ?semantic-map-name ?semantic-map)))) - ?semantic-map))) - (btr:set-articulated-object-joint-position - semantic-map-object - (desig:object-identifier perceived-object) - cpoe:opening-distance)))) + ;; + (defun make-object-location-in-gripper (object gripper-link) + "Returns a new location designator that indicates a location in the + robot's gripper." + (declare (type btr:object object)) + (let* ((object-pose (cl-transforms-stamped:pose->pose-stamped + cram-tf:*fixed-frame* + 0.0 + (btr:pose object))) + (robot (btr:get-robot-object))) + (assert (member gripper-link (btr:object-attached robot object) :test #'equal)) + (let ((supporting-bounding-box (get-supporting-object-bounding-box (btr:name object)))) + (desig:make-designator + :location + `((:in :gripper) + (:pose ,(object-pose-in-frame object gripper-link))))))) ) diff --git a/cram_3d_world/cram_bullet_reasoning_belief_state/src/object-perceptions.lisp b/cram_3d_world/cram_bullet_reasoning_belief_state/src/object-perceptions.lisp index ddd96b8a15..fd48a0ab8f 100644 --- a/cram_3d_world/cram_bullet_reasoning_belief_state/src/object-perceptions.lisp +++ b/cram_3d_world/cram_bullet_reasoning_belief_state/src/object-perceptions.lisp @@ -74,11 +74,54 @@ just updated. Otherwise a new instance is created.")) (when object-name (btr:object btr:*current-bullet-world* object-name)))) +(defmethod register-object-designator-data (data &key type) + (let ((instance-name + (or (gethash (desig:object-identifier data) + *object-identifier-to-instance-mappings*) + (setf (gethash (desig:object-identifier data) + *object-identifier-to-instance-mappings*) + ;; (gensym (string (desig:object-identifier data))) + (desig:object-identifier data)))) + (object-pose + (desig:object-pose data))) + ;; Hack 1: put the object a bit down + ;; as RS always says it's too high after cutting off the plane + (setf object-pose + (cram-tf:translate-pose object-pose + ;; :z -0.04 :y -0.02 :x 0.0 + ;; :z -0.01 + )) + ;; Hack 2: deal with shitty identity resolution on RS / KnowRob side :P + (prolog `(and (btr:bullet-world ?world) + (btr:item-type ?world ?name ,type) + (btr:retract ?world (btr:object ?name)))) + ;; and spawn + (prolog `(and (btr:bullet-world ?world) + (-> (btr:object ?world ,instance-name) + (btr:assert ?world + (btr:object-pose ,instance-name ,object-pose)) + (btr:assert ?world + (btr:object :mesh ,instance-name ,object-pose + :mesh ,type ;; ,(object-mesh data) + :mass 0.2 ;; ,(object-mass data) + ;; :types ,(list type) + ;; :disable-face-culling t + :color ,(if (slot-boundp data 'desig::color) + (desig:object-color data) + '(0.5 0.5 0.5))))))) + ;; simulate world + (btr:simulate btr:*current-bullet-world* 10))) + (defmethod register-object-designator-data ((data cram-physics-utils:object-shape-data-mixin) &key type) (declare (ignore type)) nil) +(defmethod register-object-designator-data + ((data cram-physics-utils:object-point-data-mixin) &key type) + (declare (ignore type)) + nil) + (defmethod register-object-designator-data ((data cram-physics-utils:object-mesh-data-mixin) &key type) (let ((instance-name (or @@ -98,39 +141,6 @@ just updated. Otherwise a new instance is created.")) :types ,(list type) :disable-face-culling t))))))) -(defmethod register-object-designator-data - (data &key type) - (let ((instance-name (or - (gethash (desig:object-identifier data) - *object-identifier-to-instance-mappings*) - (setf (gethash (desig:object-identifier data) - *object-identifier-to-instance-mappings*) - ;; (gensym (string (desig:object-identifier data))) - (desig:object-identifier data))))) - ;; below is a hack to deal with shitty identity resolution on RS / KnowRob side :P - (prolog `(and (btr:bullet-world ?world) - (btr:item-type ?world ?name ,type) - (btr:retract ?world (btr:object ?name)))) - (prolog `(and (btr:bullet-world ?world) - (-> (btr:object ?world ,instance-name) - (btr:assert ?world - (btr:object-pose ,instance-name ,(desig:object-pose data))) - (btr:assert ?world - (btr:object :mesh ,instance-name ,(desig:object-pose data) - :mesh ,type ;; ,(object-mesh data) - :mass 0.2 ;; ,(object-mass data) - ;; :types ,(list type) - ;; :disable-face-culling t - :color ,(if (slot-boundp data 'desig::color) - (desig:object-color data) - '(0.5 0.5 0.5))))) - (btr:simulate ?world 10))))) - -(defmethod register-object-designator-data - ((data cram-physics-utils:object-point-data-mixin) &key type) - (declare (ignore type)) - nil) - (defmethod object-mass ((data cram-physics-utils:object-mesh-data-mixin)) (cram-physics-utils:calculate-mass :mesh :points (cram-physics-utils:vertices data))) diff --git a/cram_3d_world/cram_bullet_reasoning_belief_state/src/occasions.lisp b/cram_3d_world/cram_bullet_reasoning_belief_state/src/occasions.lisp index 70792d20c1..0f6701d41f 100644 --- a/cram_3d_world/cram_bullet_reasoning_belief_state/src/occasions.lisp +++ b/cram_3d_world/cram_bullet_reasoning_belief_state/src/occasions.lisp @@ -1,19 +1,21 @@ +;;; ;;; Copyright (c) 2012, Lorenz Moesenlechner +;;; 2020, Christopher Pollok ;;; All rights reserved. -;;; +;;; ;;; Redistribution and use in source and binary forms, with or without ;;; modification, are permitted provided that the following conditions are met: -;;; +;;; ;;; * Redistributions of source code must retain the above copyright ;;; notice, this list of conditions and the following disclaimer. ;;; * Redistributions in binary form must reproduce the above copyright ;;; notice, this list of conditions and the following disclaimer in the ;;; documentation and/or other materials provided with the distribution. ;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software ;;; without specific prior written permission. -;;; +;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" ;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE ;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE @@ -28,57 +30,405 @@ (in-package :cram-bullet-reasoning-belief-state) -(def-fact-group occasions (cpoe:object-in-hand cpoe:object-picked cpoe:object-placed-at cpoe:loc) - (<- (cpoe:object-in-hand ?object ?side ?grasp) - (btr:bullet-world ?world) - (cram-robot-interfaces:robot ?robot) - (btr:attached ?world ?robot ?link ?object-name ?grasp) - (once - (and (object-designator-name ?object ?object-name) - (desig:obj-desig? ?object))) - (cram-robot-interfaces:end-effector-link ?robot ?side ?link)) +(defparameter *torso-convergence-delta* 0.01 "In meters") +(defparameter *gripper-joint-convergence-delta* 0.005 "In meters") +(defparameter *arm-joints-convergence-delta* 0.0174 "In radians, about 1 deg.") +(defparameter *ee-position-convergence-delta* 0.02 "In meters") +(defparameter *ee-rotation-convergence-delta* 0.07 "In radians, about 4 deg.") +(defparameter *looking-convergence-delta* 0.01 "In meters") +(defparameter *looking-convergence-joints-delta* 0.07 "In radians, about 4 deg.") + +(def-fact-group occasions (cpoe:object-in-hand + cpoe:object-at-location + cpoe:robot-at-location + cpoe:torso-at + cpoe:gripper-joint-at + cpoe:gripper-opened + cpoe:gripper-closed + cpoe:arms-positioned-at + cpoe:tool-frames-at + cpoe:looking-at + cpoe:location-reset) - (<- (cpoe:object-in-hand ?object ?side) - (cpoe:object-in-hand ?object ?side ?_)) + ;; This occasion is defined in cram_urdf_environment_manipulation + ;; (<- (cpoe:container-state ?container-designator ?distance) ...) + ;; if we want the arm, we get it from the link + (<- (cpoe:object-in-hand ?object ?arm ?grasp) + (btr:bullet-world ?world) + (rob-int:robot ?robot) + (btr:attached ?world ?robot ?link ?object-name ?grasp) + (once (and (object-designator-name ?object ?object-name) + (desig:obj-desig? ?object))) + (-> (bound ?arm) + (rob-int:end-effector-link ?robot ?arm ?link) + (once (or (rob-int:end-effector-link ?robot ?arm ?link) + (true))))) + ;; + ;; if we only want to know the link and don't care about the arm + ;; it can be that the arm is not even given in the attachments + ;; so we need a bit of copy paste here... + (<- (cpoe:object-in-hand ?object ?_ ?grasp ?link) + (btr:bullet-world ?world) + (rob-int:robot ?robot) + (btr:attached ?world ?robot ?link ?object-name ?grasp) + (once (and (object-designator-name ?object ?object-name) + (desig:obj-desig? ?object)))) + ;; + (<- (cpoe:object-in-hand ?object ?arm) + (cpoe:object-in-hand ?object ?arm ?_)) + ;; (<- (cpoe:object-in-hand ?object) (setof ?object (cpoe:object-in-hand ?object ?_) ?objects) (member ?object ?objects)) + ;; + (<- (cpoe:object-in-hand ?object :left-or-right) + (or (cpoe:object-in-hand ?object :left) + (cpoe:object-in-hand ?object :right))) - (<- (cpoe:object-picked ?object) - (cpoe:object-in-hand ?object)) - (<- (cpoe:object-placed-at ?object ?location) - (cpoe:loc ?object ?location)) + (<- (cpoe:robot-at-location ?location) + (rob-int:robot ?robot) + (%object-at-location ?_ ?robot ?location)) - (<- (cpoe:loc ?robot ?location) - (cram-robot-interfaces:robot ?robot) - (object-at-location ?_ ?robot ?location)) - (<- (cpoe:loc ?object ?location) - (desig:obj-desig? object) + (<- (cpoe:object-at-location ?object ?location) + (desig:obj-desig? ?object) (object-designator-name ?object ?object-name) - (object-at-location ?_ ?object-name ?location))) + (%object-at-location ?_ ?object-name ?location)) + + + (<- (cpoe:torso-at ?joint-state) + (symbol-value *torso-convergence-delta* ?torso-delta) + (cpoe:torso-at ?joint-state ?torso-delta)) + ;; + (<- (cpoe:torso-at ?joint-state ?delta) + (lisp-type ?joint-state keyword) + (rob-int:robot ?robot) + (rob-int:robot-torso-link-joint ?robot ?_ ?joint) + (rob-int:joint-lower-limit ?robot ?joint ?lower-limit) + (rob-int:joint-upper-limit ?robot ?joint ?upper-limit) + (-> (equal ?joint-state :upper-limit) + (cpoe:torso-at ?upper-limit ?delta) + (-> (equal ?joint-state :lower-limit) + (cpoe:torso-at ?lower-limit ?delta) + (-> (equal ?joint-state :middle) + (and (lisp-fun - ?upper-limit ?lower-limit ?middle-diff) + (lisp-fun / ?middle-diff 2 ?middle-half-diff) + (lisp-fun + ?lower-limit ?middle-half-diff ?middle) + (cpoe:torso-at ?middle ?delta)) + (fail))))) + ;; + (<- (cpoe:torso-at ?joint-state ?delta) + (lisp-type ?joint-state number) + (rob-int:robot ?robot) + (rob-int:robot-torso-link-joint ?robot ?_ ?torso-joint) + (btr:bullet-world ?world) + (btr:joint-state ?world ?robot ?torso-joint ?torso-joint-state) + (lisp-pred cram-tf:values-converged ?torso-joint-state ?joint-state ?delta)) + + (<- (cpoe:gripper-joint-at ?gripper ?joint-state) + (symbol-value *gripper-joint-convergence-delta* ?gripper-delta) + (cpoe:gripper-joint-at ?gripper ?joint-state ?gripper-delta)) + + (<- (cpoe:gripper-joint-at ?gripper ?joint-state ?delta) + (lisp-type ?gripper keyword) + (rob-int:robot ?robot) + (rob-int:gripper-meter-to-joint-multiplier ?robot ?mult) + (lisp-fun * ?joint-state ?mult ?joint-state-mult) + (lisp-fun * ?delta ?mult ?delta-mult) + (forall (rob-int:gripper-joint ?robot ?gripper ?gripper-joint) + (%joint-at ?gripper-joint ?joint-state-mult ?delta-mult))) + + (<- (cpoe:gripper-joint-at ?gripper ?joint-state ?delta) + (lisp-type ?gripper list) + (forall (member ?single-gripper ?gripper) + (cpoe:gripper-joint-at ?single-gripper ?joint-state ?delta))) + + (<- (cpoe:gripper-opened ?gripper) + (symbol-value *gripper-joint-convergence-delta* ?gripper-delta) + (cpoe:gripper-opened ?gripper ?gripper-delta)) + + (<- (cpoe:gripper-opened ?gripper ?delta) + (lisp-type ?gripper keyword) + (rob-int:robot ?robot) + (rob-int:gripper-meter-to-joint-multiplier ?robot ?mult) + (lisp-fun * ?delta ?mult ?delta-mult) + (rob-int:gripper-joint ?robot ?gripper ?_) + (forall (rob-int:gripper-joint ?robot ?gripper ?gripper-joint) + (and (rob-int:joint-upper-limit ?robot ?gripper-joint ?upper-limit) + (%joint-at ?gripper-joint ?upper-limit ?delta-mult)))) + + (<- (cpoe:gripper-opened ?gripper ?delta) + (lisp-type ?gripper list) + (forall (member ?single-gripper ?gripper) + (cpoe:gripper-opened ?single-gripper ?delta))) + + (<- (cpoe:gripper-closed ?gripper) + (symbol-value *gripper-joint-convergence-delta* ?gripper-delta) + (cpoe:gripper-closed ?gripper ?gripper-delta)) + + (<- (cpoe:gripper-closed ?gripper ?delta) + (lisp-type ?gripper keyword) + (rob-int:robot ?robot) + (rob-int:gripper-meter-to-joint-multiplier ?robot ?mult) + (lisp-fun * ?delta ?mult ?delta-mult) + (rob-int:gripper-joint ?robot ?gripper ?gripper-joint) + (forall (rob-int:gripper-joint ?robot ?gripper ?gripper-joint) + (and (rob-int:joint-lower-limit ?robot ?gripper-joint ?lower-limit) + (%joint-at ?gripper-joint ?lower-limit ?delta-mult)))) + (<- (cpoe:gripper-closed ?gripper ?delta) + (lisp-type ?gripper list) + (forall (member ?single-gripper ?gripper) + (cpoe:gripper-closed ?single-gripper ?delta))) + (<- (cpoe:arms-positioned-at ?left-configuration ?right-configuration) + (symbol-value *arm-joints-convergence-delta* ?delta) + (cpoe:arms-positioned-at ?left-configuration ?right-configuration ?delta)) + ;; + (<- (cpoe:arms-positioned-at ?left-config ?right-config ?delta) + (rob-int:robot ?robot) + (-> (lisp-pred identity ?left-config) + (and (man-int:joint-state-for-arm-config ?robot ?left-config :left + ?left-goal-states) + (lisp-pred btr:robot-converged-to-goal-joint-states + ?left-goal-states ?delta)) + (true)) + (-> (lisp-pred identity ?right-config) + (and (man-int:joint-state-for-arm-config ?robot ?right-config :right + ?right-goal-states) + (lisp-pred btr:robot-converged-to-goal-joint-states + ?right-goal-states ?delta)) + (true))) + ;; For checking other than arm configurations, e.g., neck configuration + (<- (cpoe:arms-positioned-at ?effector-type ?effector-name + ?effector-configuration-name ?delta) + (rob-int:robot ?robot) + (rob-int:robot-joint-states ?robot ?effector-type ?effector-name + ?effector-configuration-name + ?effector-joint-states) + (lisp-pred btr:robot-converged-to-goal-joint-states + ?effector-joint-states ?delta)) + + + (<- (cpoe:tool-frames-at ?left-poses ?right-poses) + (symbol-value *ee-position-convergence-delta* ?delta-position) + (symbol-value *ee-rotation-convergence-delta* ?delta-rotation) + (cpoe:tool-frames-at ?left-poses ?right-poses ?delta-position ?delta-rotation)) + ;; + (<- (cpoe:tool-frames-at ?left-poses ?right-poses ?delta-pos ?delta-rot) + (or (and (lisp-pred identity ?left-poses) + (lisp-type ?left-poses list)) + (and (lisp-pred identity ?right-poses) + (lisp-type ?right-poses list))) + (-> (and (lisp-pred identity ?left-poses) + (lisp-type ?left-poses list)) + (and (lisp-fun last ?left-poses ?left-pose-list) + (lisp-fun car ?left-pose-list ?left-pose)) + (equal ?left-poses ?left-pose)) + (-> (and (lisp-pred identity ?right-poses) + (lisp-type ?right-poses list)) + (and (lisp-fun last ?right-poses ?right-pose-list) + (lisp-fun car ?right-pose-list ?right-pose)) + (equal ?right-poses ?right-pose)) + (cpoe:tool-frames-at ?left-pose ?right-pose ?delta-pos ?delta-rot)) + ;; + (<- (cpoe:tool-frames-at ?left-pose ?right-pose ?delta-pos ?delta-rot) + (not (lisp-type ?left-pose cl-transforms-stamped:pose-stamped)) + (not (lisp-type ?right-pose cl-transforms-stamped:pose-stamped)) + (or (lisp-type ?left-pose cl-transforms:pose) + (lisp-type ?right-pose cl-transforms:pose)) + ;; If the pose doesn't have a frame, we have to assume that it's in fixed frame + (symbol-value cram-tf:*fixed-frame* ?fixed-frame) + (-> (lisp-type ?left-pose cl-transforms:pose) + (lisp-fun cl-transforms-stamped:pose->pose-stamped ?fixed-frame 0.0 + ?left-pose ?left-pose-stamped) + (equal ?left-pose ?left-pose-stamped)) + (-> (lisp-type ?right-pose cl-transforms:pose) + (lisp-fun cl-transforms-stamped:pose->pose-stamped ?fixed-frame 0.0 + ?right-pose ?right-pose-stamped) + (equal ?right-pose ?right-pose-stamped)) + (cpoe:tool-frames-at ?left-pose-stamped ?right-pose-stamped + ?delta-pos ?delta-rot)) + ;; + (<- (cpoe:tool-frames-at ?left-pose-stamped ?right-pose-stamped + ?delta-pos ?delta-rot) + (or (lisp-type ?left-pose-stamped cl-transforms-stamped:pose-stamped) + (lisp-type ?right-pose-stamped cl-transforms-stamped:pose-stamped)) + (rob-int:robot ?robot) + (btr:bullet-world ?world) + (symbol-value cram-tf:*fixed-frame* ?fixed-frame) + (-> (lisp-type ?left-pose-stamped cl-transforms-stamped:pose-stamped) + (and (rob-int:robot-tool-frame ?robot :left ?left-tool-frame) + (btr:link-pose ?world ?robot ?left-tool-frame ?left-tool-pose) + (lisp-fun cl-transforms-stamped:pose->pose-stamped ?fixed-frame 0.0 + ?left-tool-pose ?left-tool-pose-stamped) + (lisp-pred cram-tf:pose-stampeds-converged + ?left-tool-pose-stamped ?left-pose-stamped + ?delta-pos ?delta-rot)) + (true)) + (-> (lisp-type ?right-pose-stamped cl-transforms-stamped:pose-stamped) + (and (rob-int:robot-tool-frame ?robot :right ?right-tool-frame) + (btr:link-pose ?world ?robot ?right-tool-frame ?right-tool-pose) + (lisp-fun cl-transforms-stamped:pose->pose-stamped ?fixed-frame 0.0 + ?right-tool-pose ?right-tool-pose-stamped) + (lisp-pred cram-tf:pose-stampeds-converged + ?right-tool-pose-stamped ?right-pose-stamped + ?delta-pos ?delta-rot)) + (true))) + + + (<- (cpoe:looking-at ?location-or-object-or-frame-or-direction-or-pose) + (symbol-value *looking-convergence-delta* ?delta) + (cpoe:looking-at ?location-or-object-or-frame-or-direction-or-pose ?delta)) + ;; + (<- (cpoe:looking-at ?object-designator ?delta) + (desig:obj-desig? ?object-designator) + (desig:current-designator ?object-designator ?current-object-desig) + (lisp-fun man-int:get-object-pose-in-map ?current-object-desig ?object-pose) + (cpoe:looking-at ?object-pose ?delta)) + ;; + (<- (cpoe:looking-at ?location-designator ?delta) + (desig:loc-desig? ?location-designator) + (desig:current-designator ?location-designator ?current-location-designator) + (desig:designator-groundings ?current-location-designator ?poses) + ;; Note(gaya): when checking if a goal has been achieved after having performed + ;; the action, it might happen that this implementation will give a + ;; false negative, if the costmap is big. + ;; Although, if this is happening AFTER the action, the designator + ;; must already be resolved, and perhaps the resolved pose will coincide + ;; with what the robot is looking at... + (once (member ?pose ?poses)) + (cpoe:looking-at ?pose ?delta)) + ;; + (<- (cpoe:looking-at ?frame ?delta) + (lisp-type ?frame string) + (symbol-value cram-tf:*fixed-frame* ?fixed-frame) + ;; Don't want to use the transformer in goal proving, so just assume TRUE + ;; (symbol-value cram-tf:*transformer* ?transformer) + ;; (-> (lisp-pred cl-tf:wait-for-transform ?transformer + ;; :source-frame ?frame + ;; :target-frame ?fixed-frame + ;; :timeout 0.1) + ;; (and (lisp-fun lookup-transform-handled ?transformer ?fixed-frame ?frame + ;; ?frame-transform) + ;; (lisp-fun cl-transforms-stamped:stamp ?frame-transform ?stamp) + ;; (lisp-fun cram-tf:transform->pose-stamped ?fixed-frame ?stamp + ;; ?frame-transform ?frame-pose-stamped) + ;; (cpoe:looking-at ?frame-pose-stamped ?delta)) + ;; (fail)) + ) + ;; + (<- (cpoe:looking-at ?direction ?delta) + (lisp-type ?direction keyword) + (rob-int:robot ?robot) + ;; btr:looking-in-direction-p needs a vector, here the direction is a keyword + (or (and (rob-int:robot-pose ?robot :neck ?_ ?direction ?pose-stamped) + (cpoe:looking-at ?pose-stamped ?delta)) + (and (symbol-value *looking-convergence-joints-delta* ?joints-delta) + (cpoe:arms-positioned-at :neck ?_ ?direction ?joints-delta)))) + ;; + (<- (cpoe:looking-at ?pose ?delta) + (not (lisp-type ?pose cl-transforms-stamped:pose-stamped)) + (lisp-type ?pose cl-transforms:pose) + (symbol-value cram-tf:*fixed-frame* ?fixed-frame) + (lisp-fun cl-transforms-stamped:pose->pose-stamped ?fixed-frame 0.0 ?pose + ?pose-stamped) + (cpoe:looking-at ?pose-stamped ?delta)) + ;; + (<- (cpoe:looking-at ?pose-stamped-in-map ?delta) + (lisp-type ?pose-stamped-in-map cl-transforms-stamped:pose-stamped) + (lisp-fun cl-transforms-stamped:frame-id ?pose-stamped-in-map ?frame) + (symbol-value cram-tf:*fixed-frame* ?fixed-frame) + (rob-int:robot ?robot) + (rob-int:camera-frame ?robot ?camera-frame) + (btr:bullet-world ?world) + (btr:link-pose ?world ?robot ?camera-frame ?camera-pose) + (-> (lisp-pred string-equal ?frame ?fixed-frame) + (or (lisp-pred btr:looking-at-pose-p ?world ?camera-pose ?pose-stamped-in-map) + (and (rob-int:camera-horizontal-angle ?robot ?camera-angle-h) + (rob-int:camera-vertical-angle ?robot ?camera-angle-v) + (btr:%object ?world ?robot ?robot-object) + (lisp-fun cl-transforms:origin ?pose-stamped-in-map ?target-point) + (lisp-fun cl-transforms:origin ?camera-pose ?camera-point) + (lisp-fun cl-transforms:v- ?target-point ?camera-point ?direction) + (lisp-pred btr:looking-in-direction-p ?robot-object ?camera-frame + ?camera-angle-h ?camera-angle-v ?direction))) + (true)) + ;; Don't want to use the transformer if the pose is not in map. Assume TRUE. + ;; (and (symbol-value cram-tf:*transformer* ?transformer) + ;; (symbol-value cram-tf:*fixed-frame* ?fixed-frame) + ;; (-> (lisp-pred cl-tf:wait-for-transform ?transformer + ;; :source-frame ?camera-frame + ;; :target-frame ?fixed-frame + ;; :timeout 0.1) + ;; (and + ;; (lisp-fun cl-tf:lookup-transform ?transformer ?fixed-frame + ;; ?camera-frame ?camera-transform) + ;; (lisp-fun cl-tf:translation ?camera-transform ?camera-point) + ;; (lisp-fun cl-tf:origin ?pose-stamped ?target-point) + ;; (lisp-fun cl-tf:v- ?target-point ?camera-point ?direction) + ;; (rob-int:camera-horizontal-angle ?robot ?camera-angle-h) + ;; (rob-int:camera-vertical-angle ?robot ?camera-angle-v) + ;; (lisp-pred looking-in-direction ?camera-frame ?camera-angle-h + ;; ?camera-angle-v ?direction)) + ;; (fail))) + ) + + (<- (cpoe:location-reset ?some-location-designator) + (desig:loc-desig? ?some-location-designator) + (desig:current-designator ?some-location-designator ?location-designator) + (-> (or (spec:property ?location-designator (:in ?some-object-designator)) + (spec:property ?location-designator (:above ?some-object-designator))) + (and (desig:desig-prop ?location-designator (?tag ?some-object-designator)) + (desig:current-designator ?some-object-designator ?object-designator) + (-> (or (and (equal :in ?tag) + (man-int:object-is-a-container ?object-designator)) + (and (equal :above ?tag) + (man-int:object-is-a-prismatic-container ?object-designator))) + (cpoe:container-state ?object-designator :close) + (true))) + (true))) + + (<- (cpoe:location-accessible ?some-location-designator) + (desig:loc-desig? ?some-location-designator) + (desig:current-designator ?some-location-designator ?location-designator) + (-> (spec:property ?location-designator (:in ?container-object)) + (and (desig:current-designator ?container-object ?object-designator) + (or (desig:desig-prop ?object-designator (:type :robot)) + (and (rob-int:robot ?robot) + (desig:desig-prop ?object-designator (:part-of ?robot))) + (cpoe:container-state ?object-designator :open))) + ;; Above keyword is inaccessible for prismatic containers like drawers + ;; but not for revolute containers like fridge/oven + (-> (spec:property ?location-designator (:above ?location-object)) + (or (not (man-int:object-is-a-prismatic-container ?location-object)) + (cpoe:container-state ?location-object :open)) + (true))))) + + + +(def-fact-group occasion-utilities (object-designator-name + desig:desig-location-prop) -(def-fact-group occasion-utilities (object-designator-name desig:desig-location-prop) (<- (object-designator-name ?name ?name) (lisp-type ?name symbol)) (<- (object-designator-name ?object-designator ?object-name) (or (and (bound ?object-designator) - (desig:obj-desig? ?object-designator)) + (desig:obj-desig? ?object-designator) + (desig:current-designator ?object-designator + ?current-object-designator) + (desig:desig-prop ?current-object-designator (:name ?object-name))) (and (not (bound ?object-designator)) + ;; all object designators who have the same name should be + ;; perceptions of the same exact object, and, thus, + ;; they should be equated into one chain (lisp-fun unique-object-designators ?object-designators) - (member ?one-object-designator-from-chain ?object-designators) - (desig:current-designator ?one-object-designator-from-chain ?object-designator))) - (lisp-fun get-designator-object-name ?object-designator ?belief-name) - (-> (lisp-pred identity ?belief-name) - (equal ?object-name ?belief-name) - (and (desig:desig-prop ?object-designator (:type ?object-type)) - (btr:bullet-world ?w) - (btr:item-type ?world ?object-name ?object-type)))) + (member ?one-desig-from-chain ?object-designators) + (desig:current-designator ?one-desig-from-chain ?object-designator) + (desig:desig-prop ?object-designator (:name ?object-name))))) (<- (desig:desig-location-prop ?designator ?location) (desig:obj-desig? ?designator) @@ -99,7 +449,7 @@ (btr:object ?_ ?o) (btr:pose ?_ ?o ?loc)) - (<- (object-at-location ?world ?object-name ?location-designator) + (<- (%object-at-location ?world ?object-name ?location-designator) (lisp-type ?location-designator desig:location-designator) (btr:bullet-world ?world) (lisp-fun desig:current-desig ?location-designator ?current-location) @@ -107,17 +457,26 @@ (desig:designator-groundings ?current-location ?_) (or (btr:object-pose ?world ?object-name ?object-pose) (btr:object-bottom-pose ?world ?object-name ?object-pose)) + ;; this only works for location designators that are resolved through costmaps + ;; for others, such as those that are resolved through ATTACHMENT tags, + ;; this does not work... (lisp-pred desig:validate-location-designator-solution ?current-location ?object-pose)) - (<- (object-at-location ?world ?object-name ?location-designator) - (not (bound ?location)) + (<- (%object-at-location ?world ?object-name ?location-designator) + (not (bound ?location-designator)) (btr:bullet-world ?world) (btr:object-pose ?world ?object-name ?object-pose) (symbol-value cram-tf:*fixed-frame* ?fixed-frame) (lisp-fun cl-transforms-stamped:pose->pose-stamped ?fixed-frame 0.0 ?object-pose ?object-pose-stamped) (desig:designator :location ((:pose ?object-pose-stamped)) - ?location-designator))) + ?location-designator)) + + (<- (%joint-at ?joint ?goal-state ?delta) + (rob-int:robot ?robot) + (btr:bullet-world ?world) + (btr:joint-state ?world ?robot ?joint ?state) + (lisp-pred cram-tf:values-converged ?state ?goal-state ?delta))) (defun unique-object-designators () "Returns all designators. For equated designators, only one instance diff --git a/cram_3d_world/cram_bullet_reasoning_belief_state/src/package.lisp b/cram_3d_world/cram_bullet_reasoning_belief_state/src/package.lisp index cf0f8103d2..f972f24d87 100644 --- a/cram_3d_world/cram_bullet_reasoning_belief_state/src/package.lisp +++ b/cram_3d_world/cram_bullet_reasoning_belief_state/src/package.lisp @@ -42,10 +42,8 @@ ;; occasions #:object-designator-name ;; belief-state - #:*kitchen-urdf* - #:*robot-parameter* #:*kitchen-parameter* #:*spawn-debug-window* #:setup-world-database #:vary-kitchen-urdf - ;; process-modules + ;; world-state-detecting #:world-state-detecting-pm)) diff --git a/cram_3d_world/cram_bullet_reasoning_belief_state/src/tf.lisp b/cram_3d_world/cram_bullet_reasoning_belief_state/src/tf.lisp index df3c8ef741..e9f150e928 100644 --- a/cram_3d_world/cram_bullet_reasoning_belief_state/src/tf.lisp +++ b/cram_3d_world/cram_bullet_reasoning_belief_state/src/tf.lisp @@ -68,7 +68,7 @@ (if (member parent-name bullet-links) (progn (push - (cl-tf:transform->transform-stamped + (cl-transforms-stamped:transform->transform-stamped parent-name link-name time (cl-urdf:origin link-joint)) virtual-joint-transforms) @@ -95,7 +95,7 @@ (warn "Robot was not present in the world. Not going to GET-TRANSFORMS-FROM-BULLET.") (let* (;; global fixed frame and the odom frame are the same (global->odom - (cl-tf:make-transform-stamped + (cl-transforms-stamped:make-transform-stamped fixed-frame odom-frame time (cl-transforms:make-identity-vector) (cl-transforms:make-identity-rotation))) @@ -103,7 +103,7 @@ (robot-pose-in-map (btr:link-pose ?robot-instance base-frame)) (odom->base-frame - (cl-tf:transform->transform-stamped + (cl-transforms-stamped:transform->transform-stamped odom-frame base-frame time (cl-transforms:pose->transform robot-pose-in-map))) ;; the current configuration of robot's Bullet world joints @@ -114,7 +114,7 @@ (loop for link in (btr:link-names ?robot-instance) append (unless (equal link base-frame) (list - (cl-tf:transform->transform-stamped + (cl-transforms-stamped:transform->transform-stamped base-frame link time @@ -131,6 +131,37 @@ list-of-base-frame->link list-of-base-frame->virtual-link))))) +(defun get-environment-transforms-from-bullet (&key + (fixed-frame cram-tf:*fixed-frame*) + (time (cut:current-timestamp))) + "Calculate the transform from fixed frame to all links of environment object. +Assumes that the environment is spawned at the `fixed-frame' origin!" + (let ((environment-instance (btr:get-environment-object))) + (if (not environment-instance) + (warn "Environment was not present in the world.~%~ + Not going to GET-TRANSFORMS-FROM-BULLET for the environment.") + (loop for link in (btr:link-names environment-instance) + append (list + (cl-transforms-stamped:transform->transform-stamped + fixed-frame + link + time + (cl-transforms:reference-transform + (btr:link-pose environment-instance link)))))))) + +(defun get-item-transforms-from-bullet (&key + (fixed-frame cram-tf:*fixed-frame*) + (time (cut:current-timestamp))) + "Calculate the transform from fixed frame to all item objects." + (loop for item in (remove-if-not (lambda (object) + (typep object 'btr:item)) + (btr:objects btr:*current-bullet-world*)) + append (list + (cl-transforms-stamped:transform->transform-stamped + fixed-frame + (roslisp-utilities:rosify-underscores-lisp-name (btr:name item)) + time + (cl-transforms:reference-transform (btr:pose item)))))) (defun set-tf-from-bullet (&key (transformer cram-tf:*transformer*) (fixed-frame cram-tf:*fixed-frame*) @@ -140,14 +171,24 @@ (display-warnings nil)) "Sets the transform from fixed frame to odom and then robot and all robot link transforms" - (let ((transforms + (let ((robot-transforms (get-transforms-from-bullet :fixed-frame fixed-frame :odom-frame odom-frame :base-frame base-frame :time time - :display-warnings display-warnings))) - (dolist (transform transforms) + :display-warnings display-warnings)) + (environment-transforms + (get-environment-transforms-from-bullet + :fixed-frame fixed-frame + :time time)) + (item-transforms + (get-item-transforms-from-bullet + :fixed-frame fixed-frame + :time time))) + (dolist (transform (append robot-transforms + environment-transforms + item-transforms)) (cl-tf:set-transform transformer transform diff --git a/cram_3d_world/cram_bullet_reasoning_belief_state/src/process-modules.lisp b/cram_3d_world/cram_bullet_reasoning_belief_state/src/world-state-detecting.lisp similarity index 100% rename from cram_3d_world/cram_bullet_reasoning_belief_state/src/process-modules.lisp rename to cram_3d_world/cram_bullet_reasoning_belief_state/src/world-state-detecting.lisp diff --git a/cram_3d_world/cram_bullet_reasoning_utilities/src/vis-tools.lisp b/cram_3d_world/cram_bullet_reasoning_utilities/src/vis-tools.lisp index 4d13af49e1..b05ed84862 100644 --- a/cram_3d_world/cram_bullet_reasoning_utilities/src/vis-tools.lisp +++ b/cram_3d_world/cram_bullet_reasoning_utilities/src/vis-tools.lisp @@ -83,5 +83,5 @@ '?transform (car (prolog:prolog `(and (cram-robot-interfaces:robot ?robot) - (cram-robot-interfaces:standard-to-particular-gripper-transform + (cram-robot-interfaces:standard<-particular-gripper-transform ?robot ?transform))))))))))))) diff --git a/cram_3d_world/cram_fetch_deliver_plans/cram-fetch-deliver-plans.asd b/cram_3d_world/cram_fetch_deliver_plans/cram-fetch-deliver-plans.asd index e186d88140..fd87734af2 100644 --- a/cram_3d_world/cram_fetch_deliver_plans/cram-fetch-deliver-plans.asd +++ b/cram_3d_world/cram_fetch_deliver_plans/cram-fetch-deliver-plans.asd @@ -44,7 +44,9 @@ cram-common-failures cram-mobile-pick-place-plans + cram-robot-interfaces ; at least for (robot ?r) cram-manipulation-interfaces + cram-location-costmap ; for resetting the costmap cache cram-urdf-projection-reasoning ; for projection-based reasoning cram-urdf-environment-manipulation) diff --git a/cram_3d_world/cram_fetch_deliver_plans/package.xml b/cram_3d_world/cram_fetch_deliver_plans/package.xml index 1f74416f9f..13b90008e0 100644 --- a/cram_3d_world/cram_fetch_deliver_plans/package.xml +++ b/cram_3d_world/cram_fetch_deliver_plans/package.xml @@ -21,6 +21,7 @@ cram_prolog cram_common_failures cram_mobile_pick_place_plans + cram_robot_interfaces cram_manipulation_interfaces cram_urdf_projection_reasoning cram_urdf_environment_manipulation diff --git a/cram_3d_world/cram_fetch_deliver_plans/src/fetch-and-deliver-designators.lisp b/cram_3d_world/cram_fetch_deliver_plans/src/fetch-and-deliver-designators.lisp index a70a150d1f..bfc6ba5397 100644 --- a/cram_3d_world/cram_fetch_deliver_plans/src/fetch-and-deliver-designators.lisp +++ b/cram_3d_world/cram_fetch_deliver_plans/src/fetch-and-deliver-designators.lisp @@ -76,8 +76,10 @@ the `look-pose-stamped'." (spec:property ?action-designator (:target ?some-location-designator)) (desig:current-designator ?some-location-designator ?location-designator) ;; robot-location - (lisp-fun calculate-robot-navigation-goal-towards-target ?location-designator - ?robot-rotated-pose) + (-> (man-int:location-always-reachable ?location-designator) + (lisp-fun cram-tf:robot-current-pose ?robot-rotated-pose) + (lisp-fun calculate-robot-navigation-goal-towards-target ?location-designator + ?robot-rotated-pose)) (desig:designator :location ((:pose ?robot-rotated-pose)) ?robot-location) (desig:designator :action ((:type :turning-towards) (:target ?location-designator) @@ -95,8 +97,12 @@ the `look-pose-stamped'." (spec:property ?action-designator (:location ?some-location-designator)) (desig:current-designator ?some-location-designator ?location-designator) ;; object - (desig:desig-prop ?location-designator (:in ?some-object-designator)) + (once (or (spec:property ?location-designator (:in ?some-object-designator)) + (spec:property ?location-designator (:above ?some-object-designator)))) (desig:current-designator ?some-object-designator ?object-designator) + ;; location of the object that we are trying to access + (once (or (spec:property ?object-designator (:location ?object-location-desig)) + (equal ?object-location-desig nil))) ;; arm (-> (spec:property ?action-designator (:arm ?arm)) (true) @@ -110,7 +116,8 @@ the `look-pose-stamped'." (once (or (spec:property ?action-designator (:distance ?distance)) (equal ?distance NIL))) ;; robot-location - (once (or (and (spec:property ?action-designator (:robot-location ?some-robot-location)) + (once (or (and (spec:property ?action-designator (:robot-location + ?some-robot-location)) (desig:current-designator ?robot-location ?robot-location)) (desig:designator :location ((:reachable-for ?robot) (:arm ?arm) @@ -118,6 +125,7 @@ the `look-pose-stamped'." ?robot-location))) (desig:designator :action ((:type ?action-type) (:object ?object-designator) + (:object-location ?object-location-desig) (:arm ?arm) (:distance ?distance) (:robot-location ?robot-location)) @@ -128,21 +136,41 @@ the `look-pose-stamped'." ?resolved-action-designator)) (spec:property ?action-designator (:type :searching)) (rob-int:robot ?robot) - ;; object - (spec:property ?action-designator (:object ?some-object-designator)) - (desig:current-designator ?some-object-designator ?object-designator) - ;; location - (spec:property ?action-designator (:location ?some-location-designator)) - (desig:current-designator ?some-location-designator ?location-designator) + ;; searching for an object or for a location + (once (or (spec:property ?action-designator (:object ?some-obj-desig)) + (and (spec:property ?action-designator (:location ?some-loc-desig)) + (man-int:location-reference-object ?some-loc-desig + ?some-obj-desig)))) + (desig:current-designator ?some-obj-desig ?object-designator) + ;; context + (once (or (spec:property ?action-designator (:context ?context)) + (equal ?context NIL))) + ;; where to look for the given object or the given location's reference object + (-> (and (spec:property ?object-designator (:location ?some-location-designator)) + (not (equal ?some-location-designator NIL))) + (and (desig:current-designator ?some-location-designator ?location-designator) + (equal ?object-designator ?object-designator-with-location)) + (and (spec:property ?object-designator (:type ?object-type)) + (rob-int:environment-name ?environment) + (lisp-fun man-int:get-object-likely-location + ?object-type ?environment nil ?context ?location-designator) + (equal ?new-props ((:location ?location-designator))) + (lisp-fun desig:extend-designator-properties + ?object-designator ?new-props + ?object-designator-with-location) + (lisp-pred desig:equate + ?object-designator ?object-designator-with-location))) ;; robot-location - (once (or (and (spec:property ?action-designator (:robot-location ?some-location-to-stand)) - (desig:current-designator ?some-location-to-stand ?location-to-stand)) + (once (or (and (spec:property ?action-designator (:robot-location + ?some-location-to-stand)) + (desig:current-designator ?some-location-to-stand + ?location-to-stand)) (desig:designator :location ((:visible-for ?robot) (:location ?location-designator) (:object ?object-designator)) ?location-to-stand))) (desig:designator :action ((:type :searching) - (:object ?object-designator) + (:object ?object-designator-with-location) (:location ?location-designator) (:robot-location ?location-to-stand)) ?resolved-action-designator)) @@ -155,26 +183,52 @@ the `look-pose-stamped'." (spec:property ?action-designator (:object ?some-object-designator)) (desig:current-designator ?some-object-designator ?object-designator) ;; arms - (-> (desig:desig-prop ?action-designator (:arms ?arms)) + (-> (spec:property ?action-designator (:arms ?arms)) (true) - (equal ?arms NIL)) + ;; (equal ?arms NIL) + (setof ?arm (man-int:robot-free-hand ?robot ?arm) ?arms)) ;; grasps - (-> (desig:desig-prop ?action-designator (:grasps ?grasps)) + (-> (spec:property ?action-designator (:grasps ?grasps)) (true) + ;; we do not ask for grasps because they are arm-specific! + ;; therefore, projection reasoning is essential for these plans + ;; (lisp-fun man-int:get-action-grasps ?object-type ?arm ?object-transform + ;; ?grasps) (equal ?grasps NIL)) ;; robot-location - (once (or (and (spec:property ?action-designator (:robot-location ?some-location-designator)) - (desig:current-designator ?some-location-designator ?robot-location-designator)) + (once (or (and (spec:property ?action-designator (:robot-location + ?some-location-designator)) + (desig:current-designator ?some-location-designator + ?robot-location-designator)) (desig:designator :location ((:reachable-for ?robot) ;; ?arm is not available because we're sampling ;; (:arm ?arm) - (:object ?object-designator)) + (:object ?object-designator) + ;; have to add the visibility + ;; constraint as he reperceives + ;; each time before grasping + (:visible-for ?robot)) ?robot-location-designator))) + ;; if the object is in the hand or its reference object is in the hand + ;; we need to bring the hand closer to the other hand, e.g., bring to front + (-> (man-int:object-or-its-reference-in-hand ?object-designator ?object-hand) + (equal ?object-in-hand T) + (and (equal ?object-in-hand NIL) + (equal ?object-hand NIL))) ;; look-location - (once (or (and (spec:property ?action-designator (:look-location ?some-look-loc-desig)) - (desig:current-designator ?some-look-loc-desig ?look-location-designator)) - (desig:designator :location ((:of ?object-designator)) - ?look-location-designator))) + (once (or (and (spec:property ?action-designator (:look-location + ?some-look-loc-desig)) + (desig:current-designator ?some-look-loc-desig + ?look-location-designator)) + (-> (or (equal ?object-in-hand NIL) (equal ?object-hand NIL)) + (desig:designator :location ((:of ?object-designator)) + ?look-location-designator) + (and (desig:designator :object ((:part-of ?robot) + (:link :robot-tool-frame) + (:which-link ?object-hand)) + ?object-hand-designator) + (desig:designator :location ((:of ?object-hand-designator)) + ?look-location-designator))))) ;; pick-up-action (once (or (desig:desig-prop ;; spec:property ?action-designator (:pick-up-action ?some-pick-up-action-designator)) @@ -186,7 +240,9 @@ the `look-pose-stamped'." (:grasps ?grasps) (:robot-location ?robot-location-designator) (:look-location ?look-location-designator) - (:pick-up-action ?pick-up-action-designator)) + (:pick-up-action ?pick-up-action-designator) + (:object-in-hand ?object-in-hand) + (:object-hand ?object-hand)) ?resolved-action-designator)) @@ -199,12 +255,33 @@ the `look-pose-stamped'." ;; arm (once (or (spec:property ?action-designator (:arm ?arm)) (equal ?arm NIL))) + ;; context + (once (or (spec:property ?action-designator (:context ?context)) + (equal ?context NIL))) ;; target - (spec:property ?action-designator (:target ?some-location-designator)) - (desig:current-designator ?some-location-designator ?location-designator) + (-> (and (spec:property ?action-designator (:target ?some-location-designator)) + (not (equal ?some-location-designator NIL))) + (desig:current-designator ?some-location-designator ?location-designator) + (and (spec:property ?object-designator (:type ?object-type)) + (rob-int:environment-name ?environment) + (lisp-fun man-int:get-object-destination + ?object-type ?environment nil ?context ?location-designator))) + ;; target stable? or have to check stability first? + (-> (man-int:location-always-stable ?location-designator) + (equal ?target-stable T) + (equal ?target-stable NIL)) + ;; also, the target location can be w.r.t. other object, which can be in hand, + ;; in which case we need to bring the other object hand closer + (-> (and (man-int:location-reference-object ?location-designator ?target-obj) + (cpoe:object-in-hand ?target-obj ?target-hand)) + (equal ?target-in-hand T) + (and (equal ?target-in-hand NIL) + (equal ?target-hand NIL))) ;; robot-location - (once (or (and (spec:property ?action-designator (:robot-location ?some-robot-loc-desig)) - (desig:current-designator ?some-robot-loc-desig ?robot-location-designator)) + (once (or (and (spec:property ?action-designator (:robot-location + ?some-robot-loc-desig)) + (desig:current-designator ?some-robot-loc-desig + ?robot-location-designator)) (desig:designator :location ((:reachable-for ?robot) (:object ?object-designator) (:location ?location-designator)) @@ -219,21 +296,39 @@ the `look-pose-stamped'." (:arm ?arm) (:target ?location-designator) (:robot-location ?robot-location-designator) - (:place-action ?place-action-designator)) + (:place-action ?place-action-designator) + (:target-stable ?target-stable) + (:target-in-hand ?target-in-hand) + (:target-hand ?target-hand)) ?resolved-action-designator)) - (<- (desig:action-grounding ?action-designator (transport ?resolved-action-designator)) + (<- (desig:action-grounding ?action-designator (transport + ?resolved-action-designator)) (spec:property ?action-designator (:type :transporting)) ;; object (spec:property ?action-designator (:object ?some-object-designator)) (desig:current-designator ?some-object-designator ?object-designator) + ;; context + (once (or (spec:property ?action-designator (:context ?context)) + (equal ?context NIL))) ;; search location - (spec:property ?action-designator (:location ?some-search-loc-desig)) - (desig:current-designator ?some-search-loc-desig ?search-location-designator) - (-> (desig:desig-prop ?search-location-designator (:in ?_)) - (equal ?fetching-location-accessible NIL) - (equal ?fetching-location-accessible T)) + (-> (and (spec:property ?object-designator (:location ?some-search-loc-desig)) + (not (equal ?some-search-loc-desig NIL))) + (and (desig:current-designator ?some-search-loc-desig + ?search-location-designator) + (equal ?object-designator-with-location ?object-designator)) + (and (spec:property ?object-designator (:type ?object-type)) + (rob-int:environment-name ?environment) + (lisp-fun man-int:get-object-likely-location + ?object-type ?environment nil ?context + ?search-location-designator) + (equal ?new-props ((:location ?search-location-designator))) + (lisp-fun desig:extend-designator-properties + ?object-designator ?new-props + ?object-designator-with-location) + (lisp-pred desig:equate + ?object-designator ?object-designator-with-location))) ;; search location robot base (-> (desig:desig-prop ?action-designator (:search-robot-location ?some-s-robot-loc-desig)) @@ -247,21 +342,24 @@ the `look-pose-stamped'." ?fetch-robot-location-designator) (equal ?fetch-robot-location-designator NIL)) ;; arms - (-> (desig:desig-prop ?action-designator (:arms ?arms)) + (-> (spec:property ?action-designator (:arms ?arms)) (true) (equal ?arms NIL)) ;; grasps - (-> (desig:desig-prop ?action-designator (:grasps ?grasps)) + (-> (spec:property ?action-designator (:grasps ?grasps)) (true) (equal ?grasps NIL)) - ;; target location - (spec:property ?action-designator - (:target ?some-delivering-location-designator)) - (desig:current-designator ?some-delivering-location-designator - ?delivering-location-designator) - (-> (desig:desig-prop ?delivering-location-designator (:in ?_)) - (equal ?delivering-location-accessible NIL) - (equal ?delivering-location-accessible T)) + ;; deliver location + (-> (and (spec:property ?action-designator + (:target ?some-delivering-location-designator)) + (not (equal ?some-delivering-location-designator NIL))) + (desig:current-designator ?some-delivering-location-designator + ?delivering-location-designator) + (and (spec:property ?object-designator (:type ?object-type)) + (rob-int:environment-name ?environment) + (lisp-fun man-int:get-object-destination + ?object-type ?environment nil ?context + ?delivering-location-designator))) ;; deliver location robot base (-> (desig:desig-prop ?action-designator (:deliver-robot-location ?some-d-robot-loc-desig)) @@ -269,15 +367,16 @@ the `look-pose-stamped'." ?deliver-robot-location-designator) (equal ?deliver-robot-location-designator NIL)) ;; resulting action desig - (desig:designator :action ((:type :transporting) - (:object ?object-designator) - (:search-location ?search-location-designator) - (:search-robot-location ?search-robot-location-designator) - (:fetch-robot-location ?fetch-robot-location-designator) - (:arms ?arms) - (:grasps ?grasps) - (:deliver-location ?delivering-location-designator) - (:deliver-robot-location ?deliver-robot-location-designator) - (:search-location-accessible ?fetching-location-accessible) - (:delivery-location-accessible ?delivering-location-accessible)) - ?resolved-action-designator))) + (desig:designator + :action + ((:type :transporting) + (:object ?object-designator-with-location) + (:context ?context) + (:search-location ?search-location-designator) + (:search-robot-location ?search-robot-location-designator) + (:fetch-robot-location ?fetch-robot-location-designator) + (:arms ?arms) + (:grasps ?grasps) + (:deliver-location ?delivering-location-designator) + (:deliver-robot-location ?deliver-robot-location-designator)) + ?resolved-action-designator))) diff --git a/cram_3d_world/cram_fetch_deliver_plans/src/fetch-and-deliver-plans.lisp b/cram_3d_world/cram_fetch_deliver_plans/src/fetch-and-deliver-plans.lisp index 9decb8f162..f4ce5bb2ab 100644 --- a/cram_3d_world/cram_fetch_deliver_plans/src/fetch-and-deliver-plans.lisp +++ b/cram_3d_world/cram_fetch_deliver_plans/src/fetch-and-deliver-plans.lisp @@ -37,9 +37,7 @@ if yes, perform GOING action while ignoring failures." (exe:perform (desig:an action - (type positioning-arm) - (left-configuration park) - (right-configuration park))) + (type parking-arms))) (proj-reasoning:check-navigating-collisions ?navigation-location) (setf ?navigation-location (desig:current-desig ?navigation-location)) @@ -49,6 +47,8 @@ if yes, perform GOING action while ignoring failures." (roslisp:ros-warn (pp-plans navigate) "Low-level navigation failed: ~a~%.Ignoring anyway." e) (return))) + ;; going goal should not be used because we might want to reposition + ;; the base within the same location costmap (exe:perform (desig:an action (type going) (target ?navigation-location))))) @@ -84,26 +84,34 @@ turn the robot base such that it looks in the direction of target and look again (exe:perform (desig:an action (type navigating) (location ?robot-location))) - (exe:perform (desig:an action - (type looking) - (direction forward)))) + (let ((?goal `(cpoe:looking-at :forward))) + (exe:perform (desig:an action + (type looking) + (direction forward) + (goal ?goal))))) (cpl:retry)) (roslisp:ros-warn (pp-plans turn-towards) "Turning around didn't work :'(~%") (cpl:fail 'common-fail:looking-high-level-failure))) - (exe:perform (desig:an action - (type looking) - (target ?look-target))))))) + (let (;; (?goal `(cpoe:looking-at ,?look-target)) + ) + (exe:perform (desig:an action + (type looking) + (target ?look-target) + ;; (goal ?goal) + ))))))) (defun manipulate-environment (&key ((:type action-type)) ((:object ?object-to-manipulate)) + ((:object-location ?object-location)) ((:arm ?arm)) ((:distance ?distance)) ((:robot-location ?manipulate-robot-location)) &allow-other-keys) (declare (type keyword action-type ?arm) (type desig:object-designator ?object-to-manipulate) + (type (or desig:location-designator null) ?object-location) (type (or number null) ?distance) ;; here, ?manipulate-robot-location can only be null within the function ;; but one should not pass a NULL location as argument, @@ -112,6 +120,15 @@ turn the robot base such that it looks in the direction of target and look again "Navigate to reachable location, check if opening/closing trajectory causes collisions, if yes, relocate and retry, if no collisions, open or close container." + ;; Making the containing location accessible before accessing the object + (when (and ?object-location + (eq action-type :accessing)) + (let ((?goal `(cpoe:location-accessible ,?object-location))) + (exe:perform (desig:an action + (type accessing) + (location ?object-location) + (goal ?goal))))) + (cpl:with-failure-handling ((desig:designator-error (e) (roslisp:ros-warn (fd-plans environment) "~a~%Propagating up." e) @@ -130,9 +147,11 @@ if yes, relocate and retry, if no collisions, open or close container." (:error-object-or-string e :warning-namespace (fd-plans environment) :rethrow-failure 'common-fail:environment-manipulation-impossible) - (exe:perform (desig:an action - (type opening-gripper) - (gripper (left right)))) + (let ((?goal `(cpoe:gripper-opened (:left :right)))) + (exe:perform (desig:an action + (type opening-gripper) + (gripper (left right)) + (goal ?goal)))) (roslisp:ros-info (fd-plans environment) "Relocating...")))) ;; navigate, open / close @@ -142,23 +161,44 @@ if yes, relocate and retry, if no collisions, open or close container." (let ((manipulation-action (ecase action-type - (:accessing (desig:an action - (type opening) - (arm ?arm) - (object ?object-to-manipulate) - (desig:when ?distance - (distance ?distance)))) - (:sealing (desig:an action - (type closing) - (arm ?arm) - (object ?object-to-manipulate) - (desig:when ?distance - (distance ?distance))))))) + (:accessing + (let ((?goal + (if ?distance + `(cpoe:container-state ,?object-to-manipulate ,?distance) + `(cpoe:container-state ,?object-to-manipulate :open)))) + (desig:an action + (type opening) + (arm ?arm) + (object ?object-to-manipulate) + (desig:when ?distance + (distance ?distance)) + (goal ?goal)))) + (:sealing + (let ((?goal + (if ?distance + `(cpoe:container-state ,?object-to-manipulate ,?distance) + `(cpoe:container-state ,?object-to-manipulate :closed)))) + (desig:an action + (type closing) + (arm ?arm) + (object ?object-to-manipulate) + (desig:when ?distance + (distance ?distance)) + (goal ?goal))))))) (proj-reasoning:check-environment-manipulation-collisions manipulation-action) (setf manipulation-action (desig:current-desig manipulation-action)) - (exe:perform manipulation-action)))))) + (exe:perform manipulation-action))))) + + ;; Seal the object containing location after sealing the object + (when (and ?object-location + (eq action-type :sealing)) + (let ((?goal `(cpoe:location-reset ,?object-location))) + (exe:perform (desig:an action + (type sealing) + (location ?object-location) + (goal ?goal)))))) (defun search-for-object (&key @@ -203,21 +243,25 @@ retries with different search location or robot base location." (((or common-fail:navigation-goal-in-collision common-fail:looking-high-level-failure common-fail:perception-low-level-failure) (e) + (costmap:reset-costmap-cache) (common-fail:retry-with-loc-designator-solutions ?robot-location robot-location-retries (:error-object-or-string e :warning-namespace (fd-plans search-for-object) - :reset-designators (list ?search-location) - :rethrow-failure 'common-fail:object-nowhere-to-be-found)))) + :reset-designators (list ?search-location ?robot-location) + :rethrow-failure 'common-fail:object-nowhere-to-be-found) + ;; go up with torso to look from higher up + (let ((?goal `(cpoe:torso-at :upper-limit))) + (exe:perform (desig:an action + (type moving-torso) + (joint-angle upper-limit) + (goal ?goal))))))) ;; navigate (exe:perform (desig:an action (type navigating) (location ?robot-location))) - ;; go up with torso to look from higher up - (exe:perform - (desig:an action (type moving-torso) (joint-angle upper-limit))) (cpl:with-retry-counters ((move-torso-retries 1)) (cpl:with-failure-handling @@ -225,8 +269,11 @@ retries with different search location or robot base location." (cpl:do-retry move-torso-retries (roslisp:ros-warn (pick-and-place perceive) "~a" e) ;; if a failure happens, try to go with the torso a bit more down - (exe:perform - (desig:an action (type moving-torso) (joint-angle middle))) + (let ((?goal `(cpoe:torso-at :middle))) + (exe:perform (desig:an action + (type moving-torso) + (joint-angle middle) + (goal ?goal)))) (cpl:retry)))) ;; if perception action fails, try another `?search-location' and retry @@ -241,9 +288,13 @@ retries with different search location or robot base location." :warning-namespace (fd-plans search-for-object) :reset-designators (list ?robot-location))))) - (exe:perform (desig:an action - (type turning-towards) - (target ?search-location))) + (let (;; (?goal `(cpoe:looking-at ,?search-location)) + ) + (exe:perform (desig:an action + (type turning-towards) + (target ?search-location) + ;; (goal ?goal) + ))) (exe:perform (desig:an action (type perceiving) (object ?object-designator))))))))))))) @@ -257,6 +308,8 @@ retries with different search location or robot base location." ((:robot-location ?pick-up-robot-location)) ((:look-location ?look-location)) pick-up-action + object-in-hand + object-hand &allow-other-keys) (declare (type desig:object-designator ?object-designator) (type list ?arms ?grasps) @@ -297,14 +350,43 @@ and using the grasp and arm specified in `pick-up-action' (if not NIL)." (exe:perform (desig:an action (type navigating) (location ?pick-up-robot-location))) - (exe:perform (desig:an action - (type turning-towards) - (target ?look-location))) + + ;; if fetch location is in hand, we have a handover, + ;; so move the source hand closer + (when object-in-hand + (let ((?goal + (case object-hand + (:left `(cpoe:arms-positioned-at :hand-over nil)) + (:right `(cpoe:arms-positioned-at nil :hand-over)) + (t `(cpoe:arms-positioned-at nil nil))))) + (exe:perform + (desig:an action + (type positioning-arm) + (desig:when (eql object-hand :left) + (left-configuration hand-over)) + (desig:when (eql object-hand :right) + (right-configuration hand-over)) + (goal ?goal))) + (desig:reset ?look-location))) + + (let (;; (?goal `(cpoe:looking-at ,?look-location)) + ) + (exe:perform (desig:an action + (type turning-towards) + (target ?look-location) + ;; (goal ?goal) + ))) (cpl:with-retry-counters ((regrasping-retries 1)) (cpl:with-failure-handling ((common-fail:gripper-low-level-failure (e) (roslisp:ros-warn (fd-plans fetch) "Misgrasp happened: ~a~%" e) + (exe:perform (desig:an action + (type releasing) + (gripper left))) + (exe:perform (desig:an action + (type releasing) + (gripper right))) (cpl:do-retry regrasping-retries (roslisp:ros-info (fd-plans fetch) "Reperceiving and repicking...") (cpl:retry)) @@ -330,7 +412,7 @@ and using the grasp and arm specified in `pick-up-action' (if not NIL)." arm-retries (:error-object-or-string (format NIL "Manipulation failed: ~a.~%Next." e) - :warning-namespace (kvr plans) + :warning-namespace (fd-plans fetch) :rethrow-failure 'common-fail:object-unreachable) (setf ?arm (cut:lazy-car ?arms))))) @@ -346,37 +428,43 @@ and using the grasp and arm specified in `pick-up-action' (if not NIL)." grasp-retries (:error-object-or-string (format NIL "Picking up failed: ~a.~%Next" e) - :warning-namespace (kvr plans)) + :warning-namespace (fd-plans fetch)) (setf ?grasp (cut:lazy-car ?grasps))))) - (let ((pick-up-action - ;; if pick-up-action already exists, - ;; use its params for picking up - (or (when pick-up-action - (let* ((referenced-action-desig - (desig:reference pick-up-action)) - (?arm - (desig:desig-prop-value - referenced-action-desig - :arm)) - (?grasp - (desig:desig-prop-value - referenced-action-desig - :grasp))) - (desig:an action - (type picking-up) - (arm ?arm) - (grasp ?grasp) - (object - ?more-precise-perceived-object-desig)))) - (desig:an action - (type picking-up) - (desig:when ?arm - (arm ?arm)) - (desig:when ?grasp - (grasp ?grasp)) - (object - ?more-precise-perceived-object-desig))))) + (let* ((?goal + `(cpoe:object-in-hand + ,?more-precise-perceived-object-desig + :left-or-right)) + (pick-up-action + ;; if pick-up-action already exists, + ;; use its params for picking up + (or (when pick-up-action + (let* ((referenced-action-desig + (desig:reference pick-up-action)) + (?arm + (desig:desig-prop-value + referenced-action-desig + :arm)) + (?grasp + (desig:desig-prop-value + referenced-action-desig + :grasp))) + (desig:an action + (type picking-up) + (arm ?arm) + (grasp ?grasp) + (object + ?more-precise-perceived-object-desig) + (goal ?goal)))) + (desig:an action + (type picking-up) + (desig:when ?arm + (arm ?arm)) + (desig:when ?grasp + (grasp ?grasp)) + (object + ?more-precise-perceived-object-desig) + (goal ?goal))))) (setf pick-up-action (desig:current-desig pick-up-action)) (proj-reasoning:check-picking-up-collisions pick-up-action) @@ -396,6 +484,9 @@ and using the grasp and arm specified in `pick-up-action' (if not NIL)." ((:target ?target-location)) ((:robot-location ?target-robot-location)) place-action + target-stable + target-in-hand + target-hand &allow-other-keys) (declare (type desig:object-designator ?object-designator) (type (or keyword null) ?arm) @@ -415,10 +506,13 @@ If a failure happens, try a different `?target-location' or `?target-robot-locat (cpl:fail 'common-fail:delivering-failed :description "Some designator could not be resolved."))) - (cpl:with-retry-counters ((outer-target-location-retries 2)) + (cpl:with-retry-counters ((outer-target-location-retries 4)) (cpl:with-failure-handling (((or desig:designator-error common-fail:object-undeliverable) (e) + (roslisp:ros-warn (fd-plans deliver) + "outer-target-location-retries ~a~%" + (cpl:get-counter outer-target-location-retries)) (common-fail:retry-with-loc-designator-solutions ?target-location outer-target-location-retries @@ -434,12 +528,16 @@ If a failure happens, try a different `?target-location' or `?target-robot-locat (((or common-fail:navigation-goal-in-collision common-fail:object-undeliverable common-fail:manipulation-low-level-failure) (e) + (roslisp:ros-warn (fd-plans deliver) + "relocation-for-ik-retries ~A~%" + (cpl:get-counter relocation-for-ik-retries)) (common-fail:retry-with-loc-designator-solutions ?target-robot-location relocation-for-ik-retries (:error-object-or-string (format NIL "Object is undeliverable from base location.~%~a" e) :warning-namespace (fd-plans deliver) + :reset-designators (list ?target-location) :rethrow-failure 'common-fail:object-undeliverable)))) ;; navigate @@ -448,7 +546,7 @@ If a failure happens, try a different `?target-location' or `?target-robot-locat (location ?target-robot-location))) ;; take a new `?target-location' sample if a failure happens - (cpl:with-retry-counters ((target-location-retries 9)) + (cpl:with-retry-counters ((target-location-retries 2)) (cpl:with-failure-handling (((or common-fail:looking-high-level-failure common-fail:object-unreachable @@ -463,10 +561,32 @@ If a failure happens, try a different `?target-location' or `?target-robot-locat (roslisp:ros-warn (fd-plans deliver) "Retrying with new placing location ...~%")))) + ;; if target is in hand, we have a handover, + ;; so move target hand closer + (when target-in-hand + (let ((?goal + (case target-hand + (:left `(cpoe:arms-positioned-at :hand-over nil)) + (:right `(cpoe:arms-positioned-at nil :hand-over)) + (t `(cpoe:arms-positioned-at nil nil))))) + (exe:perform + (desig:an action + (type positioning-arm) + (desig:when (eql target-hand :left) + (left-configuration hand-over)) + (desig:when (eql target-hand :right) + (right-configuration hand-over)) + (goal ?goal))) + (desig:reset ?target-location))) + ;; look - (exe:perform (desig:an action - (type turning-towards) - (target ?target-location))) + (let (;; (?goal `(cpoe:looking-at ,?target-location)) + ) + (exe:perform (desig:an action + (type turning-towards) + (target ?target-location) + ;; (goal ?goal) + ))) ;; place (let ((place-action @@ -477,17 +597,25 @@ If a failure happens, try a different `?target-location' or `?target-robot-locat (desig:desig-prop-value referenced-action-desig :arm)) (?projected-target-location (desig:desig-prop-value referenced-action-desig :target))) - (desig:an action - (type placing) - (arm ?arm) - (object ?object-designator) - (target ?projected-target-location)))) - (desig:an action - (type placing) - (desig:when ?arm - (arm ?arm)) - (object ?object-designator) - (target ?target-location))))) + (let ((?goal `(cpoe:object-at-location + ,?object-designator + ,?projected-target-location))) + (desig:an action + (type placing) + (arm ?arm) + (object ?object-designator) + (target ?projected-target-location) + (goal ?goal))))) + (let ((?goal `(cpoe:object-at-location + ,?object-designator + ,?target-location))) + (desig:an action + (type placing) + (desig:when ?arm + (arm ?arm)) + (object ?object-designator) + (target ?target-location) + (goal ?goal)))))) ;; test if the placing trajectory is reachable and not colliding (setf place-action (desig:current-desig place-action)) @@ -496,20 +624,18 @@ If a failure happens, try a different `?target-location' or `?target-robot-locat ;; test if the placing pose is a good one -- not falling on the floor ;; test function throws a high-level-failure if not good pose - (proj-reasoning:check-placing-pose-stability - ?object-designator ?target-location) + (unless target-stable + (proj-reasoning:check-placing-pose-stability + ?object-designator ?target-location)) + + (exe:perform place-action) - (exe:perform place-action)))))))))) + (desig:current-desig ?object-designator)))))))))) (defun drop-at-sink () (let ((?base-pose-in-map - ;; (cl-transforms-stamped:make-pose-stamped - ;; cram-tf:*fixed-frame* - ;; 0.0 - ;; (cl-transforms:make-3d-vector 0.7 -0.2 0) - ;; (cl-transforms:make-identity-rotation)) (cl-transforms-stamped:make-pose-stamped cram-tf:*fixed-frame* 0.0 @@ -529,21 +655,22 @@ If a failure happens, try a different `?target-location' or `?target-robot-locat (exe:perform (desig:an action (type going) - (target (desig:a location (pose ?base-pose-in-map))))))) - (cpl:with-failure-handling - ((common-fail:manipulation-low-level-failure (e) - (declare (ignore e)) - (return))) - (exe:perform - (desig:an action - (type placing) - ;; (target (desig:a location - ;; (pose ?placing-pose))) - )))) + (target (desig:a location (pose ?base-pose-in-map)))))) + (cpl:with-failure-handling + ((common-fail:manipulation-low-level-failure (e) + (declare (ignore e)) + (return))) + (exe:perform + (desig:an action + (type placing) + ;; (target (desig:a location + ;; (pose ?placing-pose))) + ))))) (defun transport (&key ((:object ?object-designator)) + ((:context ?context)) ((:search-location ?search-location)) ((:search-robot-location ?search-base-location)) ((:fetch-robot-location ?fetch-robot-location)) @@ -551,76 +678,113 @@ If a failure happens, try a different `?target-location' or `?target-robot-locat ((:grasps ?grasps)) ((:deliver-location ?delivering-location)) ((:deliver-robot-location ?deliver-robot-location)) - search-location-accessible - delivery-location-accessible &allow-other-keys) - (unless search-location-accessible + ;; if we are not sure about the exact location of deliver-location, find it + (let ((?goal `(man-int:location-certain ,?delivering-location))) + (exe:perform (desig:an action + (type searching) + (location ?delivering-location) + (goal ?goal)))) + ;; if deliver-location is inside a container, open the container + (let ((?goal `(cpoe:location-accessible ,?delivering-location))) (exe:perform (desig:an action (type accessing) - (location ?search-location)))) - - (unwind-protect - (let ((?perceived-object-designator - (exe:perform (desig:an action - (type searching) - (object ?object-designator) - (location ?search-location) - (desig:when ?search-base-location - (robot-location ?search-base-location)))))) - (roslisp:ros-info (pp-plans transport) - "Found object of type ~a." - (desig:desig-prop-value ?perceived-object-designator :type)) - - ;; If running on the real robot, execute below task tree in projection - ;; N times first, then pick the best parameterization - ;; and use that parameterization in the real world. - ;; If running in projection, just execute the task tree below as normal. - (let (?fetch-pick-up-action ?deliver-place-action) - (proj-reasoning:with-projected-task-tree - (?fetch-robot-location ?fetch-pick-up-action - ?deliver-robot-location ?deliver-place-action) - 3 - #'proj-reasoning:pick-best-parameters-by-distance - - (let ((?fetched-object - (exe:perform (desig:an action - (type fetching) - (desig:when ?arms - (arms ?arms)) - (desig:when ?grasps - (grasps ?grasps)) - (object ?perceived-object-designator) - (desig:when ?fetch-robot-location - (robot-location ?fetch-robot-location)) - (pick-up-action ?fetch-pick-up-action))))) - (roslisp:ros-info (pp-plans transport) "Fetched the object.") - - (cpl:with-failure-handling - ((common-fail:delivering-failed (e) - (declare (ignore e)) - (drop-at-sink) - ;; (return) - )) - (unless delivery-location-accessible - (exe:perform (desig:an action - (type accessing) - (location ?delivering-location)))) - (unwind-protect - (exe:perform (desig:an action - (type delivering) - ;; (desig:when ?arm - ;; (arm ?arm)) - (object ?fetched-object) - (target ?delivering-location) - (desig:when ?deliver-robot-location - (robot-location ?deliver-robot-location)) - (place-action ?deliver-place-action))) - (unless delivery-location-accessible - (exe:perform (desig:an action - (type sealing) - (location ?delivering-location)))))))))) + (location ?delivering-location) + (goal ?goal)))) - (unless search-location-accessible - (exe:perform (desig:an action - (type sealing) - (location ?search-location)))))) + ;; if we are not sure about the exact location of search-location, find it + (let ((?goal `(man-int:location-certain ,?search-location))) + (exe:perform (desig:an action + (type searching) + (location ?search-location) + (goal ?goal)))) + + ;; if search-location is inside a container, open the container + (let ((?goal `(cpoe:location-accessible ,?search-location))) + (exe:perform (desig:an action + (type accessing) + (location ?search-location) + (goal ?goal)))) + + ;; search for the object to find it's exact pose + (exe:perform (desig:an action + (type searching) + (object ?object-designator) + (desig:when ?context + (context ?context)) + (desig:when ?search-base-location + (robot-location ?search-base-location)))) + (setf ?object-designator (desig:current-desig ?object-designator)) + (roslisp:ros-info (pp-plans transport) + "Found object of type ~a." + (desig:desig-prop-value ?object-designator :type)) + + ;; If running on the real robot, execute below task tree + ;; in projection N times first, then pick the best parameterization + ;; and use that parameterization in the real world. + ;; If running in projection, + ;; just execute the task tree below as normal. + (let (?fetch-pick-up-action ?deliver-place-action) + (proj-reasoning:with-projected-task-tree + (?fetch-robot-location + ?fetch-pick-up-action + ?deliver-robot-location + ?deliver-place-action) + 3 + #'proj-reasoning:pick-best-parameters-by-distance + + ;; fetch the object + (let ((?fetch-goal + `(cpoe:object-in-hand + ,?object-designator :left-or-right))) + (exe:perform (desig:an action + (type fetching) + (desig:when ?arms + (arms ?arms)) + (desig:when ?grasps + (grasps ?grasps)) + (object ?object-designator) + (desig:when ?fetch-robot-location + (robot-location ?fetch-robot-location)) + (pick-up-action ?fetch-pick-up-action) + (goal ?fetch-goal)))) + (setf ?object-designator (desig:current-desig ?object-designator)) + (roslisp:ros-info (pp-plans transport) "Fetched the object.") + + (cpl:with-failure-handling + ((common-fail:delivering-failed (e) + (declare (ignore e)) + ;; (return) + (drop-at-sink))) + + ;; deliver at destination + (let ((?goal + `(cpoe:object-at-location + ,?object-designator ,?delivering-location))) + (exe:perform (desig:an action + (type delivering) + ;; (desig:when ?arm + ;; (arm ?arm)) + (object ?object-designator) + (context ?context) + (target ?delivering-location) + (desig:when ?deliver-robot-location + (robot-location ?deliver-robot-location)) + (place-action ?deliver-place-action) + (goal ?goal))))))) + + ;; reset the fetch location + (let ((?goal `(cpoe:location-reset ,?search-location))) + (exe:perform (desig:an action + (type sealing) + (location ?search-location) + (goal ?goal)))) + + ;; reset the target location + (let ((?goal `(cpoe:location-reset ,?delivering-location))) + (exe:perform (desig:an action + (type sealing) + (location ?delivering-location) + (goal ?goal)))) + + (desig:current-desig ?object-designator)) diff --git a/cram_3d_world/cram_urdf_environment_manipulation/cram-urdf-environment-manipulation.asd b/cram_3d_world/cram_urdf_environment_manipulation/cram-urdf-environment-manipulation.asd index 35880e60c5..d61d70d998 100644 --- a/cram_3d_world/cram_urdf_environment_manipulation/cram-urdf-environment-manipulation.asd +++ b/cram_3d_world/cram_urdf_environment_manipulation/cram-urdf-environment-manipulation.asd @@ -56,8 +56,7 @@ cram-bullet-reasoning-belief-state cram-bullet-reasoning-utilities - ;; cram-robot-pose-gaussian-costmap - ;; cram-occupancy-grid-costmap + cram-robot-pose-gaussian-costmap cram-location-costmap) :components ((:module "src" diff --git a/cram_3d_world/cram_urdf_environment_manipulation/package.xml b/cram_3d_world/cram_urdf_environment_manipulation/package.xml index c2de27a213..133f8200fa 100644 --- a/cram_3d_world/cram_urdf_environment_manipulation/package.xml +++ b/cram_3d_world/cram_urdf_environment_manipulation/package.xml @@ -34,6 +34,5 @@ cram_bullet_reasoning_belief_state cram_bullet_reasoning_utilities cram_robot_pose_gaussian_costmap - cram_occupancy_grid_costmap cram_location_costmap diff --git a/cram_3d_world/cram_urdf_environment_manipulation/src/action-designators.lisp b/cram_3d_world/cram_urdf_environment_manipulation/src/action-designators.lisp index e6301b9da7..189e4ee777 100644 --- a/cram_3d_world/cram_urdf_environment_manipulation/src/action-designators.lisp +++ b/cram_3d_world/cram_urdf_environment_manipulation/src/action-designators.lisp @@ -86,6 +86,11 @@ (lisp-fun btr:object ?world ?btr-environment ?environment-object) (lisp-fun btr:name ?environment-object ?environment-name) + (btr:joint-state ?world ?environment-name ?joint-name ?current-state) + (-> (equal ?action-type :opening) + (lisp-fun + ?current-state ?clipped-distance ?absolute-distance) + (lisp-fun - ?current-state ?clipped-distance ?absolute-distance)) + ;; infer missing information like ?gripper-opening, opening trajectory (lisp-fun man-int:get-action-gripper-opening ?container-type ?gripper-opening) @@ -106,8 +111,8 @@ ;; calculate trajectory (equal (?container-designator) ?objects) (-> (equal ?arm :left) - (and (lisp-fun man-int:get-action-trajectory - ?action-type ?arm NIL ?objects + (and (lisp-fun man-int:get-action-trajectory ?action-type + ?arm NIL NIL ?objects :opening-distance ?clipped-distance :handle-axis ?handle-axis ?left-trajectory) @@ -128,8 +133,8 @@ (equal ?left-manipulate-poses NIL) (equal ?left-retract-poses NIL))) (-> (equal ?arm :right) - (and (lisp-fun man-int:get-action-trajectory - ?action-type ?arm NIL ?objects + (and (lisp-fun man-int:get-action-trajectory ?action-type + ?arm NIL NIL ?objects :opening-distance ?clipped-distance :handle-axis ?handle-axis ?right-trajectory) @@ -152,11 +157,17 @@ (or (lisp-pred identity ?left-trajectory) (lisp-pred identity ?right-trajectory)) + (-> (lisp-pred identity ?left-reach-poses) + (equal ?left-reach-poses (?look-pose . ?_)) + (equal ?right-reach-poses (?look-pose . ?_))) + ;; make new action designator (desig:designator :action ((:type ?action-type) (:arm ?arm) (:gripper-opening ?gripper-opening) (:distance ?clipped-distance) + (:absolute-distance ?absolute-distance) + (:look-pose ?look-pose) (:left-reach-poses ?left-reach-poses) (:right-reach-poses ?right-reach-poses) (:left-grasp-poses ?left-grasp-poses) diff --git a/cram_3d_world/cram_urdf_environment_manipulation/src/costmaps.lisp b/cram_3d_world/cram_urdf_environment_manipulation/src/costmaps.lisp index 90f1ab334b..76a254fdf0 100644 --- a/cram_3d_world/cram_urdf_environment_manipulation/src/costmaps.lisp +++ b/cram_3d_world/cram_urdf_environment_manipulation/src/costmaps.lisp @@ -118,13 +118,13 @@ environment, in which it can be found, respectively." (line-equation-in-xy neutral-point manipulated-point) (let* ((P (cl-transforms:make-3d-vector x y 0)) (dist (line-p-dist a b c P)) - ;;(dist-p (line-p-dist-point a b c P)) + (dist-p (line-p-dist-point a b c P)) ) (if (and (< dist (+ (/ width 2) padding)) ;; Commenting this out for now, so there won't be poses in front of the drawer. - ;;(< (cl-transforms:v-norm (cl-transforms:v- dist-p neutral-point)) - ;; (+ (cl-transforms:v-norm V) padding)) + (< (cl-transforms:v-norm (cl-transforms:v- dist-p neutral-point)) + (+ (cl-transforms:v-norm V) padding)) ) 0 1)))))) @@ -308,7 +308,7 @@ to face from `pos1' towards `pos2'." (p-rel (cl-transforms:v- point2 point1))) (atan (cl-transforms:y p-rel) (cl-transforms:x p-rel)))) -(defun make-point-to-point-generator (pos1 pos2 &key (samples 1) sample-step) +(defun make-point-to-point-generator (pos1 pos2 &key (samples 1) sample-step sample-offset) "Returns a function that takes an X and Y coordinate and returns a lazy-list of quaternions to face from `pos1' to `pos2'." (location-costmap:make-orientation-generator @@ -317,7 +317,8 @@ quaternions to face from `pos1' to `pos2'." pos1 pos2) :samples samples - :sample-step sample-step)) + :sample-step sample-step + :sample-offset sample-offset)) (defun angle-halfway-to-point-direction (x y pos1 pos2 target-pos) "Takes an X and Y coordinate and returns a quaternion between the one facing @@ -326,7 +327,7 @@ from pos1 to pos2 and the one facing from (X,Y) to target-pos." (target-direction (costmap::angle-to-point-direction x y target-pos))) (/ (+ pos-direction target-direction) 2))) -(defun make-angle-halfway-to-point-generator (pos1 pos2 target-pos &key (samples 1) sample-step) +(defun make-angle-halfway-to-point-generator (pos1 pos2 target-pos &key (samples 1) sample-step sample-offset) "Returns a function that takes an X and Y coordinate and returns a lazy-list of quaternions facing from (X,Y) halfway to target-pos. Meaning pos1 and pos2 describe a direction and the quaternion is the angle between one facing directly @@ -335,7 +336,8 @@ from (X,Y) to target-pos and the direction between pos1 and pos2." (alexandria:rcurry #'angle-halfway-to-point-direction pos1 pos2 target-pos) :samples samples - :sample-step sample-step)) + :sample-step sample-step + :sample-offset sample-offset)) (defun middle-pose (pose1 pose2) "Take two poses and return a pose in the middle of them. @@ -348,9 +350,9 @@ Disregarding the orientation (using the pose2's)." 0.5))) (cram-tf:translate-pose pose2 - :x-offset (cl-transforms:x translation-to-middle) - :y-offset (cl-transforms:y translation-to-middle) - :z-offset (cl-transforms:z translation-to-middle)))) + :x (cl-transforms:x translation-to-middle) + :y (cl-transforms:y translation-to-middle) + :z (cl-transforms:z translation-to-middle)))) (defmethod costmap:costmap-generator-name->score ((name (eql 'poses-reachable-cost-function))) 10) @@ -373,69 +375,101 @@ Disregarding the orientation (using the pose2's)." (def-fact-group environment-manipulation-costmap (costmap:desig-costmap) (<- (costmap:desig-costmap ?designator ?costmap) - (cram-robot-interfaces:reachability-designator ?designator) + (rob-int:reachability-designator ?designator) (spec:property ?designator (:object ?container-designator)) (spec:property ?container-designator (:type ?container-type)) (man-int:object-type-subtype :container-prismatic ?container-type) (spec:property ?container-designator (:urdf-name ?container-name)) (spec:property ?container-designator (:part-of ?btr-environment)) (spec:property ?designator (:arm ?arm)) + (rob-int:robot ?robot-name) (costmap:costmap ?costmap) - ;; reachability gaussian costmap + (costmap:costmap-in-reach-distance ?robot-name ?distance) + (costmap:costmap-reach-minimal-distance ?robot-name ?minimal-distance) + + ;; reachability range costmap (lisp-fun get-handle-min-max-pose ?container-name ?btr-environment ?poses) - (lisp-fun costmap:2d-pose-covariance ?poses 0.05 (?mean ?covariance)) - (costmap:costmap-add-function - container-handle-reachable-cost-function - (costmap:make-gauss-cost-function ?mean ?covariance) - ?costmap) + (forall (member ?pose ?poses) + (and (instance-of + gaussian-costmap::pose-distribution-range-include-generator + ?include-generator-id) + (costmap:costmap-add-function + ?include-generator-id + (costmap:make-range-cost-function ?pose ?distance) + ?costmap) + (instance-of + gaussian-costmap::pose-distribution-range-exclude-generator + ?exclude-generator-id) + (costmap:costmap-add-function + ?exclude-generator-id + (costmap:make-range-cost-function + ?pose ?minimal-distance :invert t) + ?costmap))) + ;; cutting out drawer costmap - (costmap:costmap-manipulation-padding ?padding) + (costmap:costmap-manipulation-padding ?robot-name ?padding) (costmap:costmap-add-function opened-drawer-cost-function (make-opened-drawer-cost-function ?container-name ?btr-environment ?padding) ?costmap) + ;; cutting out for specific arm costmap (costmap:costmap-add-function opened-drawer-side-cost-function (make-opened-drawer-side-cost-function ?container-name ?arm ?btr-environment) ?costmap) + ;; orientation generator ;; generate an orientation opposite to the axis of the drawer (equal ?poses (?neutral-pose ?manipulated-pose)) - (costmap:orientation-samples ?samples) - (costmap:orientation-sample-step ?sample-step) + (costmap:orientation-samples ?robot-name ?samples) + (costmap:orientation-sample-step ?robot-name ?sample-step) + (once (or (costmap:reachability-orientation-offset ?robot-name ?sample-offset) + (equal ?sample-offset 0.0))) (costmap:costmap-add-orientation-generator (make-angle-halfway-to-point-generator ?manipulated-pose ?neutral-pose ?neutral-pose :samples ?samples - :sample-step ?sample-step) + :sample-step ?sample-step + :sample-offset ?sample-offset) ?costmap)) (<- (costmap:desig-costmap ?designator ?costmap) - (cram-robot-interfaces:reachability-designator ?designator) + (rob-int:reachability-designator ?designator) (spec:property ?designator (:object ?container-designator)) (spec:property ?container-designator (:type ?container-type)) (man-int:object-type-subtype :container-revolute ?container-type) (spec:property ?container-designator (:urdf-name ?container-name)) (spec:property ?container-designator (:part-of ?btr-environment)) (spec:property ?designator (:arm ?arm)) + (rob-int:robot ?robot-name) (costmap:costmap ?costmap) + (costmap:costmap-in-reach-distance ?robot-name ?distance) + (costmap:costmap-reach-minimal-distance ?robot-name ?minimal-distance) - ;; reachability gaussian costmap - (lisp-fun get-handle-min-max-pose ?container-name ?btr-environment (?min-pose ?max-pose)) - (lisp-fun middle-pose ?min-pose ?max-pose ?middle-pose) - ;; TODO(cpo): If you can, please beautifiy this. - (equal (?middle-pose) ?poses) - (lisp-fun costmap:2d-pose-covariance ?poses 0.05 (?mean ?covariance)) - (costmap:costmap-add-function - container-handle-reachable-cost-function - (costmap:make-gauss-cost-function ?mean ?covariance) - ?costmap) + ;; reachability range costmap + (lisp-fun get-handle-min-max-pose ?container-name ?btr-environment ?poses) + (forall (member ?pose ?poses) + (and (instance-of + gaussian-costmap::pose-distribution-range-include-generator + ?include-generator-id) + (costmap:costmap-add-function + ?include-generator-id + (costmap:make-range-cost-function ?pose ?distance) + ?costmap) + (instance-of + gaussian-costmap::pose-distribution-range-exclude-generator + ?exclude-generator-id) + (costmap:costmap-add-function + ?exclude-generator-id + (costmap:make-range-cost-function + ?pose ?minimal-distance :invert t) + ?costmap))) ;; cutting out door costmap - (costmap:costmap-manipulation-padding ?padding) + (costmap:costmap-manipulation-padding ?robot-name ?padding) (costmap:costmap-add-function opened-door-cost-function (make-opened-door-cost-function ?container-name ?btr-environment ?padding) @@ -453,13 +487,11 @@ Disregarding the orientation (using the pose2's)." (lisp-fun cl-urdf:child ?joint ?joint-link) (lisp-fun cl-urdf:name ?joint-link ?joint-name) (lisp-fun get-urdf-link-pose ?joint-name ?btr-environment ?joint-pose) - (costmap:orientation-samples ?samples) - (costmap:orientation-sample-step ?sample-step) + (costmap:orientation-samples ?robot-name ?samples) + (costmap:orientation-sample-step ?robot-name ?sample-step) + (once (or (costmap:reachability-orientation-offset ?robot-name ?sample-offset) + (equal ?sample-offset 0.0))) (costmap:costmap-add-orientation-generator (costmap:make-angle-to-point-generator - ?joint-pose - :samples ?samples - :sample-step ?sample-step) - ?costmap) - ) - ) + ?joint-pose :samples ?samples :sample-step ?sample-step :sample-offset ?sample-offset) + ?costmap))) diff --git a/cram_3d_world/cram_urdf_environment_manipulation/src/environment-occasions.lisp b/cram_3d_world/cram_urdf_environment_manipulation/src/environment-occasions.lisp index 9832ebf9b3..5ee9a16911 100644 --- a/cram_3d_world/cram_urdf_environment_manipulation/src/environment-occasions.lisp +++ b/cram_3d_world/cram_urdf_environment_manipulation/src/environment-occasions.lisp @@ -29,12 +29,30 @@ (in-package :env-man) +(defparameter *container-state-convergence-delta* 0.1 "In meters or rad.") + (def-fact-group environment-occasions (cpoe:container-state) + (<- (cpoe:container-state ?container-designator ?distance) + (symbol-value *container-state-convergence-delta* ?delta) + (cpoe:container-state ?container-designator ?distance ?delta)) + + (<- (cpoe:container-state ?container-designator ?distance ?delta) (spec:property ?container-designator (:urdf-name ?container-name)) (spec:property ?container-designator (:part-of ?btr-environment)) (btr:bullet-world ?world) (lisp-fun get-container-link ?container-name ?btr-environment ?container-link) (lisp-fun get-connecting-joint ?container-link ?joint) (lisp-fun cl-urdf:name ?joint ?joint-name) - (btr:joint-state ?world ?btr-environment ?joint-name ?distance))) + (btr:joint-state ?world ?btr-environment ?joint-name ?joint-state) + (or (and (lisp-type ?distance number) + (lisp-pred cram-tf:values-converged ?joint-state ?distance ?delta)) + (and (member ?distance (:open :closed)) + (lisp-fun cl-urdf:limits ?joint ?joint-limits) + (lisp-fun cl-urdf:lower ?joint-limits ?lower-limit) + (lisp-fun cl-urdf:upper ?joint-limits ?upper-limit) + (-> (equal ?distance :open) + (lisp-pred cram-tf:values-converged + ?joint-state ?upper-limit ?delta) + (lisp-pred cram-tf:values-converged + ?joint-state ?lower-limit ?delta)))))) diff --git a/cram_3d_world/cram_urdf_environment_manipulation/src/environment.lisp b/cram_3d_world/cram_urdf_environment_manipulation/src/environment.lisp index 98469976c2..f72f295e74 100644 --- a/cram_3d_world/cram_urdf_environment_manipulation/src/environment.lisp +++ b/cram_3d_world/cram_urdf_environment_manipulation/src/environment.lisp @@ -30,7 +30,7 @@ (in-package :env-man) (defun get-current-environment () - (btr:object btr:*current-bullet-world* :kitchen) + (btr:get-environment-object) ;; (find 'btr::urdf-semantic-map-object ;; (btr:objects btr:*current-bullet-world*) ;; :key #'type-of) @@ -38,7 +38,10 @@ (defun get-container-pose-and-transform (name btr-environment) "Return a list of the pose-stamped and transform-stamped of the object named -NAME in the environment BTR-ENVIRONMENT." +`name' in the environment `btr-environment'. +The frame-id will be cram-tf:*robot-base-frame* and the child-frame-id will be the `name'." + (declare (type (or string symbol) name) + (type keyword btr-environment)) (when (symbolp name) (setf name (roslisp-utilities:rosify-underscores-lisp-name name))) @@ -51,9 +54,14 @@ NAME in the environment BTR-ENVIRONMENT." cram-tf:*robot-base-frame* :use-zero-time t)) (transform (cram-tf:pose-stamped->transform-stamped pose name))) - (list pose transform))) + (list + (the cl-transforms-stamped:pose-stamped pose) + (the cl-transforms-stamped:transform-stamped transform)))) (defun get-urdf-link-pose (name btr-environment) + "Return the pose of the object with `name' in `btr-environment'." + (declare (type (or string symbol) name) + (type keyword btr-environment)) (when (symbolp name) (setf name (roslisp-utilities:rosify-underscores-lisp-name name))) @@ -66,29 +74,41 @@ NAME in the environment BTR-ENVIRONMENT." name)))) (defun get-container-link (container-name btr-environment) + "Return the link of the container with `container-name' in the `btr-environment'." + (declare (type (or string symbol) container-name) + (type keyword btr-environment)) (when (symbolp container-name) (setf container-name (roslisp-utilities:rosify-underscores-lisp-name container-name))) - (gethash container-name - (cl-urdf:links - (btr:urdf - (btr:object btr:*current-bullet-world* - btr-environment))))) + (the cl-urdf:link + (gethash container-name + (cl-urdf:links + (btr:urdf + (btr:object btr:*current-bullet-world* + btr-environment)))))) (defun get-container-joint-type (container-name btr-environment) + "Return the joint-type of the container with `container-name' in the `btr-environment'." + (declare (type (or string symbol) container-name) + (type keyword btr-environment)) (find-container-joint-type-under-joint (cl-urdf:from-joint (get-container-link container-name btr-environment)))) (defun find-container-joint-type-under-joint (joint) - "Return the first joint type different from :FIXED under the given JOINT." + "Return the first joint type different from :FIXED under the given `joint'." + (declare (type cl-urdf:joint joint)) (if (eq :FIXED (cl-urdf:joint-type joint)) (find-container-joint-type-under-joint (car (cl-urdf:to-joints (cl-urdf:child joint)))) (cl-urdf:joint-type joint))) (defun get-handle-link (container-name btr-environment) + "Return the link object of the handle of the container with `container-name' in +the `btr-environment' (of type cl-urdf:link)." + (declare (type (or string symbol) container-name) + (type keyword btr-environment)) (when (symbolp container-name) (setf container-name (roslisp-utilities:rosify-underscores-lisp-name container-name))) @@ -96,32 +116,39 @@ NAME in the environment BTR-ENVIRONMENT." (get-container-link container-name btr-environment))) (defun find-handle-under-link (link) - (if (search "handle" (cl-urdf:name link)) - link - (reduce (lambda (&optional x y) (or x y)) - (mapcar 'find-handle-under-link - (mapcar 'cl-urdf:child (cl-urdf:to-joints link)))))) + "Return the link object of the handle under the given `link' object." + (declare (type (or null cl-urdf:link) link)) + (the (or null cl-urdf:link) + (if (search "handle" (cl-urdf:name link)) + link + (reduce (lambda (&optional x y) (or x y)) + (mapcar 'find-handle-under-link + (mapcar 'cl-urdf:child (cl-urdf:to-joints link))))))) (defun get-joint-position (joint btr-environment) - (gethash (cl-urdf:name joint) - (btr:joint-states (btr:object btr:*current-bullet-world* btr-environment)))) + "Return the value of the `joint' in the `btr-environment'." + (declare (type cl-urdf:joint joint) + (type keyword btr-environment)) + (the number + (gethash (cl-urdf:name joint) + (btr:joint-states (btr:object btr:*current-bullet-world* btr-environment))))) (defun get-connecting-joint (part) - "Returns the connecting (moveable) joint of `part', which can be either - a link or a joint of an URDF." - (or - (get-connecting-joint-below part) - (get-connecting-joint-above part))) + "Returns the connecting (moveable) joint of `part' of type cl-urdf:joint." + (declare (type (or cl-urdf:joint cl-urdf:link) part)) + (or (get-connecting-joint-below part) + (get-connecting-joint-above part))) (defun get-connecting-joint-below (part) - "Traverse the URDF downwards to find a connecting joint." + "Traverse the URDF downwards to find a connecting joint and returns it. +The type of return value is cl-urdf:joint. +See `get-connecting-joint' for more info." + (declare (type (or cl-urdf:joint cl-urdf:link) part)) (when part (if (typep part 'cl-urdf:joint) - (or - (when (not (eql (cl-urdf:joint-type part) :FIXED)) - part) - (get-connecting-joint-below (cl-urdf:child part))) - + (or (when (not (eql (cl-urdf:joint-type part) :FIXED)) + part) + (get-connecting-joint-below (cl-urdf:child part))) (when (typep part 'cl-urdf:link) (find-if (lambda (joint) @@ -129,27 +156,35 @@ NAME in the environment BTR-ENVIRONMENT." (cl-urdf:to-joints part)))))) (defun get-connecting-joint-above (part) - "Traverse the URDF upwards to find a connecting joint." + "Traverse the URDF upwards to find a connecting joint and returns it. +The type of return value is cl-urdf:joint. +See `get-connecting-joint' for more info." + (declare (type (or cl-urdf:joint cl-urdf:link) part)) (when part (if (typep part 'cl-urdf:joint) - (or - (when (not (eql (cl-urdf:joint-type part) :FIXED)) - part) - (get-connecting-joint-above (cl-urdf:parent part))) - + (or (when (not (eql (cl-urdf:joint-type part) :FIXED)) + part) + (get-connecting-joint-above (cl-urdf:parent part))) (when (typep part 'cl-urdf:link) (get-connecting-joint-above (cl-urdf:from-joint part)))))) (defun get-manipulated-link (part) - "Returns the link under the connecting joint. Which is the one actuallz being manipulated." + "Returns the link under the connecting joint of `part' of type cl-urdf:link. +Which is the one actually being manipulated." + (declare (type (or cl-urdf:joint cl-urdf:link) part)) (cl-urdf:child (get-connecting-joint part))) (defun get-manipulated-pose (link-name joint-position btr-environment &key relative) - "Returns the pose of a link based on its connection joint position - JOINT-POSITION. If RELATIVE is T, the actual value is calculated - by JOINT-POSITION * . This function returns two - values, the new pose of the link and the joint that was changed." + "Returns the pose of the link with `link-name' based on its connection joint position +`joint-position'. If `relative' is T, the actual value is calculated +by `joint-position' * . This function returns two +values, the new pose of the link and the joint object that was changed. +`btr-environment' is the name of the bullet environment (eg. :kitchen)." + (declare (type (or string symbol) link-name) + (type number joint-position) + (type keyword btr-environment) + (type boolean relative)) (when (not (floatp joint-position)) (setf joint-position (float joint-position))) (let ((link (get-container-link link-name btr-environment))) @@ -159,19 +194,20 @@ NAME in the environment BTR-ENVIRONMENT." (values (case (cl-urdf:joint-type joint) (:prismatic - (cl-transforms:transform->pose - (cl-transforms:transform* - (cl-transforms:pose->transform (get-urdf-link-pose link-name btr-environment)) - (cl-transforms:make-transform - (cl-transforms:v* - (cl-urdf:axis joint) - (- - (if relative - (* joint-position - (cl-urdf:upper (cl-urdf:limits joint))) - joint-position) - (get-joint-position joint btr-environment))) - (cl-transforms:make-identity-rotation))))) + (the cl-transforms:pose + (cl-transforms:transform->pose + (cl-transforms:transform* + (cl-transforms:pose->transform (get-urdf-link-pose link-name btr-environment)) + (cl-transforms:make-transform + (cl-transforms:v* + (cl-urdf:axis joint) + (- + (if relative + (* joint-position + (cl-urdf:upper (cl-urdf:limits joint))) + joint-position) + (get-joint-position joint btr-environment))) + (cl-transforms:make-identity-rotation)))))) (:revolute (let* ((rotation (cl-transforms:axis-angle->quaternion @@ -192,19 +228,23 @@ NAME in the environment BTR-ENVIRONMENT." (cl-transforms:transform-diff link-transform joint-transform))) - (cl-transforms:transform-pose - (cl-transforms:make-transform - (cl-transforms:rotate - rotation - (cl-transforms:translation joint-to-handle)) - (cl-transforms:make-identity-rotation)) - (get-urdf-link-pose (cl-urdf:name (cl-urdf:child joint)) btr-environment)) - ))) + (the cl-transforms:pose + (cl-transforms:transform-pose + (cl-transforms:make-transform + (cl-transforms:rotate + rotation + (cl-transforms:translation joint-to-handle)) + (cl-transforms:make-identity-rotation)) + (get-urdf-link-pose (cl-urdf:name (cl-urdf:child joint)) btr-environment)))))) joint)))))) (defun get-handle-axis (container-designator) "Return either a vector with (1 0 0) for horizontal handles or (0 0 1) for -vertical handles on the container described by CONTAINER-DESIGNATOR." +vertical handles on the container described by `container-designator'. +Prismatic containers are assumed to have horizontal handles while revolute containers are assumed +to have vertical ones. There are exceptions to this of course. For now those are hard-coded into +this function." + (declare (type desig:object-designator container-designator)) ;; Check for exceptions based on name. (let ((name-exception (alexandria:switch ((roslisp-utilities:rosify-underscores-lisp-name @@ -232,33 +272,63 @@ Using a default (1 0 0)." (cl-transforms:make-3d-vector 1 0 0))))))) (defun get-positive-joint-state (joint btr-environment) + (declare (type cl-urdf:joint joint) + (type keyword btr-environment)) (mod (btr:joint-state (btr:object btr:*current-bullet-world* btr-environment) (cl-urdf:name joint)) (* 2 pi))) +(defun get-connecting-joint-state-secure (container-name btr-environment) + (let* ((joint (get-connecting-joint + (get-container-link container-name + btr-environment))) + (type (find-container-joint-type-under-joint joint)) + (state (btr:joint-state + (btr:object btr:*current-bullet-world* + btr-environment) + (cl-urdf:name joint)))) + (ecase type + (:revolute + (mod state (* 2 pi))) + (:prismatic + state)))) + +(defun get-relative-distance (container-name btr-environment distance action-type) + (declare (type (or string symbol) container-name) + (type keyword btr-environment) + (type number distance) + (type keyword action-type)) + (let ((state (get-connecting-joint-state-secure container-name btr-environment))) + (ecase action-type + (:opening + (- distance state)) + (:closing + (- (- distance state)))))) + (defun clip-distance (container-name btr-environment distance action-type) "Return a distance that stays inside the joint's limits." + (declare (type (or string symbol) container-name) + (type keyword btr-environment) + (type number distance) + (type keyword action-type)) (let ((joint (get-connecting-joint (get-container-link container-name btr-environment)))) (let ((upper-limit (cl-urdf:upper (cl-urdf:limits joint))) (lower-limit (cl-urdf:lower (cl-urdf:limits joint))) - (state (get-positive-joint-state joint btr-environment))) - (if (eq action-type :opening) - (if (> (+ state distance) upper-limit) - (- upper-limit state) - distance) - (if (< (- state distance) lower-limit) - (- state lower-limit) - distance))))) - -(defun get-relative-distance (container-name btr-environment distance action-type) - (let* ((joint (get-connecting-joint - (get-container-link container-name - btr-environment))) - (state (get-positive-joint-state joint btr-environment))) - (if (eq action-type :opening) - (- distance state) - (- (- distance state))))) + (state (get-connecting-joint-state-secure container-name btr-environment))) + (ecase action-type + (:opening + (if (> (+ state distance) upper-limit) + (- upper-limit state) + (if (< (+ state distance) lower-limit) + (- (- state lower-limit)) + distance))) + (:closing + (if (< (- state distance) lower-limit) + (- state lower-limit) + (if (> (- state distance) upper-limit) + (- (- upper-limit state)) + distance))))))) diff --git a/cram_3d_world/cram_urdf_environment_manipulation/src/math.lisp b/cram_3d_world/cram_urdf_environment_manipulation/src/math.lisp index 0c0db6ade6..be1b4ec754 100644 --- a/cram_3d_world/cram_urdf_environment_manipulation/src/math.lisp +++ b/cram_3d_world/cram_urdf_environment_manipulation/src/math.lisp @@ -30,8 +30,9 @@ (in-package :env-man) (defun line-equation (x1 y1 x2 y2) - "Return the a, b and c values of the equation descriping a straight line -through (x1,y1) and (x2,y2)." + "Return the a, b and c values of the term (ax + by + c) descriping a straight line +through the points (`x1',`y1') and (`x2',`y2')." + (declare (type number x1 y2 x2 y2)) (let ((x (- x2 x1)) (y (- y2 y1))) (if (eq 0 x) @@ -42,9 +43,20 @@ through (x1,y1) and (x2,y2)." 1 (- 0 (- y1 (* m x1)))))))) +(defun line-equation-in-xy (p1 p2) + "Helper-function to get the equation (a,b,c values) describing a line between `p1' and `p2' +in the x-y-plane (i.e. only considering the first two dimensions)." + (declare (type cl-transforms:3d-vector p1 p2)) + (let ((x1 (cl-transforms:x p1)) + (y1 (cl-transforms:y p1)) + (x2 (cl-transforms:x p2)) + (y2 (cl-transforms:y p2))) + (line-equation x1 y1 x2 y2))) + (defun distance-point (a b c x y) - "Return the coordinates on the line described by ax + bx + c + "Return the coordinates on the line described by ax + by + c from which the distance to the point (x,y) is minimal." + (declare (type number a b c x y)) (values (/ (- (* b (- (* b x) (* a y))) (* a c)) @@ -53,16 +65,10 @@ from which the distance to the point (x,y) is minimal." (- (* a (+ (* (- 0 b) x) (* a y))) (* b c)) (+ (expt a 2) (expt b 2))))) -(defun line-equation-in-xy (p1 p2) - "Return the equation (a,b,c values) describing a line between p1 and p2 in the x-y-plane." - (let ((x1 (cl-transforms:x p1)) - (y1 (cl-transforms:y p1)) - (x2 (cl-transforms:x p2)) - (y2 (cl-transforms:y p2))) - (line-equation x1 y1 x2 y2))) - (defun line-p-dist (a b c p) - "Return the disctance between the line described by ax + bx + c + (declare (type number a b c) + (type cl-transforms:3d-vector p)) + "Return the distance between the line described by ax + by + c and the point p (in the x-y plane)." (let ((x (cl-transforms:x p)) (y (cl-transforms:y p))) @@ -71,8 +77,10 @@ and the point p (in the x-y plane)." (sqrt (+ (expt a 2) (expt b 2)))))) (defun line-p-dist-point (a b c p) - "Return the point on the line described by ax + bx + c -from which the distance to the point (x,y) is minimal." + "Return the point on the line described by ax + by + c +from which the distance to the point p is minimal." + (declare (type number a b c) + (type cl-transforms:3d-vector p)) (let ((px (cl-transforms:x p)) (py (cl-transforms:y p))) (multiple-value-bind (x y) @@ -80,13 +88,15 @@ from which the distance to the point (x,y) is minimal." (cl-transforms:make-3d-vector x y 0)))) (defun angle-between-vectors (v1 v2) - "Return the cos of the angle between vectors V1 and V2." + "Return the cos of the angle between vectors `v1' and `v2.'" + (declare (type cl-transforms:3d-vector v1 v2)) (/ (cl-transforms:dot-product v1 v2) (* (cl-transforms:v-norm v1) (cl-transforms:v-norm v2)))) (defun v-which-side (v1 v2) - "Return either :left or :right depending on which side of v1 v2 is." + "Return either :left or :right depending on which side of `v1' `v2' is." + (declare (type cl-transforms:3d-vector v1 v2)) (let ((v2-rot90ccw (cl-transforms:make-3d-vector (- (cl-transforms:y v2)) (cl-transforms:x v2) diff --git a/cram_3d_world/cram_urdf_environment_manipulation/src/plans.lisp b/cram_3d_world/cram_urdf_environment_manipulation/src/plans.lisp index cd520d8d44..d3278a1053 100644 --- a/cram_3d_world/cram_urdf_environment_manipulation/src/plans.lisp +++ b/cram_3d_world/cram_urdf_environment_manipulation/src/plans.lisp @@ -33,13 +33,15 @@ ((:type ?type)) ((:arm ?arm)) ((:gripper-opening ?gripper-opening)) - distance + ((:distance ?distance)) + ((:absolute-distance ?absolute-distance)) + ((:look-pose ?look-pose)) ((:left-reach-poses ?left-reach-poses)) ((:right-reach-poses ?right-reach-poses)) ((:left-grasp-poses ?left-grasp-poses)) ((:right-grasp-poses ?right-grasp-poses)) - ((:left-open-poses ?left-manipulate-poses)) - ((:right-open-poses ?right-manipulate-poses)) + ((:left-manipulate-poses ?left-manipulate-poses)) + ((:right-manipulate-poses ?right-manipulate-poses)) ((:left-retract-poses ?left-retract-poses)) ((:right-retract-poses ?right-retract-poses)) joint-name @@ -49,7 +51,7 @@ ((:container-object ?container-designator)) &allow-other-keys) (declare (type keyword ?arm) - (type number ?gripper-opening distance) + (type number ?gripper-opening ?distance) (type list ?left-reach-poses ?right-reach-poses ?left-grasp-poses ?right-grasp-poses @@ -61,27 +63,38 @@ ;;;;;;;;;;;;;;; OPEN GRIPPER AND REACH ;;;;;;;;;;;;;;;; (cpl:par - (roslisp:ros-info (environment-manipulation manipulate-container) - "Opening gripper") - (exe:perform - (desig:an action - (type setting-gripper) - (gripper ?arm) - (position ?gripper-opening))) - (roslisp:ros-info (environment-manipulation manipulate-container) - "Reaching") + (roslisp:ros-info (env-manip plan) "Looking, opening gripper and reaching") (cpl:with-failure-handling - ((common-fail:manipulation-low-level-failure (e) - (roslisp:ros-warn (env-plans manipulate) - "Manipulation messed up: ~a~%Failing." + ((common-fail:ptu-low-level-failure (e) + (roslisp:ros-warn (env-manip plan) + "Looking-at had a problem: ~a~%Ignoring." e) - ;; (return) - )) + (return))) + (exe:perform + (desig:an action + (type looking) + (target (desig:a location + (pose ?look-pose)))))) + (let ((?goal `(cpoe:gripper-joint-at ,?arm ,?gripper-opening))) (exe:perform (desig:an action - (type reaching) - (left-poses ?left-reach-poses) - (right-poses ?right-reach-poses))))) + (type setting-gripper) + (gripper ?arm) + (position ?gripper-opening) + (goal ?goal)))) + (cpl:with-failure-handling + ((common-fail:manipulation-low-level-failure (e) + (roslisp:ros-warn (env-plans manipulate) + "Manipulation messed up: ~a~%Ignoring." + e) + (return))) + (let ((?goal `(cpoe:tool-frames-at ,?left-reach-poses ,?right-reach-poses))) + (exe:perform + (desig:an action + (type reaching) + (left-poses ?left-reach-poses) + (right-poses ?right-reach-poses) + (goal ?goal)))))) ;;;;;;;;;;;;;;;;;;;; GRIPPING ;;;;;;;;;;;;;;;;;;;;;;;; (roslisp:ros-info (environment-manipulation manipulate-container) @@ -91,16 +104,18 @@ (roslisp:ros-warn (env-plans manipulate) "Manipulation messed up: ~a~%Failing." e) - ;; (return) - )) - (exe:perform - (desig:an action - (type grasping) - (object (desig:an object - (name ?environment-name))) - (link ?link-name) - (left-poses ?left-grasp-poses) - (right-poses ?right-grasp-poses)))) + (return))) + (let ((?goal `(cpoe:tool-frames-at ,?left-grasp-poses ,?right-grasp-poses))) + (exe:perform + (desig:an action + (type grasping) + (object (desig:an object + (name ?environment-name))) + (link ?link-name) + (left-poses ?left-grasp-poses) + (right-poses ?right-grasp-poses) + (goal ?goal))))) + (when (eq ?type :opening) (exe:perform (desig:an action @@ -117,18 +132,25 @@ e) ;; (return) )) - (let ((?push-or-pull (if (eq ?type :opening) - :pulling - :pushing))) + (let ((?push-or-pull + (if (eq ?type :opening) + :pulling + :pushing)) + (?goal + `(cpoe:tool-frames-at ,?left-manipulate-poses ,?right-manipulate-poses))) (exe:perform (desig:an action (type ?push-or-pull) - (object (desig:an object - (name ?environment-name))) + (object (desig:an object (name ?environment-name))) (container-object ?container-designator) (link ?link-name) - (left-poses ?left-manipulate-poses) - (right-poses ?right-manipulate-poses))))) + (desig:when ?absolute-distance + (distance ?absolute-distance)) + (desig:when (eq ?arm :left) + (left-poses ?left-manipulate-poses)) + (desig:when (eq ?arm :right) + (right-poses ?right-manipulate-poses)) + (goal ?goal))))) (when (and joint-name) (cram-occasions-events:on-event @@ -138,23 +160,27 @@ :joint-name joint-name :side ?arm :environment ?environment-object - :distance distance))) + :distance ?distance))) ;;;;;;;;;;;;;;;;;;;; RETRACTING ;;;;;;;;;;;;;;;;;;;;;;;;;;; (roslisp:ros-info (environment-manipulation manipulate-container) "Retracting") - (exe:perform - (desig:an action - (type releasing) - (gripper ?arm))) + (let ((?goal `(cpoe:gripper-opened ,?arm))) + (exe:perform + (desig:an action + (type releasing) + (gripper ?arm) + (goal ?goal)))) (cpl:with-failure-handling ((common-fail:manipulation-low-level-failure (e) (roslisp:ros-warn (env-plans manipulate) "Manipulation messed up: ~a~%Ignoring." e) (return))) - (exe:perform - (desig:an action - (type retracting) - (left-poses ?left-retract-poses) - (right-poses ?right-retract-poses))))) + (let ((?goal `(cpoe:tool-frames-at ,?left-retract-poses ,?right-retract-poses))) + (exe:perform + (desig:an action + (type retracting) + (left-poses ?left-retract-poses) + (right-poses ?right-retract-poses) + (goal ?goal)))))) diff --git a/cram_3d_world/cram_urdf_environment_manipulation/src/trajectories.lisp b/cram_3d_world/cram_urdf_environment_manipulation/src/trajectories.lisp index b3045711d5..c370548478 100644 --- a/cram_3d_world/cram_urdf_environment_manipulation/src/trajectories.lisp +++ b/cram_3d_world/cram_urdf_environment_manipulation/src/trajectories.lisp @@ -29,7 +29,7 @@ (in-package :env-man) -(defparameter *drawer-handle-grasp-x-offset* 0.0 "in meters") +(defparameter *drawer-handle-grasp-x-offset* -0.015 "in meters") (defparameter *drawer-handle-pregrasp-x-offset* 0.10 "in meters") (defparameter *drawer-handle-retract-offset* 0.10 "in meters") (defparameter *door-handle-retract-offset* 0.05 "in meters") @@ -37,14 +37,19 @@ (defmethod man-int:get-action-trajectory :heuristics 20 ((action-type (eql :opening)) arm grasp + location objects-acted-on &key opening-distance handle-axis) "Return a trajectory for opening the object in OBJECTS-ACTED-ON. -OPENING-DISTANCE is a float in m, describing how far the object should opened. -HANDLE-AXIS is a `cl-transforms:3d-vector' describing the handle's orientation -in the robot's XZ-plane. It's Z-element should be 0." +`opening-distance' describes how far the object should be opened in m. +`handle-axis' describes the handle's orientation +in the robot's XZ-plane. It's Y-element should be 0." + (declare (type keyword arm) + (type list objects-acted-on) + (type number opening-distance) + (type cl-transforms:3d-vector handle-axis)) (when (not (eql 1 (length objects-acted-on))) (error "Action-type ~a requires exactly one object.~%" action-type)) (make-trajectory action-type arm objects-acted-on opening-distance handle-axis)) @@ -52,14 +57,19 @@ in the robot's XZ-plane. It's Z-element should be 0." (defmethod man-int:get-action-trajectory :heuristics 20 ((action-type (eql :closing)) arm grasp + location objects-acted-on &key opening-distance handle-axis) "Return a trajectory for closing the object in OBJECTS-ACTED-ON. -OPENING-DISTANCE is a float in m, describing how far the object should closed. -HANDLE-AXIS is a `cl-transforms:3d-vector' describing the handle's orientation -in the robot's XZ-plane. It's Z-element should be 0." +`opening-distance' describes how far the object should be closed in m. +`handle-axis' describes the handle's orientation +in the robot's XZ-plane. It's Y-element should be 0." + (declare (type keyword arm) + (type list objects-acted-on) + (type number opening-distance) + (type cl-transforms:3d-vector handle-axis)) (when (not (eql 1 (length objects-acted-on))) (error "Action-type ~a requires exactly one object.~%" action-type)) (make-trajectory action-type arm objects-acted-on opening-distance handle-axis)) @@ -70,7 +80,13 @@ in the robot's XZ-plane. It's Z-element should be 0." opening-distance handle-axis) "Make a trajectory for opening or closing a container. -This should only be used by get-action-trajectory for action-types :opening and :closing." +This should only be called by `get-action-trajectory' for action-types :opening and :closing. +The parameters are analog to the ones of `get-action-trajectory'." + (declare (type keyword action-type) + (type keyword arm) + (type list objects-acted-on) + (type number opening-distance) + (type cl-transforms:3d-vector handle-axis)) (when (equal action-type :closing) (setf opening-distance (- opening-distance))) (let* ((object-designator @@ -107,8 +123,20 @@ This should only be used by get-action-trajectory for action-types :opening and (defun make-prismatic-trajectory (object-transform arm action-type grasp-pose opening-distance) - "Return a list of `man-int::traj-segment' representing a trajectory to open a -container with prismatic joints." + "Return a list of `man-int::traj-segment's representing a trajectory to open a +container with prismatic joints. +`object-transform' should have `cram-tf:*robot-base-frame*' +as it's frame and the object's frame as the child. +`arm' is the arm that should be used (eg. :left or :right) +`action-type' is :opening or :closing +`grasp-pose' is a transform with the object's frame and the +frame of the robot's end effector as the child (eg. `cram-tf:*robot-left-tool-frame*). +`opening-distance' is the distance the object should be manipulated in m." + (declare (type cl-transforms-stamped:transform-stamped object-transform) + (type keyword arm) + (type keyword action-type) + (type cl-transforms-stamped:transform-stamped grasp-pose) + (type number opening-distance)) (mapcar (lambda (label transform) (man-int:make-traj-segment @@ -130,7 +158,19 @@ container with prismatic joints." (defun make-revolute-trajectory (object-transform arm action-type grasp-pose opening-angle) "Return a list of `man-int::traj-segment' representing a trajectory to open a -container with revolute joints." +container with revolute joints. +`object-transform' should have `cram-tf:*robot-base-frame*' +as it's frame and the object's frame as the child. +`arm' is the arm that should be used (eg. :left or :right) +`action-type' is :opening or :closing +`grasp-pose' is a transform with the object's frame and the +frame of the robot's end effector as the child (eg. `cram-tf:*robot-left-tool-frame*). +`opening-distance' is the distance the object should be manipulated in rad." + (declare (type cl-transforms-stamped:transform-stamped object-transform) + (type keyword arm) + (type keyword action-type) + (type cl-transforms-stamped:transform-stamped grasp-pose) + (type number opening-angle)) (let* ((traj-poses (get-revolute-traj-poses grasp-pose :angle-max opening-angle)) (last-traj-pose (car (last traj-poses)))) (mapcar @@ -161,7 +201,7 @@ container with revolute joints." (defun 3d-vector->keyparam-list (v) - "Convert a `cl-transform:3d-vector' into a list with content + "Convert a vector into a list with content (:AX :AY :AZ )." (declare (type cl-transforms:3d-vector v)) (list @@ -173,7 +213,11 @@ container with revolute joints." &key (axis (cl-transforms:make-3d-vector 0 0 1)) angle-max) - "Return a list of transforms from joint to gripper rotated around AXIS by ANGLE-MAX." + "Return a list of stamped transforms from of the gripper-frame in the joint-frame rotated +around `axis' by `angle-max' in steps of 0.1 rad." + (declare (type cl-transforms-stamped:transform-stamped joint-to-gripper) + (type cl-transforms:3d-vector axis) + (type number angle-max)) (let ((angle-step (if (>= angle-max 0) 0.1 -0.1))) @@ -185,7 +229,8 @@ container with revolute joints." (cl-transforms-stamped:frame-id joint-to-gripper) (cl-transforms-stamped:child-frame-id joint-to-gripper) (cl-transforms-stamped:stamp joint-to-gripper) - (cl-transforms:rotate rotation (cl-tf:translation joint-to-gripper)) + (cl-transforms:rotate rotation (cl-transforms:translation + joint-to-gripper)) (apply 'cl-transforms:euler->quaternion (3d-vector->keyparam-list (cl-transforms:v+ @@ -201,7 +246,16 @@ container with revolute joints." arm handle-axis btr-environment) - "Get the transform from the container handle to the robot's gripper." + "Get the transform of the robot's gripper in the container handle frame. +`object-name' is the name of a container in the `btr-environment'. +`arm' denotes which arm's gripper should be used (eg. :left or :right). +`handle-axis' is the axis on which the handle lies when looked at from the front in form of a vector. +So normally (1 0 0) or (0 0 1). +`btr-environment' is the name of the environment in which the container is located (eg. :KITCHEN)." + (declare (type (or string symbol) object-name) + (type keyword arm) + (type cl-transforms:3d-vector handle-axis) + (type keyword btr-environment)) (when (symbolp object-name) (setf object-name (roslisp-utilities:rosify-underscores-lisp-name object-name))) diff --git a/cram_3d_world/cram_urdf_projection/cram-urdf-projection.asd b/cram_3d_world/cram_urdf_projection/cram-urdf-projection.asd index 81f9848944..0645c3d7b7 100644 --- a/cram_3d_world/cram_urdf_projection/cram-urdf-projection.asd +++ b/cram_3d_world/cram_urdf_projection/cram-urdf-projection.asd @@ -36,7 +36,7 @@ cram-projection cram-prolog cram-designators - cram-utilities ; for lazy list stuff with prolog + cram-utilities ; for lazy list stuff with prolog and equalize-lists cram-process-modules cl-transforms @@ -53,7 +53,11 @@ cram-bullet-reasoning-belief-state ; for special projection variable definition ; and world-state-detecting PM - cram-ik-interface) + cram-ik-interface + ;; can't depend on giskard because it wants the env. service... + ;; cram-giskard ; as an alternative to the ik solver + sensor_msgs-msg ; cram-ik-interface returns a joint state message + ) :components ((:module "src" :components diff --git a/cram_3d_world/cram_urdf_projection/package.xml b/cram_3d_world/cram_urdf_projection/package.xml index 8e8c51c818..cae6587c69 100644 --- a/cram_3d_world/cram_urdf_projection/package.xml +++ b/cram_3d_world/cram_urdf_projection/package.xml @@ -32,4 +32,5 @@ cram_bullet_reasoning cram_bullet_reasoning_belief_state cram_ik_interface + sensor_msgs diff --git a/cram_3d_world/cram_urdf_projection/src/low-level.lisp b/cram_3d_world/cram_urdf_projection/src/low-level.lisp index bcf46297ed..d14afac419 100644 --- a/cram_3d_world/cram_urdf_projection/src/low-level.lisp +++ b/cram_3d_world/cram_urdf_projection/src/low-level.lisp @@ -2,6 +2,7 @@ ;;; Copyright (c) 2011, Lorenz Moesenlechner ;;; 2017, Gayane Kazhoyan ;;; 2019, Vanessa Hassouna +;;; 2020, Amar Fayaz ;;; All rights reserved. ;;; ;;; Redistribution and use in source and binary forms, with or without @@ -13,8 +14,8 @@ ;;; notice, this list of conditions and the following disclaimer in the ;;; documentation and/or other materials provided with the distribution. ;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software ;;; without specific prior written permission. ;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" @@ -37,9 +38,23 @@ "in seconds, sleeps to show colliding configurations") (defparameter *be-strict-with-collisions* nil - "when grasping a spoon from table, fingers can collide with kitchen, so we might allow this") + "when grasping a spoon from table, fingers can collide with kitchen, so allow this") + +(defparameter *projection-convergence-delta-joint* 0.17 + "For moving arm joints. In radiants, about 10 degrees.") + +(defparameter *torso-resampling-step* 0.1d0 + "In meters.") +(defparameter *base-resampling-step* 0.1d0 + "In meters") +(defparameter *base-resampling-x-limit* 0.2d0 + "In meters") +(defparameter *base-resampling-y-limit* 0.2d0 + "In meters.") + +(defparameter *giskard-mode* nil + "Use giskard or teleporting/IK solver for joint and cartesian motions.") -(defparameter *projection-convergence-delta-joint* 0.17 "in radiants, about 10 degrees") (defun robot-transform-in-map () (let ((pose-in-map @@ -57,7 +72,7 @@ (defun robot-joint-states-with-odom-joints-as-hash-table () (let* ((observed-joint-states - (btr:joint-states (btr:get-robot-object))) + (alexandria:copy-hash-table (btr:joint-states (btr:get-robot-object)))) (robot-pose (btr:pose (btr:get-robot-object))) (robot-x @@ -81,8 +96,7 @@ (btr:add-vis-axis-object target) - (let* ((world btr:*current-bullet-world*) - (world-state (btr::get-state world))) + (let ((world-pose-info (btr:get-world-objects-pose-info))) (unwind-protect (progn ;; assert new robot pose @@ -94,10 +108,11 @@ ;; return joint state. this will be our observation ;; currently only used by HPN (robot-joint-states-with-odom-joints-as-hash-table)) - (when (btr:robot-colliding-objects-without-attached '(:floor)) + (when (or (btr:robot-colliding-objects-without-attached '(:floor)) + (btr:robot-attached-objects-in-collision)) (unless (< (abs *debug-short-sleep-duration*) 0.0001) (cpl:sleep *debug-short-sleep-duration*)) - (btr::restore-world-state world-state world) + (btr:restore-world-poses world-pose-info) (cpl:fail 'common-fail:navigation-pose-unreachable :pose-stamped target))))) ;;;;;;;;;;;;;;;;; TORSO ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; @@ -120,10 +135,10 @@ (cropped-joint-angle (if (numberp joint-angle) (if (< joint-angle lower-limit) - lower-limit - (if (> joint-angle upper-limit) - upper-limit - joint-angle)) + lower-limit + (if (> joint-angle upper-limit) + upper-limit + joint-angle)) (ecase joint-angle (:upper-limit upper-limit) (:lower-limit lower-limit) @@ -134,7 +149,8 @@ (when (numberp joint-angle) (unless (< (abs (- joint-angle cropped-joint-angle)) 0.0001) (cpl:fail 'common-fail:torso-goal-not-reached - :description (format nil "Torso goal ~a was out of joint limits" joint-angle) + :description (format nil "Torso goal ~a was out of joint limits" + joint-angle) :torso joint-angle))))) @@ -186,7 +202,8 @@ cram-tf:*fixed-frame* :use-zero-time t)) (pan-tilt-angles - (btr:calculate-pan-tilt (btr:get-robot-object) ?pan-link ?tilt-link pose-in-world)) + (btr:calculate-pan-tilt + (btr:get-robot-object) ?pan-link ?tilt-link pose-in-world)) (pan-angle (first pan-tilt-angles)) (tilt-angle @@ -217,45 +234,65 @@ (cpl:fail 'common-fail:ptu-goal-not-reached :description "Look action wanted to twist the neck"))))) -(defparameter *camera-pose-unit-vector-multiplyer* 0.4) -(defparameter *camera-pose-z-offset* 0.2) -(defparameter *camera-resampling-step* 0.1) -(defparameter *camera-x-axis-limit* 0.5) -(defparameter *camera-y-axis-limit* 0.5) - (defun get-neck-ik (ee-link cartesian-pose base-link joint-names) - (let ((joint-state-msg - (or (ik:call-ik-service-with-resampling - (cl-tf:pose->pose-stamped - base-link - 0.0 - cartesian-pose) - base-link ee-link - (btr::make-robot-joint-state-msg - (btr:get-robot-object) - :joint-names joint-names) - *camera-resampling-step* :x - 0 (- *camera-x-axis-limit*) *camera-x-axis-limit*) - (ik:call-ik-service-with-resampling - (cl-tf:pose->pose-stamped - base-link - 0.0 - cartesian-pose) - base-link ee-link - (btr::make-robot-joint-state-msg - (btr:get-robot-object) - :joint-names joint-names) - *camera-resampling-step* :y - 0 (- *camera-y-axis-limit*) *camera-y-axis-limit*)))) - (when joint-state-msg - (map 'list #'identity (roslisp:msg-slot-value joint-state-msg :position))))) + (cut:with-vars-strictly-bound (?camera-resampling-step + ?camera-x-axis-limit + ?camera-y-axis-limit + ?camera-z-axis-limit) + (car + (prolog:prolog + '(and + (rob-int:robot ?robot) + (rob-int:neck-camera-resampling-step ?robot ?camera-resampling-step) + (rob-int:neck-camera-x-axis-limit ?robot ?camera-x-axis-limit) + (rob-int:neck-camera-y-axis-limit ?robot ?camera-y-axis-limit) + (rob-int:neck-camera-z-axis-limit ?robot ?camera-z-axis-limit)))) + + (let* ((validation-function + (lambda (ik-solution-msg torso-offsets) + (declare (ignore torso-offsets)) + (not (perform-collision-check :avoid-all nil nil ik-solution-msg)))) + (cartesian-pose-stamped + (cl-transforms-stamped:pose->pose-stamped + base-link 0.0 + cartesian-pose)) + (neck-seed-state-msg + (btr::make-robot-joint-state-msg + (btr:get-robot-object) + :joint-names joint-names)) + (joint-state-msg + (ik:find-ik-for + (cartesian-pose-stamped + base-link + ee-link + neck-seed-state-msg + validation-function) + (ik:with-resampling + (:x + ?camera-x-axis-limit + (- ?camera-x-axis-limit) + ?camera-resampling-step) + (ik:with-resampling + (:y + ?camera-y-axis-limit + (- ?camera-y-axis-limit) + ?camera-resampling-step) + (ik:with-resampling + (:z + ?camera-z-axis-limit + (- ?camera-z-axis-limit) + ?camera-resampling-step))))))) + (when joint-state-msg + (map 'list #'identity + (roslisp:msg-slot-value joint-state-msg :position)))))) (defun calculate-camera-pose-from-object-pose (neck-base-t-object) "Takes the vector from neck-base to object, sets its Z to 0, -then normalizes to get a unit vector, then multiplies with a multiplier to make it shorter - (multiplier should be comparable to maximum length between neck base and camera), -then pulls the vector up in Z a bit to avoid colliding with bottom parts of robot, -and that would be the desired camera position. +then normalizes to get a unit vector, then multiplies with a multiplier +to make it shorter (multiplier should be comparable to maximum length +between neck base and camera), then pulls the vector up in Z a bit +to avoid colliding with bottom parts of robot, and that would be +the desired camera position. Next, to calculate desired camera rotation, looks at the object from camera position, calculates an angle that would have to be applied around X axis to align camera's Z with the object, calculates similar angle around Y axis and applies the rotations. " @@ -265,12 +302,26 @@ with the object, calculates similar angle around Y axis and applies the rotation (cl-transforms:copy-3d-vector neck-base-t-object-vector :z 0.0)) (neck-base-t-object-unit-vector (cl-transforms:normalize-vector neck-base-t-object-vector-without-z)) + (neck-camera-pose-unit-vector-multiplier + (cut:var-value + '?mult + (car + (prolog:prolog + `(and (rob-int:robot ?rob) + (rob-int:neck-camera-pose-unit-vector-multiplier ?rob ?mult)))))) (neck-base-t-object-short-vector - (cl-transforms:v* neck-base-t-object-unit-vector *camera-pose-unit-vector-multiplyer*)) + (cl-transforms:v* + neck-base-t-object-unit-vector + neck-camera-pose-unit-vector-multiplier)) (neck-base-t-object-short-vector-lifted - (cl-transforms:v+ neck-base-t-object-short-vector - (cl-transforms:make-3d-vector 0 0 *camera-pose-z-offset*))) - + (cl-transforms:v+ + neck-base-t-object-short-vector + (cl-transforms:make-3d-vector + 0 0 (cut:var-value + '?z-offset + (car (prolog:prolog + `(and (rob-int:robot ?robot) + (rob-int:neck-camera-z-offset ?robot ?z-offset)))))))) (neck-base-t-camera-not-oriented (cl-transforms:make-transform neck-base-t-object-short-vector-lifted @@ -284,8 +335,10 @@ with the object, calculates similar angle around Y axis and applies the rotation neck-base-t-object)) (rotation-angle-around-x (- (atan - (cl-transforms:y (cl-transforms:translation camera-not-oriented-t-object)) - (cl-transforms:z (cl-transforms:translation camera-not-oriented-t-object))))) + (cl-transforms:y + (cl-transforms:translation camera-not-oriented-t-object)) + (cl-transforms:z + (cl-transforms:translation camera-not-oriented-t-object))))) (neck-base-t-camera-rotated-around-x (cram-tf:rotate-transform-in-own-frame neck-base-t-camera-not-oriented @@ -299,8 +352,10 @@ with the object, calculates similar angle around Y axis and applies the rotation neck-base-t-object)) (rotation-angle-around-y (atan - (cl-transforms:x (cl-transforms:translation camera-rotated-around-x-t-object)) - (cl-transforms:z (cl-transforms:translation camera-rotated-around-x-t-object)))) + (cl-transforms:x + (cl-transforms:translation camera-rotated-around-x-t-object)) + (cl-transforms:z + (cl-transforms:translation camera-rotated-around-x-t-object)))) (neck-base-t-camera (cram-tf:rotate-transform-in-own-frame neck-base-t-camera-rotated-around-x @@ -310,7 +365,10 @@ with the object, calculates similar angle around Y axis and applies the rotation (defun look-at-pose-stamped-many-joints (object-pose) (declare (type cl-transforms-stamped:pose-stamped object-pose)) (let* ((map-p-object - (cram-tf:ensure-pose-in-frame object-pose cram-tf:*fixed-frame* :use-zero-time t)) + (cram-tf:ensure-pose-in-frame + object-pose + cram-tf:*fixed-frame* + :use-zero-time t)) (bindings (cut:lazy-car (prolog:prolog @@ -330,9 +388,10 @@ with the object, calculates similar angle around Y axis and applies the rotation (map-p-neck-base (btr:link-pose (btr:get-robot-object) neck-base-frame)) + (map-t-neck-base + (cl-transforms:pose->transform map-p-neck-base)) (neck-base-t-map - (cl-transforms:transform-inv - (cl-transforms:pose->transform map-p-neck-base))) + (cl-transforms:transform-inv map-t-neck-base)) (neck-base-t-object (cl-transforms:transform* neck-base-t-map @@ -342,14 +401,21 @@ with the object, calculates similar angle around Y axis and applies the rotation (calculate-camera-pose-from-object-pose neck-base-t-object)) (camera-t-neck-ee - (cl-transforms:transform-inv (cl-transforms:pose->transform neck-ee-p-camera))) + (cl-transforms:transform-inv + (cl-transforms:pose->transform neck-ee-p-camera))) (neck-base-t-neck-ee (cl-transforms:transform* neck-base-t-camera camera-t-neck-ee)) (neck-base-p-neck-ee (cl-transforms:transform->pose neck-base-t-neck-ee)) (joint-state - (get-neck-ik neck-ee-frame neck-base-p-neck-ee neck-base-frame neck-joints))) + (get-neck-ik neck-ee-frame neck-base-p-neck-ee + neck-base-frame neck-joints)) + + (map-t-camera + (cl-transforms:transform-pose map-t-neck-base neck-base-t-camera))) + + (btr:add-vis-axis-object map-t-camera) (if joint-state (look-at-joint-angles joint-state) @@ -365,8 +431,7 @@ with the object, calculates similar angle around Y axis and applies the rotation (prolog:prolog `(and (rob-int:robot ?robot) (btr:bullet-world ?w) - (rob-int:robot-neck-joints - ?robot . ?joint-names)))))))) + (rob-int:robot-neck-joints ?robot . ?joint-names)))))))) (if pose (if (= neck-joints-num 2) (look-at-pose-stamped-two-joints pose) @@ -431,7 +496,9 @@ with the object, calculates similar angle around Y axis and applies the rotation (quantifier (desig:quantifier input-designator)) ;; find all visible objects with name `object-name' and of type `object-type' - (name-pose-type-lists ; e.g.: ((mondamin-1 :mondamin ) (mug-2 :mug )) + ;; name-pose-type-lists is, e.g.: + ;; ((mondamin-1 :mondamin) (mug-2 :mug)) + (name-pose-type-lists (cut:force-ll (cut:lazy-mapcar (lambda (solution-bindings) @@ -442,7 +509,7 @@ with the object, calculates similar angle around Y axis and applies the rotation (btr:bullet-world ?world) ,@(when object-name `((prolog:== ?object-name ,object-name))) - (btr:object ?world ?object-name) + (btr:item ?world ?object-name) ;; it is possible to ask RoboSherlock for ;; (all object (type kitchen-object)) ;; which returns a list of all the objects RS sees @@ -461,15 +528,18 @@ with the object, calculates similar angle around Y axis and applies the rotation (unless name-pose-type-lists (cpl:fail 'common-fail:perception-object-not-found :object input-designator - :description (format nil "Could not find object ~a." input-designator))) + :description (format nil "Could not find object ~a." + input-designator))) - ;; Extend the input-designator with the information found through visibility check: - ;; name & pose & type of the object, + ;; Extend the input-designator with the information found + ;; through visibility check: name & pose & type of the object, ;; equate the input-designator to the new output-designator. ;; If multiple objects are visible, return multiple equated objects, - ;; otherwise only take first found object. I.e. need to find :an object (not :all objects) + ;; otherwise only take first found object. + ;; I.e. need to find :an object (not :all objects) (case quantifier - (:all (mapcar (alexandria:curry #'extend-perceived-object-designator input-designator) + (:all (mapcar (alexandria:curry #'extend-perceived-object-designator + input-designator) name-pose-type-lists)) ((:a :an) (extend-perceived-object-designator input-designator @@ -487,16 +557,17 @@ with the object, calculates similar angle around Y axis and applies the rotation (prolog:prolog `(and (btr:bullet-world ?world) - (assert ?world (btr:joint-state ?robot - ((?joint ,(case action-type - (:open '?max-limit) - ((:close :grip) '?min-limit) - (T (if (numberp action-type) - (* action-type - (cut:var-value - '?mult - solution-bindings)) - (error "[PROJ GRIP] failed"))))))))) + (assert ?world + (btr:joint-state ?robot + ((?joint ,(case action-type + (:open '?max-limit) + ((:close :grip) '?min-limit) + (T (if (numberp action-type) + (* action-type + (cut:var-value + '?mult solution-bindings)) + (error + "[PROJ GRIP] failed"))))))))) solution-bindings)) (cut:force-ll @@ -508,12 +579,13 @@ with the object, calculates similar angle around Y axis and applies the rotation (rob-int:gripper-meter-to-joint-multiplier ?robot ?mult))))) ;; check if there is an object to grip - (when (eql action-type :grip) ; if action was gripping check if gripper collided with an item + ;; i.e. if action was gripping check if gripper collided with an item + (when (eql action-type :grip) (unless (prolog:prolog `(and (btr:bullet-world ?world) (rob-int:robot ?robot) (btr:contact ?world ?robot ?object-name ?link) - (rob-int:gripper-link ?robot ,arm ?link) + (rob-int:hand-link ?robot ,arm ?link) (btr:%object ?world ?object-name ?object-instance) ;; (or (prolog:lisp-type ?object-instance btr:item) ;; (prolog:lisp-type ?object-instance btr:robot-object)) @@ -530,6 +602,182 @@ with the object, calculates similar angle around Y axis and applies the rotation ;;;;;;;;;;;;;;;;; ARMS ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;;; utilities and collision check function + +(defun calculate-base-pose-with-torso-offsets (map-p-base map-p-torso + x-offset y-offset) + (declare (type cl-transforms:pose map-p-base map-p-torso) + (type (or null number) x-offset y-offset)) + (if (or (and (not x-offset) (not y-offset)) + (and (equalp x-offset 0.0) (equalp y-offset 0.0))) + map-p-base + (let* ((x-offset + (or x-offset 0.0)) + (y-offset + (or y-offset 0.0)) + (map-t-base + (cram-tf:pose->transform-stamped + cram-tf:*fixed-frame* cram-tf:*robot-base-frame* 0.0 + map-p-base)) + (map-t-torso + (cram-tf:pose->transform-stamped + cram-tf:*fixed-frame* cram-tf:*robot-torso-frame* 0.0 + map-p-torso)) + (base-t-torso + (cram-tf:apply-transform + (cram-tf:transform-stamped-inv map-t-base) + map-t-torso)) + (torso-t-base + (cram-tf:transform-stamped-inv + base-t-torso)) + (torso-t-torso-offsetted + (cl-transforms-stamped:make-transform-stamped + cram-tf:*robot-torso-frame* + cram-tf:*robot-torso-frame* + 0.0 + (cl-transforms:make-3d-vector x-offset y-offset 0.0) + (cl-transforms:make-identity-rotation))) + (map-t-base-offsetted + (reduce + #'cram-tf:apply-transform + `(,map-t-base ,base-t-torso ,torso-t-torso-offsetted ,torso-t-base)))) + (cram-tf:strip-transform-stamped map-t-base-offsetted)))) + +(defun apply-torso-offsets (torso-offsets) + (let* ((torso-offset-x + (cdr (assoc :x torso-offsets))) + (torso-offset-y + (cdr (assoc :y torso-offsets))) + (torso-offset-z + (cdr (assoc :z torso-offsets))) + (current-torso-angle + (btr:joint-state (btr:get-robot-object) cram-tf:*robot-torso-joint*)) + (new-torso-angle + (+ current-torso-angle torso-offset-z)) + (new-base-pose-stamped + (calculate-base-pose-with-torso-offsets + (btr:pose (btr:get-robot-object)) + (btr:link-pose (btr:get-robot-object) cram-tf:*robot-torso-frame*) + torso-offset-x torso-offset-y))) + (move-torso new-torso-angle) + (setf (btr:pose (btr:get-robot-object)) new-base-pose-stamped))) + +(defun perform-collision-check (collision-mode left-hand-moves right-hand-moves + &optional + joint-state-msg + torso-offsets + object-name-to-allow-collisions-with) + (declare (type (or keyword null) collision-mode) + (type (or sensor_msgs-msg:jointstate null) joint-state-msg) + (type list torso-offsets) + (type (or keyword string null) object-name-to-allow-collisions-with)) + "Returns NIL if current joint state does not result in collisions +and returns (not throws or fails but simply returns) an error instance, +if a collision occurs. +`left-hand-moves' and `right-hand-moves' are used as flags for the :allow-hand +collision mode, to see which hand is currently moving and can be allowed collisions. +If `joint-state-msg' is given, check collisions in that joint state + (and restore the world to original state afterwards), +otherwise check collisions in current joint state. +Same goes for `torso-offsets', if they are given, move the robot torso and base +with the given offsets (the offsets are specified in the torso frame). +`torso-offsets' is a list of (:x/:y/:z offset-in-torso-frame) entries." + (flet ((the-actual-collision-check (collision-mode + left-hand-moves right-hand-moves) + (ecase collision-mode + (:allow-all + nil) + (:allow-attached + ;; allow-attached means the robot is not allowed to hit anything + ;; (except the object it is holding), + ;; but the object it is holding can create collisions + ;; with environment etc. + (when (and *be-strict-with-collisions* + (btr:robot-colliding-objects-without-attached)) + (make-instance 'common-fail:manipulation-goal-not-reached + :description "Robot is in collision with environment."))) + ((or :allow-hand + :allow-arm) + ;; allow hand allows collisions between the hand and anything + ;; but not the rest of the robot + ;; therefore, we take a list of all links of the robot + ;; that are colliding with something, + ;; remove attached object collisions from this list, + ;; and then remove the hand links from the list. + ;; if the list is still not empty, there is a collision between + ;; a robot non-hand link and something else + (when (and + *be-strict-with-collisions* + (set-difference + (mapcar + #'cdr + (reduce + (lambda (link-contacts attachment) + (remove + (btr:object btr:*current-bullet-world* (car attachment)) + link-contacts + :key #'car)) + (append + (list (btr:link-contacts (btr:get-robot-object))) + (btr:attached-objects (btr:get-robot-object))))) + (append + (when left-hand-moves + (cut:var-value + '?links + (car + (prolog:prolog + `(and + (rob-int:robot ?robot) + ,(ecase collision-mode + (:allow-hand + '(rob-int:hand-links ?robot :left ?links)) + (:allow-arm + '(rob-int:arm-links ?robot :left ?links)))))))) + (when right-hand-moves + (cut:var-value + '?links + (car + (prolog:prolog + `(and + (rob-int:robot ?robot) + ,(ecase collision-mode + (:allow-hand + '(rob-int:hand-links ?robot :right ?links)) + (:allow-arm + '(rob-int:arm-links ?robot :right ?links))))))))) + :test #'string-equal)) + (make-instance 'common-fail:manipulation-goal-not-reached + :description "Robot is in collision with environment."))) + (:avoid-all + ;; avoid-all means the robot is not colliding with anything except the + ;; objects it is holding, and the object it is holding + ;; only collides with robot + (when (or (remove object-name-to-allow-collisions-with + (btr:robot-colliding-objects-without-attached)) + (remove object-name-to-allow-collisions-with + (btr:robot-attached-objects-in-collision))) + (make-instance 'common-fail:manipulation-goal-not-reached + :description "Robot is in collision with environment.")))))) + + (unless collision-mode + (setf collision-mode :avoid-all)) + ;; if joint state is given, first set the robot to given state, + ;; then perform the collision check, then restore the robot to original state + (if (or torso-offsets joint-state-msg) + (let ((world-pose-info (btr:get-world-objects-pose-info))) + (unwind-protect + (progn + (when joint-state-msg + (btr:set-robot-state-from-joints + joint-state-msg (btr:get-robot-object))) + (when torso-offsets + (apply-torso-offsets torso-offsets)) + (the-actual-collision-check + collision-mode left-hand-moves right-hand-moves)) + (btr:restore-world-poses world-pose-info))) + (the-actual-collision-check + collision-mode left-hand-moves right-hand-moves)))) + ;;; joint movement (defun move-joints (left-configuration right-configuration) @@ -544,9 +792,11 @@ with the object, calculates similar angle around Y axis and applies the rotation '?joints (car (prolog:prolog `(and (rob-int:robot ?robot) - (rob-int:arm-joints ?robot ,arm ?joints))))))) + (rob-int:arm-joints ?robot ,arm + ?joints))))))) (unless (= (length joint-values) (length joint-names)) - (error "[PROJECTION MOVE-JOINTS] length of joints list is incorrect")) + (error "[PROJECTION MOVE-JOINTS] length of joints list ~ + is incorrect")) (mapcar (lambda (name value) (list name (* value 1.0d0))) joint-names joint-values))))) @@ -566,19 +816,86 @@ with the object, calculates similar angle around Y axis and applies the rotation joint-name-value-list)) (goal-joint-state (mapcar #'second joint-name-value-list))) - (unless (cram-tf:values-converged current-joint-state goal-joint-state - *projection-convergence-delta-joint*) + (unless (cram-tf:values-converged + (cram-tf:normalize-joint-angles current-joint-state) + (cram-tf:normalize-joint-angles goal-joint-state) + *projection-convergence-delta-joint*) (cpl:fail 'common-fail:manipulation-goal-not-reached - :description (format nil "Projection did not converge to goal:~%~ - ~a (~a)~%should have been at~%~a~%~ - with delta-joint of ~a." - arm - current-joint-state - goal-joint-state - *projection-convergence-delta-joint*)))))))) + :description + (format nil + "Projection did not converge to goal:~%~ + ~a (~a)~%should have been at~%~a~%~ + with delta-joint of ~a." + arm + (cram-tf:normalize-joint-angles + current-joint-state) + (cram-tf:normalize-joint-angles + goal-joint-state) + *projection-convergence-delta-joint*)))))))) (set-configuration :left left-configuration) (set-configuration :right right-configuration))) +(defun move-joints-avoiding-collision (left-configuration right-configuration + &optional collision-mode) + "Moves arm joints with the specified configuration but tries to avoid +collision by moving its torso and base" + (cut:with-vars-strictly-bound (?torso-joint + ?torso-lower-limit ?torso-upper-limit) + (cut:lazy-car + (prolog:prolog + `(and + (rob-int:robot ?robot) + (rob-int:robot-torso-link-joint ?robot ?torso-link ?torso-joint) + (rob-int:joint-lower-limit ?robot ?torso-joint ?torso-lower-limit) + (rob-int:joint-upper-limit ?robot ?torso-joint ?torso-upper-limit)))) + (let* ((current-torso-angle + (btr:joint-state (btr:get-robot-object) ?torso-joint)) + (validation-function + (lambda (torso-offsets) + (not (perform-collision-check + collision-mode + left-configuration + right-configuration + nil + torso-offsets)))) + (joint-values + (ik:find-joint-values-for (validation-function) + (ik:with-resampling + (:x + *base-resampling-x-limit* + (- *base-resampling-x-limit*) + *base-resampling-step*) + (ik:with-resampling + (:y + *base-resampling-y-limit* + (- *base-resampling-y-limit*) + *base-resampling-step*) + (ik:with-resampling + (:z + (- ?torso-upper-limit current-torso-angle) + (- ?torso-lower-limit current-torso-angle) + *torso-resampling-step*) + (move-joints left-configuration right-configuration))))))) + + (when joint-values + (let* ((torso-offset-z + (cdr (assoc :z joint-values))) + (new-torso-angle + (+ current-torso-angle torso-offset-z)) + (torso-offset-x + (cdr (assoc :x joint-values))) + (torso-offset-y + (cdr (assoc :y joint-values))) + (new-base-pose-stamped + (calculate-base-pose-with-torso-offsets + (btr:pose (btr:get-robot-object)) + (btr:link-pose (btr:get-robot-object) + cram-tf:*robot-torso-frame*) + torso-offset-x torso-offset-y))) + (move-torso new-torso-angle) + (setf (btr:pose (btr:get-robot-object)) new-base-pose-stamped))))) + (perform-collision-check collision-mode left-configuration right-configuration)) + ;;; cartesian movement (defun tcp-pose->ee-pose (tcp-pose tool-frame end-effector-frame) @@ -680,91 +997,77 @@ with the object, calculates similar angle around Y axis and applies the rotation :result-as-pose-or-transform :pose))) (error "Arm movement goals should be given in map frame")))) -(defparameter *torso-resampling-step* 0.1) - (defun get-ik-joint-positions (ee-pose base-link end-effector-link joint-names torso-joint-name - torso-joint-lower-limit torso-joint-upper-limit) + torso-joint-lower-limit torso-joint-upper-limit + validation-function + move-base) (when ee-pose - (multiple-value-bind (ik-solution-msg torso-angle) - (let ((torso-current-angle - (btr:joint-state - (btr:get-robot-object) - torso-joint-name)) - (seed-state-msg - (btr::make-robot-joint-state-msg - (btr:get-robot-object) - :joint-names joint-names))) - (ik:call-ik-service-with-resampling - ee-pose base-link end-effector-link seed-state-msg *torso-resampling-step* :z - torso-current-angle torso-joint-lower-limit torso-joint-upper-limit)) - (unless ik-solution-msg - (cpl:fail 'common-fail:manipulation-pose-unreachable - :description (format nil "~a is unreachable for EE." ee-pose))) - (values (map 'list #'identity (roslisp:msg-slot-value ik-solution-msg :position)) - torso-angle)))) - -(defun perform-collision-check (collision-mode left-tcp-pose right-tcp-pose) - (unless collision-mode - (setf collision-mode :avoid-all)) - (ecase collision-mode - (:allow-all - nil) - (:allow-attached - ;; allow-attached means the robot is not allowed to hit anything - ;; (except the object it is holding), - ;; but the object it is holding can create collisions with environment etc. - (when (and *be-strict-with-collisions* - (btr:robot-colliding-objects-without-attached)) - (cpl:fail 'common-fail:manipulation-goal-not-reached - :description "Robot is in collision with environment."))) - (:allow-hand - ;; allow hand allows collisions between the hand and anything - ;; but not the rest of the robot - ;; therefore, we take a list of all links of the robot that are colliding - ;; with something, remove attached object collisions from this list, - ;; and then remove the hand links from the list. - ;; if the list is still not empty, there is a collision between - ;; a robot non-hand link and something else - (when (and *be-strict-with-collisions* - (set-difference - (mapcar #'cdr - (reduce (lambda (link-contacts attachment) - (remove (btr:object - btr:*current-bullet-world* - (car attachment)) - link-contacts - :key #'car)) - (append - (list (btr:link-contacts (btr:get-robot-object))) - (btr:attached-objects (btr:get-robot-object))))) - (append (when left-tcp-pose - (cut:var-value - '?hand-links - (car (prolog:prolog - `(and (rob-int:robot ?robot) - (rob-int:hand-links ?robot :left ?hand-links)))))) - (when right-tcp-pose - (cut:var-value - '?hand-links - (car (prolog:prolog - `(and (rob-int:robot ?robot) - (rob-int:hand-links ?robot :right ?hand-links))))))) - :test #'string-equal)) - (cpl:fail 'common-fail:manipulation-goal-not-reached - :description "Robot is in collision with environment."))) - (:avoid-all - ;; avoid-all means the robot is not colliding with anything except the - ;; objects it is holding, and the objects it is holding only collides with robot - (when (or (btr:robot-colliding-objects-without-attached) - (btr:robot-attached-objects-in-collision)) - (cpl:fail 'common-fail:manipulation-goal-not-reached - :description "Robot is in collision with environment."))))) - -(defun move-tcp (left-tcp-pose right-tcp-pose - &optional collision-mode - collision-object-b collision-object-b-link collision-object-a) - (declare (type (or cl-transforms-stamped:pose-stamped null) left-tcp-pose right-tcp-pose)) + (let ((current-torso-angle + (btr:joint-state (btr:get-robot-object) torso-joint-name)) + (seed-state-msg + (btr::make-robot-joint-state-msg + (btr:get-robot-object) + :joint-names joint-names)) + (disable-base-resampling + (not move-base))) + (multiple-value-bind (ik-solution-msg joint-values) + (ik:find-ik-for + (ee-pose + base-link + end-effector-link + seed-state-msg + validation-function) + (ik:with-resampling + (:x + *base-resampling-x-limit* + (- *base-resampling-x-limit*) + *base-resampling-step* + :disable-resampling disable-base-resampling) + (ik:with-resampling + (:y + *base-resampling-y-limit* + (- *base-resampling-y-limit*) + *base-resampling-step* + :disable-resampling disable-base-resampling) + (ik:with-resampling + (:z + (- torso-joint-upper-limit current-torso-angle) + (- torso-joint-lower-limit current-torso-angle) + *torso-resampling-step*))))) + (unless ik-solution-msg + (cpl:fail 'common-fail:manipulation-low-level-failure + :description + (format nil "~a is unreachable for EE or is in collision." + ee-pose))) + (let* ((torso-offset-z + (cdr (assoc :z joint-values))) + (new-torso-angle + (+ current-torso-angle torso-offset-z)) + (torso-offset-x + (cdr (assoc :x joint-values))) + (torso-offset-y + (cdr (assoc :y joint-values))) + (new-base-pose-stamped + (calculate-base-pose-with-torso-offsets + (btr:pose (btr:get-robot-object)) + (btr:link-pose (btr:get-robot-object) cram-tf:*robot-torso-frame*) + torso-offset-x torso-offset-y))) + (values (map 'list #'identity + (roslisp:msg-slot-value ik-solution-msg :position)) + new-torso-angle + new-base-pose-stamped)))))) + +(defun move-tcp-one-pose (left-tcp-pose right-tcp-pose + &optional + collision-mode + collision-object-b + collision-object-b-link + collision-object-a + (move-base t)) + (declare (type (or cl-transforms-stamped:pose-stamped null) + left-tcp-pose right-tcp-pose) + (type boolean move-base)) (declare (ignore collision-object-b collision-object-b-link collision-object-a)) (cram-tf:visualize-marker (list left-tcp-pose right-tcp-pose) :r-g-b-list '(1 0 1)) @@ -772,55 +1075,151 @@ with the object, calculates similar angle around Y axis and applies the rotation (btr:add-vis-axis-object right-tcp-pose)) (when left-tcp-pose (btr:add-vis-axis-object left-tcp-pose)) - (cut:with-vars-strictly-bound (?robot ?left-tool-frame ?right-tool-frame ?left-ee-frame ?right-ee-frame ?left-arm-joints ?right-arm-joints - ?torso-link ?torso-joint ?lower-limit ?upper-limit) + ?torso-link ?torso-joint + ?lower-limit ?upper-limit) (cut:lazy-car (prolog:prolog `(and (rob-int:robot ?robot) - (rob-int:robot-tool-frame ?robot :left ?left-tool-frame) - (rob-int:robot-tool-frame ?robot :right ?right-tool-frame) - (rob-int:end-effector-link ?robot :left ?left-ee-frame) - (rob-int:end-effector-link ?robot :right ?right-ee-frame) - (rob-int:arm-joints ?robot :left ?left-arm-joints) - (rob-int:arm-joints ?robot :right ?right-arm-joints) + (once (or (rob-int:robot-tool-frame ?robot :left ?left-tool-frame) + (equal ?left-tool-frame nil))) + (once (or (rob-int:robot-tool-frame ?robot :right ?right-tool-frame) + (equal ?right-tool-frame nil))) + (once (or (rob-int:end-effector-link ?robot :left ?left-ee-frame) + (equal ?left-ee-frame nil))) + (once (or (rob-int:end-effector-link ?robot :right ?right-ee-frame) + (equal ?right-ee-frame nil))) + (once (or (rob-int:arm-joints ?robot :left ?left-arm-joints) + (equal ?left-arm-joints nil))) + (once (or (rob-int:arm-joints ?robot :right ?right-arm-joints) + (equal ?right-arm-joints nil))) (rob-int:robot-torso-link-joint ?robot ?torso-link ?torso-joint) (rob-int:joint-lower-limit ?robot ?torso-joint ?lower-limit) (rob-int:joint-upper-limit ?robot ?torso-joint ?upper-limit)))) - (multiple-value-bind (left-ik left-torso-angle) - ;; TODO: the LET is a temporary hack until we get a relay running for PR2 - ;; such that both arms IKs go over the same ROS service - (let ((ik::*ik-service-name* - (if (string-equal (symbol-name ?robot) "PR2") - "pr2_left_arm_kinematics/get_ik" - "kdl_ik_service/get_ik"))) - (get-ik-joint-positions (ee-pose-in-map->ee-pose-in-torso - (tcp-pose->ee-pose left-tcp-pose - ?left-tool-frame ?left-ee-frame)) - ?torso-link ?left-ee-frame ?left-arm-joints - ?torso-joint ?lower-limit ?upper-limit)) - (multiple-value-bind (right-ik right-torso-angle) + (let ((validation-function + (lambda (ik-solution-msg torso-offsets) + (not (perform-collision-check + collision-mode left-tcp-pose right-tcp-pose + ik-solution-msg torso-offsets))))) + (multiple-value-bind (left-ik left-torso-angle left-base-pose) + ;; TODO: the LET is a temporary hack until we get a relay running + ;; for PR2 such that both arms IKs go over the same ROS service (let ((ik::*ik-service-name* - (if (string-equal (symbol-name ?robot) "PR2") - "pr2_right_arm_kinematics/get_ik" + (if (eql ?robot :pr2) + "pr2_left_arm_kinematics/get_ik" "kdl_ik_service/get_ik"))) - (get-ik-joint-positions (ee-pose-in-map->ee-pose-in-torso - (tcp-pose->ee-pose right-tcp-pose - ?right-tool-frame ?right-ee-frame)) - ?torso-link ?right-ee-frame ?right-arm-joints - ?torso-joint ?lower-limit ?upper-limit)) - (cond - ((and left-torso-angle right-torso-angle) - (when (not (eq left-torso-angle right-torso-angle)) - (cpl:fail 'common-fail:manipulation-pose-unreachable - :description (format nil "In MOVE-TCP goals for the two arms ~ - require different torso angles)."))) - (move-torso left-torso-angle)) - (left-torso-angle (move-torso left-torso-angle)) - (right-torso-angle (move-torso right-torso-angle))) - (move-joints left-ik right-ik) - (perform-collision-check collision-mode left-tcp-pose right-tcp-pose))))) + (get-ik-joint-positions + (ee-pose-in-map->ee-pose-in-torso + (tcp-pose->ee-pose left-tcp-pose ?left-tool-frame ?left-ee-frame)) + ?torso-link ?left-ee-frame ?left-arm-joints + ?torso-joint ?lower-limit ?upper-limit + validation-function + move-base)) + (multiple-value-bind (right-ik right-torso-angle right-base-pose) + (let ((ik::*ik-service-name* + (if (eql ?robot :pr2) + "pr2_right_arm_kinematics/get_ik" + "kdl_ik_service/get_ik"))) + (get-ik-joint-positions + (ee-pose-in-map->ee-pose-in-torso + (tcp-pose->ee-pose right-tcp-pose ?right-tool-frame ?right-ee-frame)) + ?torso-link ?right-ee-frame ?right-arm-joints + ?torso-joint ?lower-limit ?upper-limit + validation-function + move-base)) + ;; set the torso to inferred position + (cond + ((and left-torso-angle right-torso-angle) + (if (eq left-torso-angle right-torso-angle) + (move-torso left-torso-angle) + (cpl:fail 'common-fail:manipulation-pose-unreachable + :description (format nil "In MOVE-TCP goals ~ + for the two arms require different ~ + torso angles.")))) + (left-torso-angle + (move-torso left-torso-angle)) + (right-torso-angle + (move-torso right-torso-angle))) + ;; set the base to inferred position + (cond + ((and left-base-pose right-base-pose) + (if (funcall (cram-tf:make-euclidean-distance-filter + left-base-pose *base-resampling-step*) + right-base-pose) + (setf (btr:pose (btr:get-robot-object)) left-base-pose) + (cpl:fail 'common-fail:manipulation-pose-unreachable + :description (format nil "In MOVE-TCP goals ~ + for the two arms require different ~ + base-poses.")))) + (left-base-pose + (setf (btr:pose (btr:get-robot-object)) left-base-pose)) + (right-base-pose + (setf (btr:pose (btr:get-robot-object)) right-base-pose))) + ;; set the arm joints to inferred position + (move-joints left-ik right-ik) + ;; perform one last collision check + (perform-collision-check collision-mode left-tcp-pose right-tcp-pose)))))) + +(defun move-tcp (left-poses right-poses + &optional + collision-mode + collision-object-b + collision-object-b-link + collision-object-a + (move-base t)) + (declare (type (or cl-transforms-stamped:pose-stamped list null) + left-poses right-poses) + (type boolean move-base)) + + (multiple-value-bind (left-poses right-poses) + (cut:equalize-two-list-lengths left-poses right-poses) + + ;; Move arms through all but last poses of `left-poses' and `right-poses' + ;; while ignoring failures: accuracy is not so important in intermediate poses. + (mapc (lambda (left-pose right-pose) + (cpl:with-failure-handling + ;; ignore intermediate pose failures + ((common-fail:manipulation-low-level-failure (e) + (roslisp:ros-warn (urdf-proj move-tcp) "~a~%Ignoring." e) + (return))) + (move-tcp-one-pose left-pose right-pose + collision-mode collision-object-b + collision-object-b-link collision-object-a + move-base))) + (butlast left-poses) + (butlast right-poses)) + + ;; Move arm to the last pose of `left-poses' and `right-poses'. + (let ((left-pose (car (last left-poses))) + (right-pose (car (last right-poses)))) + (cpl:with-failure-handling + ((common-fail:manipulation-low-level-failure (e) + ;; propagate failures up + (roslisp:ros-error (urdf-proj move-tcp) "~a~%Failing." e))) + (move-tcp-one-pose left-pose right-pose + collision-mode collision-object-b + collision-object-b-link collision-object-a + move-base))))) + + +#+save-for-next-time +((giskard:call-giskard-cartesian-action :goal-pose-left (cl-transforms-stamped:make-pose-stamped "l_gripper_tool_frame" 0.0 (cl-transforms:make-identity-vector) (cl-transforms:make-identity-rotation))) + (let* ((root-link (cl-urdf:name (cl-urdf:root-link (btr:urdf (btr:get-robot-object))))) + (robot-transform + (handler-case + (cl-transforms-stamped:lookup-transform + cram-tf:*transformer* cram-tf:*fixed-frame* root-link + :time 0.0 :timeout cram-tf:*tf-default-timeout*) + (cl-tf:transform-stamped-error (error) + (roslisp:ros-warn (set-robot-state-from-tf) + "Failed with transform-stamped-error:~% ~a~% ~ + Ignore this warning if no real robot is running." + error) + NIL)))) + (when robot-transform + (setf (btr:link-pose (btr:get-robot-object) root-link) + (cl-transforms:transform->pose robot-transform))))) diff --git a/cram_3d_world/cram_urdf_projection/src/process-modules.lisp b/cram_3d_world/cram_urdf_projection/src/process-modules.lisp index dd1e3a0779..4e4b0f5e44 100644 --- a/cram_3d_world/cram_urdf_projection/src/process-modules.lisp +++ b/cram_3d_world/cram_urdf_projection/src/process-modules.lisp @@ -32,46 +32,68 @@ ;;;;;;;;;;;;;;;;; NAVIGATION ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; (cpm:def-process-module urdf-proj-navigation (motion-designator) - (destructuring-bind (command argument) (desig:reference motion-designator) + (destructuring-bind (command argument) + (desig:reference motion-designator) (ecase command - (cram-common-designators:move-base (drive argument))))) + (cram-common-designators:move-base + (drive argument))))) ;;;;;;;;;;;;;;;;; TORSO ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; (cpm:def-process-module urdf-proj-torso (motion-designator) - (destructuring-bind (command argument) (desig:reference motion-designator) + (destructuring-bind (command argument) + (desig:reference motion-designator) (ecase command - (cram-common-designators:move-torso (move-torso argument))))) + (cram-common-designators:move-torso + (move-torso argument))))) ;;;;;;;;;;;;;;;;; NECK ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; (cpm:def-process-module urdf-proj-neck (motion-designator) - (destructuring-bind (command goal-pose goal-configuration) (desig:reference motion-designator) + (destructuring-bind (command goal-pose goal-configuration) + (desig:reference motion-designator) (ecase command - (cram-common-designators:move-head (look-at goal-pose goal-configuration))))) + (cram-common-designators:move-head + (look-at goal-pose goal-configuration))))) ;;;;;;;;;;;;;;;;; PERCEPTION ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; (cpm:def-process-module urdf-proj-perception (motion-designator) - (destructuring-bind (command argument-1) (desig:reference motion-designator) + (destructuring-bind (command argument-1) + (desig:reference motion-designator) (ecase command - (cram-common-designators:detect (detect argument-1))))) + (cram-common-designators:detect + (detect argument-1))))) ;;;;;;;;;;;;;;;;; GRIPPERS ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; (cpm:def-process-module urdf-proj-grippers (motion-designator) - (destructuring-bind (command arg-1 arg-2 &rest arg-3) (desig:reference motion-designator) + (destructuring-bind (command arg-1 arg-2 &rest arg-3) + (desig:reference motion-designator) (ecase command - (cram-common-designators:move-gripper-joint (gripper-action arg-1 arg-2 (car arg-3)))))) + (cram-common-designators:move-gripper-joint + (gripper-action arg-1 arg-2 (car arg-3)))))) ;;;;;;;;;;;;;;;;; ARMS ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; (cpm:def-process-module urdf-proj-arms (motion-designator) - (destructuring-bind (command arg-1 &rest arg-2) (desig:reference motion-designator) + (destructuring-bind (command arg-1 &rest arg-2) + (desig:reference motion-designator) (ecase command - (cram-common-designators:move-tcp (move-tcp arg-1 (first arg-2) (second arg-2) - (third arg-2) (fourth arg-2) (fifth arg-2))) - (cram-common-designators::move-joints (move-joints arg-1 (car arg-2)))))) + (cram-common-designators:move-tcp + (move-tcp arg-1 (first arg-2) + (second arg-2) (third arg-2) (fourth arg-2) (fifth arg-2) + (sixth arg-2))) + (cram-common-designators::move-joints + (move-joints-avoiding-collision arg-1 (first arg-2) (second arg-2))) + ((or cram-common-designators:move-arm-pull + cram-common-designators:move-arm-push) + (move-tcp (when (eq arg-1 :left) + (first arg-2)) + (when (eq arg-1 :right) + (first arg-2)) + (third arg-2) (fourth arg-2) (fifth arg-2) (sixth arg-2) + (seventh arg-2)))))) ;;;;;;;;;;;;;;;;;;;;; PREDICATES ;;;;;;;;;;;;;;;;;;;;;;;; @@ -98,4 +120,6 @@ (<- (cpm:matching-process-module ?motion-designator urdf-proj-arms) (or (desig:desig-prop ?motion-designator (:type :moving-tcp)) - (desig:desig-prop ?motion-designator (:type :moving-arm-joints))))) + (desig:desig-prop ?motion-designator (:type :moving-arm-joints)) + (desig:desig-prop ?motion-designator (:type :pulling)) + (desig:desig-prop ?motion-designator (:type :pushing))))) diff --git a/cram_3d_world/cram_urdf_projection/src/projection-environment.lisp b/cram_3d_world/cram_urdf_projection/src/projection-environment.lisp index 51a85910cd..27c9b57982 100644 --- a/cram_3d_world/cram_urdf_projection/src/projection-environment.lisp +++ b/cram_3d_world/cram_urdf_projection/src/projection-environment.lisp @@ -144,7 +144,7 @@ (exe:perform (desig:a motion (type moving-gripper-joint) (gripper right) (joint-angle 0.05))) (exe:perform - (let ((?pose (cl-tf:make-pose-stamped + (let ((?pose (cl-transforms-stamped:make-pose-stamped cram-tf:*robot-base-frame* 0.0 (cl-transforms:make-3d-vector 0.8 0.4 1.0) (cl-transforms:make-identity-rotation)))) diff --git a/cram_3d_world/cram_urdf_projection_reasoning/cram-urdf-projection-reasoning.asd b/cram_3d_world/cram_urdf_projection_reasoning/cram-urdf-projection-reasoning.asd index a29f791460..2a35243064 100644 --- a/cram_3d_world/cram_urdf_projection_reasoning/cram-urdf-projection-reasoning.asd +++ b/cram_3d_world/cram_urdf_projection_reasoning/cram-urdf-projection-reasoning.asd @@ -45,6 +45,7 @@ cram-common-failures cram-mobile-pick-place-plans + cram-robot-interfaces ; for get-robot-name cram-tf cl-transforms-stamped cl-transforms diff --git a/cram_3d_world/cram_urdf_projection_reasoning/package.xml b/cram_3d_world/cram_urdf_projection_reasoning/package.xml index 8317a66cba..23d31f94ac 100644 --- a/cram_3d_world/cram_urdf_projection_reasoning/package.xml +++ b/cram_3d_world/cram_urdf_projection_reasoning/package.xml @@ -24,6 +24,7 @@ cram_occasions_events cram_common_failures cram_mobile_pick_place_plans + cram_robot_interfaces cram_tf cl_transforms_stamped cl_transforms diff --git a/cram_3d_world/cram_urdf_projection_reasoning/src/check-collisions.lisp b/cram_3d_world/cram_urdf_projection_reasoning/src/check-collisions.lisp index 850fa95e4b..176a11df08 100644 --- a/cram_3d_world/cram_urdf_projection_reasoning/src/check-collisions.lisp +++ b/cram_3d_world/cram_urdf_projection_reasoning/src/check-collisions.lisp @@ -41,8 +41,7 @@ Repeat `navigation-location-samples' + 1 times. Store found pose into designator or throw error if good pose not found." (when *projection-checks-enabled* - (let* ((world btr:*current-bullet-world*) - (world-state (btr::get-state world))) + (let ((world-pose-info (btr:get-world-objects-pose-info))) (unwind-protect (cpl:with-failure-handling ((desig:designator-error (e) @@ -89,17 +88,15 @@ Store found pose into designator or throw error if good pose not found." ;; "Found non-colliding pose~%~a to satisfy~%~a." ;; pose-at-navigation-location navigation-location-desig) navigation-location-desig)))) - (btr::restore-world-state world-state world))))) - + (btr:restore-world-poses world-pose-info))))) (defun check-picking-up-collisions (pick-up-action-desig &optional (retries 30)) (when *projection-checks-enabled* - (let* ((world btr:*current-bullet-world*) - (world-state (btr::get-state world))) - + (let ((world-pose-info (btr:get-world-objects-pose-info))) (unwind-protect + (cpl:with-failure-handling ((desig:designator-error (e) (roslisp:ros-warn (coll-check pick) @@ -114,7 +111,7 @@ Store found pose into designator or throw error if good pose not found." ;; If no configuration is good, throw `object-unreachable' failure (cpl:with-retry-counters ((pick-up-configuration-retries retries)) (cpl:with-failure-handling - (((or common-fail:manipulation-pose-unreachable + (((or common-fail:manipulation-low-level-failure common-fail:manipulation-goal-in-collision) (e) (declare (ignore e)) (urdf-proj::move-torso :upper-limit) @@ -126,7 +123,7 @@ Store found pose into designator or throw error if good pose not found." (progn (roslisp:ros-warn (coll-check pick) "No more pick-up samples to try.~ - Object unreachable.") + Object unreachable.") (cpl:fail 'common-fail:object-unreachable :description "No more pick-up samples to try.")))) (roslisp:ros-warn (coll-check pick) "No more retries left :'(") @@ -176,146 +173,172 @@ Store found pose into designator or throw error if good pose not found." :allow-all) (unless (< (abs urdf-proj::*debug-short-sleep-duration*) 0.0001) (cpl:sleep urdf-proj::*debug-short-sleep-duration*)) - (when ;; (remove object-name - ;; (btr:robot-colliding-objects-without-attached)) - (urdf-proj::perform-collision-check - collision-flag (nth i left-poses) (nth i right-poses)) + (when (urdf-proj::perform-collision-check + collision-flag + (nth i left-poses) (nth i right-poses) + nil nil object-name) (roslisp:ros-warn (coll-check pick) "Robot is in collision with environment.") (cpl:sleep urdf-proj::*debug-long-sleep-duration*) - (btr::restore-world-state world-state world) + (btr:restore-world-poses world-pose-info) (cpl:fail 'common-fail:manipulation-goal-in-collision))))) (list left-reach-poses left-grasp-poses left-lift-poses) (list right-reach-poses right-grasp-poses right-lift-poses) (list :avoid-all :allow-hand :avoid-all)))))) - (btr::restore-world-state world-state world))))) + (btr:restore-world-poses world-pose-info))))) -(defun check-placing-collisions (placing-action-desig) + +(defun check-placing-collisions (placing-action-desig &optional (retries 3)) (when *projection-checks-enabled* - (let* ((world btr:*current-bullet-world*) - (world-state (btr::get-state world))) + (let ((world-pose-info (btr:get-world-objects-pose-info))) (unwind-protect + (cpl:with-failure-handling ((desig:designator-error (e) (roslisp:ros-warn (coll-check place) "Desig ~a could not be resolved: ~a~%Cannot pick." placing-action-desig e) (cpl:fail 'common-fail:object-unreachable - :description "Designator could not be resolved")) + :description "Designator could not be resolved"))) - ((or common-fail:manipulation-goal-in-collision - common-fail:manipulation-low-level-failure) (e) - (declare (ignore e)) - (roslisp:ros-warn (coll-check place) - "Placing pose of ~a is unreachable.~%Propagating up." - placing-action-desig) - (cpl:fail 'common-fail:object-unreachable))) - - (let* ((placing-action-referenced - (second (desig:reference placing-action-desig))) - (object-designator - (desig:desig-prop-value placing-action-referenced :object)) - (arm - (desig:desig-prop-value placing-action-referenced :arm)) - (left-reach-poses - (desig:desig-prop-value placing-action-referenced :left-reach-poses)) - (right-reach-poses - (desig:desig-prop-value placing-action-referenced :right-reach-poses)) - (left-put-poses - (desig:desig-prop-value placing-action-referenced :left-put-poses)) - (right-put-poses - (desig:desig-prop-value placing-action-referenced :right-put-poses)) - (left-retract-poses - (desig:desig-prop-value placing-action-referenced :left-retract-poses)) - (right-retract-poses - (desig:desig-prop-value placing-action-referenced :right-retract-poses)) - (object-name - (desig:desig-prop-value object-designator :name))) + (cpl:with-retry-counters ((placing-retries retries)) + (cpl:with-failure-handling + (((or common-fail:manipulation-low-level-failure + common-fail:manipulation-goal-in-collision) (e) + (declare (ignore e)) + (cpl:do-retry placing-retries + (setf placing-action-desig + (desig:next-solution placing-action-desig)) + (if placing-action-desig + (cpl:retry) + (progn + (roslisp:ros-warn (coll-check place) + "No more placing samples to try.~ + Object unreachable.") + (cpl:fail 'common-fail:object-unreachable + :description + (format + nil + "No more placing samples to try.~%~ + Placing pose of ~a is unreachable.~%~ + Propagating up." + placing-action-desig))))) + (roslisp:ros-warn (coll-check place) + "Placing pose of ~a is unreachable.~%~ + Propagating up." + placing-action-desig) + (cpl:fail 'common-fail:object-unreachable + :description "No more place retries left."))) - (urdf-proj::gripper-action :open arm) + (let* ((placing-action-referenced + (second (desig:reference placing-action-desig))) + (object-designator + (desig:desig-prop-value placing-action-referenced :object)) + (arm + (desig:desig-prop-value placing-action-referenced :arm)) + (left-reach-poses + (desig:desig-prop-value placing-action-referenced :left-reach-poses)) + (right-reach-poses + (desig:desig-prop-value placing-action-referenced :right-reach-poses)) + (left-put-poses + (desig:desig-prop-value placing-action-referenced :left-put-poses)) + (right-put-poses + (desig:desig-prop-value placing-action-referenced :right-put-poses)) + (left-retract-poses + (desig:desig-prop-value placing-action-referenced :left-retract-poses)) + (right-retract-poses + (desig:desig-prop-value placing-action-referenced :right-retract-poses)) + (object-name + (desig:desig-prop-value object-designator :name))) + + (urdf-proj::gripper-action :open arm) - (roslisp:ros-info (coll-check place) - "Trying to place object ~a with arm ~a~%" - object-name arm) - - (mapcar - (lambda (left-poses right-poses) - (multiple-value-bind (left-poses right-poses) - (cut:equalize-two-list-lengths left-poses right-poses) - (dotimes (i (length left-poses)) - (urdf-proj::move-tcp (nth i left-poses) (nth i right-poses) - :allow-all) - (unless (< (abs urdf-proj:*debug-short-sleep-duration*) 0.0001) - (cpl:sleep urdf-proj:*debug-short-sleep-duration*)) - (when (or - ;; either robot collied with environment - (btr:robot-colliding-objects-without-attached) - ;; or object in hand collides with environment - ;; (remove - ;; (btr:name - ;; (find-if (lambda (x) - ;; (typep x 'btr:semantic-map-object)) - ;; (btr:objects btr:*current-bullet-world*))) - ;; (remove (btr:get-robot-name) - ;; (btr:find-objects-in-contact - ;; btr:*current-bullet-world* - ;; (btr:object - ;; btr:*current-bullet-world* - ;; object-name)) - ;; :key #'btr:name) - ;; :key #'btr:name) - ) - (roslisp:ros-warn (coll-check place) - "Robot is in collision with environment.") - (cpl:sleep urdf-proj:*debug-long-sleep-duration*) - (btr::restore-world-state world-state world) - ;; (cpl:fail 'common-fail:manipulation-goal-in-collision) - )))) - (list left-reach-poses left-put-poses left-retract-poses) - (list right-reach-poses right-put-poses right-retract-poses)))) - (btr::restore-world-state world-state world))))) + (roslisp:ros-info (coll-check place) + "Trying to place object ~a with arm ~a~%" + object-name arm) + + (mapcar + (lambda (left-poses right-poses) + (multiple-value-bind (left-poses right-poses) + (cut:equalize-two-list-lengths left-poses right-poses) + (dotimes (i (length left-poses)) + (urdf-proj::move-tcp (nth i left-poses) (nth i right-poses) + :allow-all) + (unless (< (abs urdf-proj:*debug-short-sleep-duration*) 0.0001) + (cpl:sleep urdf-proj:*debug-short-sleep-duration*)) + (when (or + ;; either robot collied with environment + (btr:robot-colliding-objects-without-attached) + ;; or object in hand collides with environment + ;; (remove + ;; (btr:name + ;; (find-if (lambda (x) + ;; (typep x 'btr:semantic-map-object)) + ;; (btr:objects btr:*current-bullet-world*))) + ;; (remove (rob-int:get-robot-name) + ;; (btr:find-objects-in-contact + ;; btr:*current-bullet-world* + ;; (btr:object + ;; btr:*current-bullet-world* + ;; object-name)) + ;; :key #'btr:name) + ;; :key #'btr:name) + ) + (roslisp:ros-warn (coll-check place) + "Robot is in collision with environment.") + (cpl:sleep urdf-proj:*debug-long-sleep-duration*) + (btr:restore-world-poses world-pose-info) + ;; (cpl:fail 'common-fail:manipulation-goal-in-collision) + )))) + ;; (list left-put-poses) + ;; (list right-put-poses) + (list left-reach-poses left-put-poses left-retract-poses) + (list right-reach-poses right-put-poses right-retract-poses)))))) + (btr:restore-world-poses world-pose-info))))) (defun check-placing-pose-stability (object-desig placing-location) (when *projection-checks-enabled* - (let* ((placing-pose - (desig:reference placing-location)) - (world - btr:*current-bullet-world*) - (world-state - (btr::get-state world)) + (let* ((world-pose-info + (btr:get-world-objects-pose-info)) + (placing-pose + (desig:reference (desig:current-desig placing-location))) (bullet-object-type (desig:desig-prop-value object-desig :type)) + (bullet-object-name + (gensym "obj")) (new-btr-object - (btr-utils:spawn-object - (gensym "obj") bullet-object-type :pose placing-pose))) + (btr:add-object btr:*current-bullet-world* :mesh + bullet-object-name placing-pose + :mesh bullet-object-type + :mass 0.2))) (unwind-protect (progn - (setf (btr:pose new-btr-object) placing-pose) (cpl:sleep urdf-proj::*debug-short-sleep-duration*) (btr:simulate btr:*current-bullet-world* 500) (btr:simulate btr:*current-bullet-world* 100) (let* ((new-pose (btr:pose new-btr-object)) (distance-new-pose-and-place-pose - (cl-tf:v-dist + (cl-transforms:v-dist (cl-transforms:origin new-pose) (cl-transforms:origin placing-pose)))) (when (> distance-new-pose-and-place-pose 0.2) (cpl:fail 'common-fail:high-level-failure :description "Pose unstable.")))) - (btr::restore-world-state world-state world))))) + (btr:remove-object btr:*current-bullet-world* bullet-object-name) + (btr:restore-world-poses world-pose-info))))) (defun check-environment-manipulation-collisions (action-desig) (when *projection-checks-enabled* - (let* ((world btr:*current-bullet-world*) - (world-state (btr::get-state world))) + (let ((world-pose-info (btr:get-world-objects-pose-info))) (unwind-protect + (cpl:with-failure-handling ((desig:designator-error (e) (roslisp:ros-warn (coll-check environment) @@ -382,7 +405,7 @@ Store found pose into designator or throw error if good pose not found." (roslisp:ros-warn (coll-check environment) "Robot is in collision with environment.") (cpl:sleep urdf-proj:*debug-long-sleep-duration*) - (btr::restore-world-state world-state world) + (btr:restore-world-poses world-pose-info) ;; (cpl:fail 'common-fail:manipulation-goal-in-collision) )))) - (btr::restore-world-state world-state world))))) + (btr:restore-world-poses world-pose-info))))) diff --git a/cram_3d_world/cram_urdf_projection_reasoning/src/projection-prediction.lisp b/cram_3d_world/cram_urdf_projection_reasoning/src/projection-prediction.lisp index 5b313de6ce..505ebe8495 100644 --- a/cram_3d_world/cram_urdf_projection_reasoning/src/projection-prediction.lisp +++ b/cram_3d_world/cram_urdf_projection_reasoning/src/projection-prediction.lisp @@ -218,7 +218,7 @@ (cpl:with-failure-handling ((cpl:plan-failure (e) (roslisp:ros-warn - (pr2-proj-reason proj-prediction) + (proj-reason proj-prediction) "PROJECTION RUN HAD A FAILURE...~%~a~%" e) (return))) ,@body)) diff --git a/cram_boxy/cram_boxy_assembly_demo/resource/bowl.dae b/cram_boxy/cram_boxy_assembly_demo/resource/bowl.dae deleted file mode 100644 index 6aa795759c..0000000000 --- a/cram_boxy/cram_boxy_assembly_demo/resource/bowl.dae +++ /dev/null @@ -1,63 +0,0 @@ - - - - - Blender User - Blender 2.79.0 commit date:2017-09-11, commit time:10:43, hash:5bd8ac9abfa - - 2017-10-25T18:06:46 - 2017-10-25T18:06:46 - - Z_UP - - - - - - - 0.06953394 0.03718966 0.0278238 0.0691601 0.03039228 0.02527147 0.07407033 0.02616602 0.02833718 0.07684761 0.02172911 0.02802979 0.0728181 0.03214913 0.02770376 0.0632326 0.04208612 0.02548915 0.06465184 0.04413431 0.02769911 0.0684939 0.03845155 0.02603691 0.06467711 0.04599577 0.02744853 0.07115334 0.02304655 0.02444523 0.07775086 0.01701629 0.02865159 0.07460933 0.01594746 0.02646762 0.07769441 0.01198869 0.02865999 0.07857304 0.01027983 0.02776193 0.05741274 0.05278813 0.0272445 0.06223839 0.03870415 0.02206528 0.06411194 0.03052461 0.01793742 0.07868921 0.006395578 0.0291171 0.07484829 0.003801703 0.02449953 0.06847399 0.01686799 0.01629936 0.05495142 0.05715727 0.02704381 0.05136436 0.05876177 0.02732294 0.04512435 0.05871683 0.02407699 0.05275779 0.05269539 0.02436709 0.05284637 0.04740905 0.01864773 0.08000588 0.003240823 0.0286858 0.07597756 -0.008265137 0.02669352 0.0792157 -0.008371829 0.02955216 0.04751265 0.0631178 0.02699488 0.04064595 0.06606495 0.02706986 0.03821665 0.06531602 0.02588582 0.05655604 0.04002952 0.01477587 0.0441693 0.05308771 0.01535284 0.05668509 0.02694678 -4.10885e-4 0.06050735 0.01985818 0.001124083 0.07278501 -0.01206773 0.02268344 0.07149004 -0.00332725 0.01840209 0.07022589 0.005331516 0.01600664 0.04700499 0.04181438 0.001156687 0.03478354 0.07090586 0.02682232 0.02920556 0.07222342 0.0269649 0.0316804 0.0651502 0.02177226 0.03651273 0.05891358 0.01623064 0.07403564 -0.02109748 0.02755808 0.07882803 -0.00699979 0.02760887 0.07811337 -0.01863741 0.0295614 0.05017787 0.03101658 -0.007394969 0.06276345 0.01031368 2.8429e-4 0.02815783 0.07016694 0.02580499 0.06933856 -0.03339546 0.02763777 0.0726791 -0.03391522 0.03028285 0.06853997 -0.02273589 0.01997733 0.06575351 -0.03127604 0.02107429 0.07407146 -0.03219968 0.0296806 0.0743556 -0.01545035 0.02228891 0.02644515 0.07304698 0.02547597 0.01819258 0.0754593 0.02580225 0.01612895 0.07481783 0.02655261 0.03232598 0.05135881 -0.002433896 0.03703451 0.04780304 -0.003139436 0.06383907 -0.001852333 1.85575e-4 0.06370484 -0.0140478 0.002869188 0.07015037 -0.0148046 0.0185824 0.0181148 0.07149797 0.02371424 0.05438196 0.02050387 -0.009458124 0.02681839 0.06272673 0.01430088 0.06384736 -0.04646378 0.03045809 0.06853264 -0.0426104 0.03029793 0.04182672 0.04037469 -0.007976412 0.05502808 0.01365494 -0.01213967 0.05800634 0.005897164 -0.009907305 0.06292134 -0.04173046 0.02613693 0.05815124 -0.00276643 -0.01041167 0.05763006 -0.010971 -0.01002192 0.06077575 -0.02345895 0.002391874 0.01553684 0.06888914 0.01928728 0.001768231 0.0746259 0.02482175 0.005929887 0.06983637 0.01851117 0.009326815 0.07788646 0.02664113 0.004071831 0.07744681 0.02685654 0.04485696 0.0289421 -0.01554638 0.02346271 0.05719709 4.83677e-4 0.01434087 0.06408184 0.009134769 0.05744028 -0.01879602 -0.007297337 0.04732906 0.0207014 -0.01795315 0.03403645 0.04357475 -0.01208633 0.02322554 0.04960852 -0.01234704 0.05710148 -0.03059035 0.001307845 0.05962955 -0.04006212 0.01885724 0.03769236 0.03487271 -0.01750165 0.04473942 0.01390576 -0.02306878 0.05113261 0.00414139 -0.01911729 0.05744707 -0.05541503 0.03109395 0.06024646 -0.05359256 0.03045117 0.05737763 -0.05076998 0.02790182 0.01471394 0.05717611 -0.004775464 0.05277293 -0.003568649 -0.01742202 0.003565132 0.05979806 -0.003014862 0.003024458 0.07748788 0.02555865 -0.004177033 0.07644087 0.02664184 -0.005632698 0.07876211 0.02640765 0.03870046 0.02389675 -0.02376514 -0.004540264 0.06914407 0.01702409 -0.009399831 0.07084196 0.02058327 0.02701157 0.04042565 -0.02010571 0.04956614 -0.01312196 -0.01955199 0.0510503 -0.03043317 -0.009252905 0.04853779 -0.02316397 -0.01685661 0.05179888 -0.03777772 -4.15714e-4 0.05414533 -0.04774659 0.01979076 0.04635691 -0.05543828 0.0201317 0.04937463 -0.05841207 0.02812027 0.04683393 -0.06383895 0.03100258 0.03317242 0.02911204 -0.02459692 -0.009725689 0.07997167 0.02723562 -0.01599627 0.07581216 0.02667403 -0.02193748 0.07129645 0.02445989 0.05258494 -0.06107747 0.03095406 0.04694819 -0.002247214 -0.02342689 0.01490473 0.05223864 -0.01256918 0.01209235 0.04708361 -0.01983207 0.04094731 0.008585393 -0.02672809 0.03416568 0.01811563 -0.02823495 0.006482839 0.05388677 -0.01246851 -0.008739531 0.05936127 -0.003023743 -0.01543599 0.06801682 0.0177114 0.04728972 -0.04481434 0.002219915 0.04257303 -0.04268527 -0.007671117 0.04222869 -0.05128026 0.005250334 -0.01536244 0.07716488 0.02651095 -0.009564936 0.07697743 0.02461379 0.02481251 0.0346896 -0.02540874 0.01621615 0.04026591 -0.0245859 -0.003258109 0.05786436 -0.006562054 -0.02206265 0.07587319 0.02694374 -0.02598446 0.07322204 0.02675473 0.03920543 -0.06568974 0.02842032 0.03651231 -0.06220608 0.02022308 0.02565938 0.0271719 -0.02879643 0.04114151 -0.01453584 -0.02608096 0.04153496 -0.02224063 -0.02362257 0.04277771 -0.03384035 -0.01614987 0.04426968 -0.06756746 0.03145033 0.04678785 -0.06499952 0.03044062 0.02992242 -0.07290428 0.03137844 0.03744828 0.004589855 -0.02872401 0.04084241 -0.00491321 -0.02735161 0.0374369 -0.04868131 -0.005784571 0.01555901 0.03315299 -0.02901089 0.0298748 0.0112254 -0.02999931 -5.45622e-4 0.04714 -0.02125328 0.006221592 0.03938949 -0.02722829 -0.01834124 0.05944645 0.001390814 -0.01884591 0.05353903 -0.00893557 -0.01073837 0.05230462 -0.0138424 -0.03334408 0.07077306 0.02713626 -0.03683596 0.06574535 0.02493578 -0.0243631 0.06484287 0.01649194 -0.002446472 0.05338597 -0.01364231 -0.02610695 0.0739668 0.02599889 0.03245812 -0.05464088 -0.001463651 0.02691417 -0.07108032 0.02805936 0.03496986 -0.07228201 0.03107392 0.04360437 -0.06074845 0.0212264 0.0362451 -0.06722742 0.02442669 0.01932448 0.02682554 -0.03018003 0.03471243 -0.01048135 -0.02891951 0.03468334 -0.02222061 -0.02730745 0.03159749 -0.03207206 -0.02494388 0.0365861 -0.03714567 -0.01888847 -0.03181141 0.07309293 0.0271787 0.03544735 -0.04503369 -0.01238161 0.02567476 -0.05984139 0.002226054 0.02545142 -0.06727707 0.02003312 0.01803338 0.01881712 -0.03064042 0.02797275 -0.001962423 -0.02964633 -0.02786934 0.05398255 -0.002267181 0.01634925 -0.07488393 0.02906382 0.0152536 -0.07814782 0.03182047 0.02006858 -0.07755643 0.03140169 0.02256029 -0.07645565 0.03035473 0.00230211 0.03397494 -0.03014415 1.4959e-4 0.0298286 -0.03093165 -0.01101797 0.04537457 -0.02158468 -0.007080137 0.03768366 -0.02814656 -0.03378552 0.06006616 0.01519155 -0.04047453 0.06133723 0.02281808 0.02753174 -0.05050742 -0.01200801 -0.03563493 0.07019686 0.02639746 -0.04132413 0.06640535 0.02723085 0.0290113 -0.01775723 -0.028943 0.00932902 -0.003438949 -0.02927041 -0.006738781 0.02001619 -0.03084695 -0.001453101 0.005738139 -0.02983164 0.02391928 -0.0316565 -0.02757954 0.02883344 -0.04196476 -0.02019977 0.02178305 -0.05529111 -0.009019136 -0.04924404 0.05729794 0.02527791 0.01787775 -0.07056313 0.0221247 -0.01818257 0.04773473 -0.0169357 -0.0132575 0.03053057 -0.03022038 0.01133918 -0.02964907 -0.02858126 -0.04370242 0.05490523 0.0172339 -0.05051451 0.06022411 0.02740764 -0.0459876 0.06463772 0.02695798 0.0165112 -0.0619542 -4.39693e-5 0.0207743 -0.03829485 -0.02570772 -0.02095043 0.02045989 -0.03087323 -0.02620083 0.04754519 -0.01316303 0.01788681 -0.04530215 -0.02217972 0.01771456 -0.05092388 -0.01676523 -0.03646683 0.04827409 -0.003513813 -0.01547008 0.03644263 -0.02752113 -0.02223747 0.04224622 -0.02089571 -0.008789956 -0.01042771 -0.02937567 0.009715318 -0.03966206 -0.02703958 0.0108022 -0.07312172 0.0245285 0.004414379 -0.07119137 0.01863193 0.009576737 -0.06519365 0.004537463 0.003512799 -0.07526278 0.02724325 4.66009e-4 -0.07875961 0.03156381 0.01057857 -0.07957887 0.03133386 -0.007365942 -0.08002823 0.03142863 -0.01811766 0.00484538 -0.03031617 0.0105763 -0.05485528 -0.01434719 0.006743729 -0.05850887 -0.0100584 -0.05878585 0.0563963 0.02778357 -0.05793017 0.05400675 0.02805256 -0.05271786 0.05979263 0.02694064 -0.05721563 0.04851067 0.02463936 -0.05248987 0.04641777 0.01632958 -0.02569943 0.03524744 -0.02475917 -0.02977091 0.02554702 -0.0280708 -0.03291249 0.04148006 -0.01554578 -0.04499757 0.04358416 2.87177e-4 0.001842737 -0.06416863 1.8597e-4 0.00679785 -0.04779589 -0.02236086 -0.04373705 0.03713285 -0.009882628 -0.0302847 0.003477454 -0.03035145 -0.03076928 0.01571202 -0.02998119 1.76659e-4 -0.03378969 -0.0284956 -0.01431411 -0.02579683 -0.029127 -0.009710967 -0.07572269 0.02864539 -0.004257082 -0.07196718 0.02064239 -0.04243165 0.03158599 -0.01621651 -0.03448635 0.03098875 -0.02268069 -0.05987489 0.05122727 0.02656763 -0.06240844 0.04686552 0.02764064 -0.01438105 -0.07854872 0.03189063 -0.00481677 -0.03813499 -0.0278576 -0.001188278 -0.04547506 -0.02435535 -2.65996e-4 -0.05246937 -0.01821696 -0.05949676 0.03786849 0.01678347 -0.05103844 0.03615403 -6.86531e-4 -0.06423318 0.03889518 0.0247634 -0.006942689 -0.05530548 -0.01439601 -0.007756173 -0.06235241 -0.002807497 -0.06854474 0.03871101 0.0281769 -0.027121 -0.009916543 -0.02991664 -0.01372706 -0.07018548 0.01908004 -0.02039188 -0.0747776 0.03012263 -0.02867454 -0.07039803 0.02775722 -0.02523952 -0.06747341 0.02002048 -0.04061818 0.02198547 -0.02331548 -0.03859078 0.01195734 -0.02764117 -0.05380624 0.024971 -0.007692515 -0.06720042 0.04301834 0.02781528 -0.05590975 0.03220427 0.00315839 -0.06637561 0.02847313 0.01981413 -0.07325625 0.02338135 0.02653819 -0.07250285 0.03248798 0.02770817 -0.0221849 -0.07716548 0.031174 -0.03085124 -0.07433164 0.03155821 -0.01350349 -0.04190927 -0.02546191 -0.01950925 -0.03000009 -0.02864676 -0.02200418 -0.03712272 -0.02619886 -0.04793721 0.02364271 -0.01601707 -0.03564816 -0.001473188 -0.02944809 -0.009134352 -0.04910445 -0.0207681 -0.0188049 -0.06269943 0.003208875 -0.0596975 0.02140855 -2.84615e-4 -0.01232844 -0.05907893 -0.007390439 -0.02864515 -0.022237 -0.02875339 -0.01667737 -0.05300992 -0.01465821 -0.06917101 0.0203588 0.01924318 -0.02922564 -0.07311153 0.03115648 -0.04753035 0.01288706 -0.02116328 -0.01920509 -0.04506254 -0.02170509 -0.05378049 0.01597732 -0.0131033 -0.0784406 0.01377832 0.02890872 -0.07582306 0.008234858 0.02606815 -0.07167673 0.007273077 0.01865053 -0.03737074 -0.06246405 0.021299 -0.04338008 -0.06132328 0.02570152 -0.04490035 0.001739621 -0.0249629 -0.04102873 -0.004156231 -0.0272578 -0.06131714 0.01324677 -0.002340435 -0.02050894 -0.05737495 -0.006378054 -0.02522587 -0.0605393 0.003268003 -0.07830083 0.01785075 0.02846848 -0.06904399 0.02636247 0.0185098 -0.06380546 0.0364995 0.01819568 -0.03927749 -0.06850665 0.03129112 -0.05146503 0.003423571 -0.01918423 -0.02782255 -0.05205637 -0.01004141 -0.02686709 -0.04570204 -0.0179674 -0.06540411 0.008831262 0.004658699 -0.0375626 -0.01844376 -0.02689474 -0.04034131 -0.0678007 0.028337 -0.03562039 -0.0655232 0.02076476 -0.02662765 -0.07167506 0.02456068 -0.04683637 -0.06556046 0.03121221 -0.03476005 -0.05540788 0.002385973 -0.07999408 0.003974497 0.02865225 -0.07904857 -0.003527104 0.02897739 -0.07632046 -0.004544973 0.02640908 -0.03283935 -0.0290277 -0.02582573 -0.03357571 -0.03673374 -0.02121764 -0.05775213 0.006406545 -0.01073437 -0.04731309 -0.05378741 0.01828449 -0.0502035 -0.06104826 0.0306549 -0.05029308 -0.01032847 -0.01966965 -0.04442983 -0.01386982 -0.02386248 -0.03847384 -0.04175627 -0.01339787 -0.06190288 0.002845585 -0.004293799 -0.03650462 -0.05016481 -0.004837393 -0.07219564 -0.00553584 0.01929372 -0.06379622 -0.005139768 -7.48972e-4 -0.05387735 -0.05398452 0.02737593 -0.04459112 -0.04636734 -5.12193e-4 -0.04447156 -0.02304208 -0.0210343 -0.04086565 -0.0322104 -0.01900321 -0.05428814 -0.003232598 -0.01603949 -0.05822271 -0.004428267 -0.01084375 -0.05628967 -0.05646204 0.03081363 -0.0538789 -0.0594235 0.0302301 -0.07922101 -0.007713258 0.02951288 -0.07580608 -0.01649051 0.02854222 -0.05427932 -0.04724061 0.01878762 -0.05728751 -0.01488554 -0.009884178 -0.04956269 -0.02373027 -0.01595312 -0.04592251 -0.03701519 -0.0103932 -0.06336098 -0.01366227 8.68164e-4 -0.07013767 -0.01834404 0.01944565 -0.07966578 -0.004171013 0.02829581 -0.06210625 -0.04588663 0.02839624 -0.05170357 -0.03941035 0.001073658 -0.06104266 -0.03923636 0.01979601 -0.07873207 -0.01451635 0.02916753 -0.07393121 -0.02275532 0.02864098 -0.06152981 -0.0518698 0.03035819 -0.05253273 -0.03074645 -0.007300078 -0.05634403 -0.02372348 -0.006653904 -0.0621795 -0.02077311 0.00241661 -0.05885148 -0.02949666 0.002886712 -0.06587368 -0.03397274 0.02348446 -0.06814599 -0.03523874 0.02763777 -0.06712549 -0.04161483 0.0303198 -0.06613075 -0.04578679 0.03069168 -0.07329767 -0.03367215 0.03045815 -0.06994301 -0.03863978 0.03020292 -0.07452565 -0.02401572 0.02850705 -0.06670266 -0.0413559 0.02658361 -0.06714415 -0.03546714 0.02238541 -0.07288604 -0.02605456 0.02552509 0.07127112 0.01849555 0.01826286 0.06142348 0.03963619 0.01792627 0.05438721 0.04997569 0.01959931 0.04765868 0.05561536 0.0190491 0.04132008 0.06132429 0.02023601 0.03099334 0.06669682 0.01980829 0.07122415 -0.02709513 0.02301299 0.06766849 -0.03286284 0.02148342 0.008519411 0.07328808 0.02047699 0.05809754 -0.04763549 0.02129095 0.06302094 -0.04057079 0.02086657 -3.26097e-4 0.07291287 0.01917964 -0.03510725 0.0658639 0.02095478 -0.02263915 0.06977266 0.0195021 -0.04612636 0.0580967 0.02009481 -0.05569779 0.05511283 0.02532809 -0.06013405 0.04376405 0.0197826 -0.07413429 0.003341376 0.0184139 -0.07433199 -0.006726026 0.01920479 -0.04217505 -0.06173813 0.02090919 -0.05036509 -0.05543249 0.02075195 -0.0728026 -0.01565092 0.01894855 -0.05952864 -0.04509621 0.01990526 0.02344477 -0.07112413 0.02183091 -0.07276678 0.01358073 0.01845693 0.04952073 -0.05547201 0.01984947 -0.01718419 -0.07268255 0.02161943 -0.002843499 -0.07479113 0.02198863 0.06790596 0.02734172 0.01779478 0.07354956 0.0068506 0.01852756 0.07368373 -0.005577743 0.01853513 0.0628131 0.03481966 0.01510912 0.05705982 0.0303604 -0.001061856 0.05146837 0.0351817 -0.005210161 0.05095952 0.04785674 0.01170754 0.06175661 0.02248215 6.72711e-4 0.06500709 0.01045805 1.72292e-4 0.06599038 -7.26266e-4 1.29753e-4 0.03966981 0.04906654 -0.002468585 0.03460919 0.06050384 0.01234126 0.07099425 -0.01870417 0.01737332 0.06381136 -0.01016634 -0.003441095 0.04656052 0.0425527 -0.003169 0.05596321 0.02115249 -0.0105865 0.05004274 0.02825295 -0.01360976 0.06038951 0.009785115 -0.009123623 0.01959794 0.07058626 0.01955944 0.02578371 0.06455999 0.01254999 0.01743966 0.06800466 0.01418125 0.03344732 0.05158954 -0.005307435 0.02500247 0.05533427 -0.006236374 0.06374275 -0.01949149 8.39898e-4 0.06053078 -0.02653652 -7.12526e-4 0.04513508 0.03567111 -0.01294976 0.03503185 0.04486596 -0.01330137 0.05984413 -0.002809286 -0.01157605 0.05786794 -0.01563805 -0.01197206 0.05125534 0.01361113 -0.01987403 0.04869961 0.02134054 -0.01934128 0.05672013 0.00847733 -0.01480376 0.01674711 0.05963963 -0.003640413 0.04277366 0.02736705 -0.0216121 0.005160689 0.06323337 -3.6177e-4 0.00605297 0.06962209 0.01358628 0.0387938 0.03535139 -0.01935428 0.0510748 -0.007056117 -0.02215152 0.05389833 0.001525104 -0.01927191 0.05737847 -0.0318765 -0.001695275 0.05376511 -0.02739191 -0.01140058 0.05384218 -0.04245543 0.004868209 0.02721679 0.04191768 -0.02164852 0.02268624 0.0506947 -0.01463299 0.004637897 0.05873799 -0.008819699 0.01262372 0.05535614 -0.0124576 0.04536271 -0.04933267 0.001416146 0.03138422 0.03220629 -0.02641284 0.04309105 0.0129233 -0.02729171 0.04744857 0.00695765 -0.02502959 -0.005422234 0.06907445 0.01243388 0.03585678 0.02177941 -0.02893745 0.05224418 -0.01994502 -0.01740926 -0.01195889 0.07248491 0.01992094 -0.006411314 0.06138795 -0.003990828 0.05151575 -0.03745311 -0.005808889 0.0442453 -0.002111017 -0.02789252 0.03792375 0.006255745 -0.03068917 0.02078765 0.03709965 -0.02793991 0.01824218 0.04689514 -0.02087372 0.0124405 0.04106754 -0.02757745 0.008645892 0.05211412 -0.01799792 0.04761958 -0.01847153 -0.02268296 0.04406911 -0.01231771 -0.02699792 0.02712839 0.02923315 -0.02978575 0.02595126 0.01796364 -0.03233444 0.02382153 0.02594149 -0.03166782 0.0466367 -0.03643423 -0.01327842 0.04604077 -0.02647 -0.0207628 -0.0160371 0.06831645 0.01408684 0.0416224 -0.04509776 -0.01002728 0.03776371 -0.05475038 1.78409e-4 0.03260809 -0.06530469 0.0169816 0.005365192 0.04561179 -0.02509117 0.03815352 -0.008053779 -0.0304383 -0.002616763 0.05465078 -0.01535743 -0.004713952 0.04820042 -0.02270108 0.03950405 -0.0188452 -0.02831506 -0.01735937 0.05979609 -0.003157317 -0.01103174 0.05385076 -0.01511538 0.01351022 0.03244102 -0.03185582 0.0422784 -0.03349035 -0.01992553 0.03810429 -0.02868789 -0.0256223 -0.02834439 0.06423646 0.0135895 0.02945333 0.0054304 -0.03207188 0.03157436 -0.004903554 -0.03155809 0.03518289 -0.04358828 -0.01756513 0.004698574 0.03637921 -0.03118759 -0.003730595 0.04072141 -0.02896326 0.002465307 0.02570658 -0.0331093 0.002992689 0.02959984 -0.03299909 0.03220742 -0.02498811 -0.02959573 0.02918624 -0.01824462 -0.03097039 0.03139346 -0.03533822 -0.02594673 0.03028625 -0.051081 -0.0130769 0.01126003 -0.004031419 -0.03132498 0.02752864 -0.05825233 -0.004315733 -0.01939004 0.055157 -0.01001083 -0.02847129 0.05545657 -0.003588259 -0.03763657 0.06020265 0.01485574 0.02100992 -0.06400066 0.002607762 -0.01617914 0.04242265 -0.02571684 -0.01655018 0.04922688 -0.01907908 0.02142828 -0.03780895 -0.02818083 0.01707488 -0.03388786 -0.02992194 0.02575075 -0.04470896 -0.02228003 -0.00711131 0.03191214 -0.03257745 0.01249122 -0.02959996 -0.03063321 0.01675522 -0.07183778 0.01948261 0.008111834 -0.07421571 0.0216059 -0.01607441 0.0357654 -0.03004658 -0.003394067 0.002179145 -0.03173714 -0.01428484 0.01995277 -0.0330224 0.01786339 -0.0530498 -0.01749885 0.01358062 -0.06104606 -0.007798016 -0.0272836 0.04855042 -0.01472288 -0.03681957 0.05104094 -0.002994298 -0.0358619 0.04731899 -0.009487807 -0.002864837 -0.01584255 -0.03117716 -0.02512186 0.04162716 -0.02291339 -0.04366576 0.05507844 0.01278132 0.01602727 -0.04640758 -0.02429884 -0.0504148 0.05218017 0.01706218 0.009030759 -0.06603807 8.15659e-4 -0.02526813 0.02050751 -0.03249037 -0.02006697 0.02835279 -0.03190308 -0.02784067 0.03202068 -0.02828365 -0.007850289 -0.03038084 -0.03090977 0.003678917 -0.03698247 -0.03008985 0.009924352 -0.04130005 -0.02846473 -0.03484261 0.04111474 -0.01758146 -0.04499119 0.03827416 -0.01101261 -0.04625159 0.04483085 -7.18411e-4 -0.02781563 -0.005949854 -0.03220951 -0.02643603 0.008533775 -0.03273183 -0.01939511 -0.02065294 -0.03145527 0.005132734 -0.05181527 -0.02163028 0.006194531 -0.05680233 -0.01590251 -0.00120151 -0.0591734 -0.01311743 8.95446e-5 -0.06495225 -0.002795636 -0.05631291 0.04253911 0.01241672 -0.03179788 0.03494769 -0.02447032 0.002389252 -0.04774606 -0.02530372 -0.00838375 -0.06674736 0.002305567 -0.03120356 0.02212357 -0.03076636 -0.04458647 0.03333169 -0.01595377 -0.04157179 0.02607482 -0.02347993 -0.0371235 0.02107352 -0.02851116 -0.006647765 -0.04440778 -0.02730959 -0.05257016 0.03679758 -0.002000749 -0.008398711 -0.07307457 0.01884782 -0.03485405 0.008227467 -0.03168767 -0.008729338 -0.03780472 -0.02979975 -0.02231144 -0.02833384 -0.03078562 -0.007327556 -0.052356 -0.02079063 -0.05536627 0.02572757 -0.008778214 -0.00699824 -0.06181317 -0.008152484 -0.03354406 -0.01785916 -0.03053033 -0.03569322 -0.005769014 -0.03124588 -0.04932594 0.02434968 -0.01734739 -0.05956298 0.02915942 0.001795053 -0.01508426 -0.05659776 -0.01398366 -0.01932859 -0.06446355 0.00241506 -0.0185067 -0.06039828 -0.006592988 -0.04739809 0.0150392 -0.0233255 -0.01747876 -0.03886938 -0.02861332 -0.02306246 -0.04094856 -0.02606254 -0.01633197 -0.04981708 -0.02128493 -0.02787637 -0.06775766 0.01777523 -0.04036682 0.009170532 -0.0294016 -0.04203408 -0.003543615 -0.02908694 -0.06260854 0.01807337 -0.001696109 -0.05537664 0.01648592 -0.01429027 -0.06983661 0.02081406 0.01605069 -0.03015828 -0.03079986 -0.02849072 -0.06074297 0.009920597 -0.009027302 -0.02735573 -0.05346006 -0.01203197 -0.02810287 -0.04708158 -0.01902371 -0.03107261 -0.05613416 -0.004961967 -0.02833998 -0.06121677 0.002359926 -0.04688072 0.002693176 -0.02597224 -0.05236256 0.008366346 -0.02036774 -0.06495469 0.005243837 -0.002628743 -0.03452372 -0.03769344 -0.02275615 -0.04142987 -0.05380392 0.002892792 -0.05486953 0.001663267 -0.0186668 -0.04681575 -0.009101212 -0.02547276 -0.05214095 -0.01061332 -0.02068966 -0.03810727 -0.04435676 -0.01450037 -0.03673154 -0.05241334 -0.005455672 -0.04126918 -0.01769655 -0.02758324 -0.03955256 -0.02810949 -0.02510005 -0.06548649 -0.005358517 -0.001934885 -0.05983322 -0.005319535 -0.01210433 -0.05392885 -0.05002593 0.01746588 -0.05043584 -0.04463291 0.001416981 -0.04590034 -0.04329222 -0.007518231 -0.04760837 -0.01997154 -0.02232313 -0.04563599 -0.03526085 -0.01574128 -0.04859489 -0.02830106 -0.01738882 -0.05493277 -0.01944082 -0.01483386 -0.06528943 -0.01341044 -6.38537e-5 -0.05993914 -0.01525878 -0.009398519 -0.05313807 -0.0378459 -0.003296196 -0.06332987 -0.03775459 0.01728922 -0.05637317 -0.02678442 -0.008738517 -0.06407517 -0.02140939 0.001853466 -0.07028043 -0.02582883 0.02033585 -0.05841082 -0.03100401 -0.001532912 - - - - - - - - - - -0.6521345 -0.2347947 0.7208274 0.2024679 0.1087474 0.9732322 0.4625782 0.2302312 0.856163 -0.5152622 -0.2762853 0.8112776 -0.5696126 -0.3874288 0.7248728 0.8325726 0.5448499 -0.09980803 0.865701 0.4701376 -0.1718502 0.1593804 0.1296095 0.9786722 -0.6619215 -0.2587342 0.7035032 0.4122294 0.1963958 0.8896604 -0.5193969 -0.1802205 0.8353128 -0.7234955 -0.1609793 0.6712973 -0.5725858 0.00779587 0.8198078 0.7082921 -0.00678122 0.7058869 0.9560127 0.1499759 -0.2520854 0.09530985 0.1315612 0.9867157 -0.5412899 -0.4143631 0.7316479 -0.7482751 -0.4274295 0.5073347 -0.7213466 -0.3764675 0.5813186 -0.7939729 -0.2763468 0.541516 -0.616792 -0.04548007 0.7858113 -0.7276461 -0.1236456 0.674717 -0.8559415 -0.09907376 0.5074923 -0.8350414 -0.2699444 0.4794121 0.8585972 0.1915786 0.4755087 0.1294664 0.1181626 0.9845182 -0.440496 -0.5232751 0.7294837 -0.4142128 -0.429929 0.80224 0.03135323 0.06348633 0.9974901 -0.4786734 -0.389379 0.7869281 -0.6404095 -0.4452759 0.6257836 -0.6350746 -0.5721365 0.5189799 -0.8030456 -0.317021 0.5045944 0.75994 0.2342644 0.6063097 -0.6618323 -0.00151056 0.7496504 0.3988397 0.04120606 0.9160944 -0.7792993 0.04076862 0.6253243 0.06888061 0.1353425 0.9884017 -0.2965493 -0.405259 0.864768 -0.3707355 -0.585641 0.7208189 0.1766078 0.2282689 0.9574462 -0.6921516 -0.576079 0.4348096 -0.749141 -0.4271159 0.5063199 -0.5946894 -0.5949636 0.5407059 -0.5498036 -0.6731649 0.4945353 -0.8370941 -0.3626844 0.4095529 -0.8628161 -0.3223021 0.3894482 -0.7759496 -0.4811605 0.4079053 -0.7976999 0.03481549 0.6020488 -0.9061363 0.07007479 0.4171409 -0.8780056 0.004229724 0.4786319 -0.8797789 -0.1450889 0.452701 -0.6032406 -0.6788753 0.418604 -0.704103 -0.5735883 0.4186114 0.05231094 0.1140833 0.9920931 -0.263133 -0.4744981 0.8400075 0.06767189 0.1325205 0.9888675 -0.4453114 -0.7623323 0.4696244 -0.409379 -0.6135926 0.6752133 -0.4823793 -0.7110424 0.5115944 -0.6516866 0.1487259 0.7437643 -0.8411342 0.1620493 0.5159782 0.9640654 -0.08438938 -0.2519058 -0.4648542 0.05071133 0.8839339 0.9589381 -0.1032098 -0.2641693 -0.7156517 -0.5506204 0.4297208 -0.7605189 -0.4951292 0.4200694 -0.8776407 -0.2437645 0.4127054 -0.9107998 -0.1480911 0.3853739 -0.2008652 -0.4016215 0.8935062 -0.3540267 -0.7242438 0.591723 -0.582485 0.2275327 0.7803462 -0.5371616 0.2293989 0.8116856 -0.8142552 0.1843806 0.5504474 -0.7975844 0.3254654 0.5078695 -0.7907218 0.3054478 0.5305287 0.5477684 -0.156024 0.8219528 0.8544046 -0.1365813 -0.5013366 0.8125715 -0.2468104 -0.5280267 0.2809173 0.95968 0.009987592 0.2311575 0.9670868 0.1063454 0.09626191 0.6101751 0.7863969 -0.1158365 -0.4425368 0.8892374 -0.5088924 -0.7556721 0.4122962 -0.5935739 -0.6837674 0.42442 -0.5192055 -0.7453636 0.4181613 -0.9224282 -0.02812033 0.3851435 -0.9102505 -0.08376753 0.4054961 -0.9173308 0.1130712 0.3817319 -0.8678027 0.1089093 0.4848271 -0.9148843 0.09634172 0.3920522 -0.8818787 0.2494272 0.4000951 -0.2325924 -0.7086479 0.6661223 -0.2330177 -0.7034075 0.6715062 -0.8214443 -0.3445202 0.4544614 -0.7746146 -0.4050869 0.4856715 -0.4009669 -0.7622247 0.5081725 -0.3169824 -0.8220999 0.4729416 0.05379688 -0.02392387 0.9982653 -0.534706 0.3868201 0.7513054 0.6829253 -0.324532 0.6544402 -0.5941327 -0.6715685 0.4427214 -0.6724218 -0.5707871 0.471223 -0.8416907 -0.2638556 0.4711021 -0.85152 -0.242195 0.4650328 -0.8555637 -0.1898673 0.4816235 -0.8889448 -0.08225119 0.4505688 -0.4033705 -0.8131514 0.4196158 -0.8921345 0.2476001 0.377876 -0.68144 0.4162495 0.6019768 -0.7130141 0.4525157 0.5355749 -0.8787915 -0.04237025 0.4753213 -0.8812093 0.07812756 0.4662255 -0.8891837 0.107645 0.4447079 -0.8682571 0.3307853 0.3697442 -0.8879356 0.2570093 0.3814663 -0.1812409 -0.7974686 0.5754961 -0.1212146 -0.8275523 0.5481462 -0.1259398 -0.8208562 0.5570766 -0.07941365 -0.6748026 0.7337132 0.03654199 0.05221724 0.9979671 -0.09444123 -0.5305165 0.8423973 0.1964821 0.4098401 0.8907447 -0.6384256 -0.5353693 0.5529851 -0.7180269 -0.3990563 0.5702556 -0.3974656 -0.8145571 0.4225139 -0.2742369 -0.8562544 0.4377472 -0.2656481 -0.8710714 0.413117 -0.8727509 0.1792678 0.4540582 -0.8721041 0.2500967 0.4205783 -0.7144755 -0.3849645 0.5842321 -0.7359953 -0.3058936 0.6039371 -0.541537 -0.6753513 0.500638 -0.4724968 -0.7250798 0.5010052 -0.3677706 -0.7974112 0.4784143 -0.4254713 -0.7398043 0.5212138 -0.8437694 0.376603 0.3823918 -0.8038011 0.4673821 0.3680462 -0.7812801 0.4305142 0.4519501 -0.5523854 -0.5952323 0.5835828 -0.6080923 -0.5440058 0.5781708 -0.7113735 -0.229083 0.6644313 -0.7159852 -0.1978611 0.6694896 -0.7834319 -0.1256222 0.6086491 -0.1231383 -0.8912329 0.43651 0.3201892 -0.1626427 0.9332879 0.05971091 -0.0311318 0.9977302 -0.5733416 0.4581981 0.6792158 -0.5807651 0.4839735 0.654585 -0.7960195 -0.04843848 0.6033298 -0.7208615 0.5294184 0.4472972 -0.2930239 -0.8205638 0.4907262 -0.2532268 -0.8691906 0.4247163 -0.7910603 -0.03399407 0.6107929 -0.7952668 0.07907301 0.6010808 -0.1398735 -0.8883796 0.4372837 -0.1307115 -0.8929465 0.4307683 -0.07911831 0.9923023 0.09526997 0.05422598 -0.6128999 0.7882978 -0.03547561 0.07826972 0.9963008 0.1374962 0.9872915 -0.07968914 -0.6094219 -0.3852096 0.692978 -0.561127 -0.4485288 0.6956713 -0.8190749 0.3533005 0.4519901 -0.030707 -0.8058319 0.5913478 -1.03966e-4 -0.9062952 0.4226455 0.0880233 -0.8470088 0.5242404 -0.01289522 -0.7287906 0.6846153 -0.4698653 -0.6002072 0.6472851 -0.3956956 -0.6824197 0.6145961 -0.7710497 0.1193648 0.6254875 -0.7681152 0.2270869 0.5986907 -0.8058025 0.363967 0.46713 -0.7616121 0.3238775 0.5612936 -0.7626566 0.2393823 0.6008753 -0.786116 0.489467 0.3774176 -0.7677616 0.4592986 0.4467515 -0.7357276 0.569584 0.366441 -0.6865367 0.5480133 0.4778587 -0.6035091 0.6453954 0.4682323 -0.6063556 0.6351899 0.4784002 -0.534943 0.5778256 0.6164038 -0.4126427 0.5117046 0.7535811 -0.4508234 -0.5304768 0.7178806 -0.5362098 -0.4549712 0.7109714 -0.6077814 -0.3166072 0.7282595 0.0106467 -0.1495344 0.9886992 0.264602 0.2596347 0.9287495 0.02734333 -0.4688526 0.8828531 0.1553506 -0.7886494 0.5948937 0.03446042 -0.054246 0.9979329 0.4455764 -0.402354 0.799733 -0.6325193 -0.103509 0.7675971 -0.7177462 4.04909e-4 0.6963047 -0.2715512 -0.8159976 0.5103019 -0.2508256 -0.7409099 0.6230081 -0.2933081 -0.684674 0.667227 -0.6135999 -0.1012657 0.7830967 -0.4979158 -0.221751 0.8383951 -0.5028476 -0.2461889 0.8285744 -0.1573094 -0.8359681 0.5257481 -0.1230684 -0.8580725 0.4985639 0.03166955 -0.9008564 0.4329604 0.1201567 -0.8222452 0.5563049 0.11949 -0.9019055 0.4150768 -0.7096277 0.5956828 0.3762854 -0.6679192 0.595309 0.4466446 -0.6794642 0.5349537 0.5021484 -0.6432913 0.6738558 0.3634483 -0.6456608 0.6700225 0.3663223 -0.427762 -0.3184974 0.845919 -0.7065632 0.0804221 0.7030653 -0.2328127 0.2231749 0.9465681 0.04307532 0.6594669 -0.7504984 -0.2214524 0.6356571 -0.7395261 -0.4211245 -0.5233851 0.7407578 -0.2805323 -0.6573678 0.6994064 -0.3046332 -0.5809847 0.7547553 0.03170984 -0.9019465 0.4306821 -0.03058636 -0.8517054 0.5231276 0.1353617 -0.8336054 0.5355178 0.04267501 -0.1337187 0.9901001 0.1612502 -0.5973476 0.7856044 0.04519146 0.09865182 0.9940953 -0.506982 0.7274785 0.462325 -0.5260145 0.7700229 0.361073 -0.4962854 0.7282843 0.4725493 -0.3842036 0.5669004 0.7287055 -0.3591442 -0.4167608 0.8350605 -0.3978199 -0.3203572 0.8597155 -0.1452407 -0.7794077 0.6094495 -0.6206984 0.2093828 0.7555742 -0.653527 0.2579275 0.711601 -0.6208136 0.1262435 0.7737268 -0.678018 0.4063487 0.6125132 -0.6617425 0.5267415 0.5335171 0.637247 -0.35618 0.6834121 0.2150509 -0.4324911 0.8756167 -0.3728398 0.7198142 0.5855409 -0.06571769 0.163415 0.9843662 -0.5201206 -0.0627591 0.8517841 -0.4902887 -0.006004035 0.8715395 -0.5661865 0.09059143 0.8192839 -0.6168558 0.3784857 0.6900997 -0.6071767 0.6731198 0.422192 -0.6121122 0.660929 0.4341562 -0.2675616 -0.4207555 0.8668192 -0.2421317 -0.4962856 0.8337103 -0.3797464 -0.1253027 0.9165653 -0.2451756 -0.09439051 0.9648727 -0.1979516 -0.1256564 0.9721243 -0.07590889 -0.7605426 0.6448355 -0.1480284 -0.6243475 0.7669928 -0.08733391 -0.654927 0.7506287 0.1897697 -0.8827647 0.4297839 0.1829096 -0.8385682 0.5131738 0.2119528 -0.852711 0.4774516 0.1112673 -0.8416575 0.5284243 0.2181823 -0.5144826 0.8292793 0.2172217 -0.5245372 0.8232106 0.2019314 -0.7902362 0.5785762 0.3089485 -0.7828833 0.5400415 -0.02255684 -0.8460791 0.5325801 -0.03897213 -0.777185 0.6280643 0.2542763 -0.8741475 0.4137749 -0.4397556 0.6030724 0.6655214 -0.1875157 0.725817 -0.6618365 -0.185153 0.7461484 -0.6395164 -0.5342837 0.7411177 0.4065535 -0.5177321 0.7730817 0.3664674 -0.3672978 0.8064498 0.463391 -0.3175005 0.6796566 0.6612567 0.08933067 -0.2531319 0.9632986 0.5122933 -0.6987117 -0.4993571 0.4248872 -0.7400987 -0.5212723 0.4071204 -0.7629984 -0.5020821 -0.1894776 -0.2862979 0.9392188 -0.2049855 -0.1273887 0.9704397 -0.1782879 -0.5078394 0.8428004 -0.2802348 0.03842568 0.9591621 -0.1532417 0.01499801 0.988075 -0.3410297 0.1126427 0.9332794 -0.3312169 0.1291748 0.9346707 -0.4581876 0.2488653 0.8533054 -0.5057653 0.4091503 0.7594718 -0.5435769 0.4126383 0.7309268 -0.4449566 0.3383173 0.8291894 0.09602111 -0.836214 0.5399318 0.07387876 -0.06699812 0.9950142 0.03499341 0.7146977 0.6985576 -0.5749194 0.5730999 0.5839729 -0.5673093 0.5712179 0.5931866 -0.4313482 0.8237267 0.3679854 -0.3781911 0.8079925 0.4517963 -0.3953927 0.8493385 0.3496983 -0.08211421 -0.04399979 0.9956513 -0.06243282 0.03570067 0.9974105 -0.03381508 0.03161388 0.998928 -0.5583639 0.643157 0.5240029 0.3195893 -0.8447241 0.4293063 0.3007576 -0.8340761 0.4624523 -0.2186735 0.6714268 0.7080734 0.1127267 -0.2339537 0.9656906 0.4261325 -0.9022833 0.06554591 0.1118963 -0.4824064 0.8687711 -0.2154001 0.7601798 0.6129677 -0.1029552 -0.4128209 0.9049747 -0.09730505 -0.236531 0.9667393 -0.06286686 -0.1546316 0.9859701 -0.04690551 -0.04979127 0.9976576 0.08355534 -0.7599823 0.6445507 0.1043135 -0.7429159 0.661207 0.08036547 -0.6228263 0.7782216 0.02148079 -0.5985774 0.800777 0.3654052 -0.8335738 0.414287 0.3544075 -0.8209674 0.4476695 0.3971114 -0.642589 0.6552725 -0.4646006 0.7081529 0.5316632 -0.4506717 0.7392802 0.5003597 -0.3480422 0.2132451 0.9129037 0.3127248 -0.5546662 0.7710698 -0.3730471 0.6948981 0.6147785 2.56881e-5 -0.4741557 0.8804411 -0.1754886 0.1343641 0.9752692 -0.05609089 0.04073458 0.9975944 0.01575261 0.05529493 0.9983458 -0.007659196 0.01400744 0.9998726 -0.004973709 0.06909817 0.9975975 2.53572e-4 0.06134265 0.9981167 -0.1598154 0.1541941 0.9750298 -0.2937712 0.3090382 0.9045408 -0.4303736 0.4852516 0.7611237 -0.4803923 0.5983313 0.6412666 -0.4264906 0.6590368 0.6194969 -0.3935264 0.7784581 0.4890193 -0.3719239 0.8085934 0.4559049 0.4693835 -0.6659783 0.5797863 0.3447786 -0.4736108 0.8104447 -0.2473538 0.8573783 0.4513521 -0.2594527 0.8444265 0.468645 0.01653289 0.04556441 0.9988246 0.2347864 -0.7774277 0.583508 0.180804 -0.7360675 0.6523148 0.04102128 -0.2069534 0.9774905 0.06893938 -0.3322574 0.940666 -0.05990111 0.1191633 0.9910662 0.002639293 0.02648478 0.9996458 0.4849064 -0.7617031 0.4297376 0.4744029 -0.7007078 0.5328702 0.325311 -0.4600497 0.826152 -0.1518216 0.2530567 0.9554646 -0.2586346 0.560944 0.7864159 -0.2941068 0.8832747 0.3651399 -0.3045313 0.8416535 0.4459597 -0.2850226 0.8874524 0.3622022 -0.3341948 0.4818324 0.8100317 -0.2815504 0.381634 0.880389 -0.001545608 0.009716391 0.9999516 0.0474506 -0.1006707 0.9937877 0.2898396 -0.7630839 0.5776644 0.3428953 -0.784834 0.5161962 -0.3039201 0.52537 0.7947447 -0.3441374 0.6766416 0.6509421 -0.3239979 0.6614175 0.6764261 0.4617716 -0.7854666 0.4120791 0.4241574 -0.7497454 0.5079098 0.4726715 -0.7009252 0.5341214 0.1471233 -0.5973226 0.7883912 0.1237685 -0.3734315 0.9193642 0.2176096 -0.6131767 0.7593816 0.2314243 -0.6758538 0.6997603 -0.02021533 0.03735476 0.9990976 -0.01548779 0.02509242 0.9995652 -0.05289906 0.160338 0.9856438 -0.1533625 0.3348134 0.9297204 -0.3158069 0.7459126 0.5864132 -0.1385374 0.8541055 0.5013096 -0.1599223 0.873771 0.4592919 -0.1331853 0.9285956 0.3463699 -0.1845909 0.9122657 0.3656467 -0.09069126 0.8858064 0.4551069 -0.1060177 0.8081716 0.5793264 -0.04012954 0.6525515 0.7566812 0.1472248 -0.7137973 0.6847031 0.01400327 -0.3626068 0.9318371 -0.01738744 8.18308e-4 0.9998486 0.3183196 -0.6979935 0.6414654 -0.03217124 0.05903959 0.9977371 -7.3923e-4 0.03552097 0.9993687 -0.03130346 0.04237371 0.9986113 -0.2401317 0.7862145 0.5693889 -0.2131546 0.8295255 0.5161904 -0.2142035 0.8402993 0.49801 -0.005661725 0.1098511 0.993932 -0.260192 0.3582186 0.8966492 -0.2772011 0.6669132 0.6916548 0.3981981 -0.4204728 0.8152552 0.4328278 -0.4343065 0.7899608 0.6210224 -0.6000168 0.5042927 0.544656 -0.623648 0.5607256 0.2759268 -0.5655215 0.7772065 0.2205019 -0.3356151 0.9158283 0.2820568 -0.4138714 0.8655371 0.4532689 -0.7121821 0.5360447 0.3719627 -0.6657441 0.6468605 -0.1640487 0.4966998 0.8522778 0.6129336 -0.6778532 0.4059897 0.5740433 -0.70046 0.4240638 -0.127605 0.8905771 0.4365654 -0.128005 0.8927513 0.4319835 0.1869555 -0.2050932 0.9607208 0.3962451 -0.5861254 0.7067157 -0.1659929 0.6867154 0.7077206 -0.132776 0.5295525 0.8378215 0.5773161 -0.6552357 0.4872088 0.5397745 -0.6547112 0.5291472 -0.153301 0.7045327 0.692916 -0.1105327 0.9029279 0.4153358 -0.00676763 0.03442776 0.9993844 0.1029145 -0.02601367 0.99435 0.1866734 -0.2055574 0.9606764 -0.05185115 0.1601805 0.9857249 -0.01291072 0.0554645 0.9983772 -0.01787233 0.02259618 0.999585 0.04202914 0.7619264 0.6462987 0.01455134 0.9013344 0.4328795 0.01864743 0.9031331 0.4289556 0.5488498 -0.5695334 0.6118788 0.4351876 -0.5500376 0.7127906 0.5085977 -0.5350564 0.6745688 -0.5195317 -0.09041398 0.8496541 -0.8434956 0.5215484 0.1284627 0.5502531 -0.3877193 0.7395238 -0.0822094 0.927533 0.3645879 -0.001089036 0.9345099 0.3559356 0.01839274 -0.2175138 0.975884 0.02535051 0.7355408 0.677006 0.4039586 -0.4428184 0.8004558 -0.03580617 0.1853261 0.9820246 -0.005864381 0.4282675 0.903633 -0.06393682 0.5147236 0.8549689 -0.08260816 0.7281658 0.6804047 -0.04978924 0.7818096 0.6215261 0.7181035 -0.5671384 0.403338 0.6754787 -0.6045134 0.4222467 0.6909465 -0.5408268 0.4796867 0.6931725 -0.4991866 0.5199276 0.03448325 0.8528427 0.5210282 0.01284843 0.8726131 0.4882432 -6.14859e-4 0.8034872 0.5953219 0.5498379 -0.3643296 0.7516264 0.576447 -0.4115972 0.7059014 0.6586922 -0.5957565 0.4595639 -0.0282365 0.04424774 0.9986215 -0.02874928 0.02650004 0.9992353 0.05962485 0.9266928 0.3710597 0.114284 0.9250551 0.3622324 0.08735316 0.8776059 0.471357 0.161116 0.6176817 0.7697474 0.1589576 0.6847624 0.7112194 0.2252622 0.8740637 0.4304295 0.2407761 0.8804011 0.4085593 0.4598325 -0.271711 0.8454154 0.4730296 -0.3782678 0.7957114 0.3725808 -0.2132573 0.9031639 -0.006376206 0.0309391 0.9995009 0.7061282 -0.4931185 0.5081507 0.6878538 -0.4698673 0.5532469 0.004144251 0.6599234 0.7513215 -0.04108321 0.09631145 0.994503 -0.2679674 0.3740713 0.8878425 0.5514395 -0.4261336 0.7171644 0.02272427 0.1196112 0.9925608 0.747648 -0.5200355 0.4130201 0.7493206 -0.4747103 0.4617022 0.7965116 -0.45457 0.3986673 0.7657151 -0.3975191 0.5056273 0.6052863 -0.2662222 0.7501696 0.7747735 -0.3940564 0.4944145 0.09476399 -0.1345635 0.9863632 -0.4315299 0.2083658 0.8777047 -0.1890442 -0.9603295 0.2050109 -0.1839895 -0.6612736 0.7272312 0.1345309 0.5882701 0.7973957 0.05025058 0.4502185 0.8915033 0.005639553 0.1066368 0.9942821 0.1088079 0.2887908 0.9511891 0.1101475 0.3394383 0.9341569 0.6006321 -0.398903 0.6929051 0.6880246 -0.4628416 0.5589273 0.1860796 -0.02235454 0.9822803 0.3120956 -0.05918806 0.9482052 0.03149348 0.07495689 0.9966894 0.03572648 0.6618566 0.7487787 0.0968064 0.5843785 0.8056863 0.08037698 0.7280183 0.6808297 0.2417925 0.9051664 0.3495858 0.1748846 0.9109127 0.3737025 0.8089849 -0.41622 0.4150956 0.7981444 -0.418309 0.4335704 0.08438611 0.848739 0.5220355 0.2042089 0.8814458 0.4258543 0.1127578 0.05883127 0.9918794 0.06168174 0.08625125 0.9943622 0.1307059 0.07715076 0.9884148 0.1744599 0.8046536 0.5675355 0.1553122 0.7341313 0.6610064 0.858004 -0.3236533 0.3988452 0.7714446 -0.3050594 0.5584015 0.2144848 0.7460952 0.6303477 0.1404076 0.1358903 0.980724 0.5547318 -0.232459 0.7988964 0.63372 -0.3142374 0.706862 0.1726726 0.6095762 0.7736932 0.2101225 0.6851962 0.6973915 0.701007 -0.2860506 0.6532719 0.7403081 -0.3450071 0.5769872 0.2340119 0.5400607 0.8084386 0.627371 -0.1500725 0.764123 0.8526707 -0.1599364 0.497366 0.8238418 -0.1820636 0.5367844 0.5953705 -0.1255245 0.7935853 0.4419796 0.8055962 0.3945488 0.3481475 0.7043092 0.6186615 0.3787951 0.7974656 0.4696414 0.5712809 -0.1408248 0.808583 0.3927797 -0.03756344 0.9188652 0.4546562 -0.04762649 0.8893928 0.8160538 -0.2962378 0.4962857 0.8121349 -0.2888599 0.5069485 0.2352205 0.8106592 0.5361931 0.2349847 0.8668693 0.4396815 0.388663 0.8512219 0.3526507 0.2998692 0.8813695 0.3650569 -0.1524019 0.1113794 0.9820226 -0.8124631 0.2957271 -0.5024433 -0.7560774 0.3860896 -0.5284712 -0.7574868 0.3748862 -0.5344848 0.3244681 0.6893281 0.6477248 0.09964489 0.1889414 0.9769198 0.2922673 0.8571558 0.4241037 0.6411923 -0.1076975 0.7597854 0.7444971 -0.1747914 0.6443384 0.8706444 -0.2754381 0.4075688 0.2942411 0.7825411 0.5486818 0.3169521 0.7209806 0.616221 0.2722378 0.6854094 0.6753522 0.8960248 -0.2052955 0.3936922 0.9035472 -0.1904014 0.3838618 0.2498852 0.1164373 0.9612491 0.3301011 0.1039214 0.9382077 0.2042886 0.253405 0.9455433 -0.382802 -0.7913573 -0.4766721 -0.2907607 -0.8230223 -0.4879474 -0.3328431 -0.7972666 -0.5035687 0.01700061 0.0703299 0.997379 -0.4427189 -0.8210571 -0.3603683 0.3684414 0.8148688 0.4474818 0.414098 0.832616 0.3677955 0.3942978 0.8078943 0.4379912 -0.2373099 0.01219236 0.9713575 0.6811443 -0.02102357 0.7318473 0.7256624 -0.009888947 0.6879799 -0.7306842 0.09810835 0.6756296 0.2286738 0.2628762 0.9373391 0.3655206 0.4517376 0.8138352 0.3483528 0.5386098 0.7671701 0.328531 0.550285 0.7676287 0.8249267 -0.2127044 0.5236916 0.7634255 -0.1620486 0.6252374 0.5501871 0.7546477 0.3574928 0.4897487 0.7279146 0.479882 0.4408718 0.6943649 0.5687614 0.05240052 0.1608397 0.9855886 0.2888998 0.2229604 0.9310347 0.6092785 0.07402253 0.7894937 0.664808 0.03030651 0.7463993 0.5899599 0.07446205 0.8039918 0.4614467 0.5864363 0.6657023 0.4581874 0.6657307 0.5889542 0.8656311 -0.1390748 0.4809792 0.8900175 -0.1320716 0.4363783 0.4412128 0.7735502 0.4549192 0.4808276 0.6782862 0.5556371 0.9222627 -0.01797324 0.3861457 0.9164083 -0.04051083 0.3981894 0.9132127 -0.0669949 0.4019383 0.8715408 -0.02085191 0.4898794 0.8645098 -0.009788095 0.5025207 0.5636468 0.7098685 0.4223613 0.499598 0.5647498 0.6568558 0.475241 0.1373757 0.8690649 0.5663963 0.7352639 0.3722665 0.5553539 0.7310175 0.3964789 0.5108364 0.3725491 0.7747603 0.4894061 0.4126406 0.768251 0.4917786 0.3019488 0.8166889 0.5249977 0.2485953 0.813989 0.705555 0.03514224 0.7077833 0.7928862 -0.04933881 0.607369 0.8502797 -0.04222357 0.5246348 0.8010451 -0.04081726 0.5972109 0.4371472 0.5556465 0.7072195 -0.09048712 0.05529636 0.9943614 -0.2769567 -0.3978156 0.8746644 0.5282585 0.5244596 0.6677464 0.5729767 0.6467224 0.5034361 0.696428 0.06275326 0.7148777 0.6327447 0.1624495 0.757129 0.8658695 0.12384 0.4846996 0.6241248 0.6284338 0.4642621 0.6530352 0.667364 0.358009 0.6520155 0.2206948 0.7253756 0.7775109 0.1221522 0.616892 0.7783511 0.1260432 0.6150469 0.7439961 0.2159072 0.6323401 0.6712979 0.2318177 0.7040027 0.8751941 0.007226884 0.4837179 0.5818119 0.5152837 0.6292676 0.5990561 0.6202732 0.5063527 0.9147839 0.1199092 0.3857362 0.8692536 0.1346511 0.4756757 0.8652296 0.1219999 0.4863063 0.9156898 0.1515487 0.3722168 0.8528017 0.1429862 0.5022792 -0.7114224 -0.05931854 0.7002567 -0.7862991 0.1101582 0.6079467 0.6548135 0.6090121 0.4475754 0.5382372 0.4577843 0.7076258 0.6218786 0.3944568 0.6765139 0.646479 0.4384423 0.6243664 0.6712178 0.5813957 0.4598324 0.6897332 0.6198252 0.3742794 0.7342673 0.5749655 0.3609241 0.6946205 0.5249695 0.491843 0.1852166 -0.03653985 0.9820182 0.2693828 0.09572702 0.9582638 0.8424711 0.2595694 0.4720871 -0.5519183 -0.5693541 0.6092801 0.2024379 0.3226897 0.9246028 0.6848468 0.4329499 0.5861223 0.7543144 0.3587663 0.5498151 0.7736685 0.2887279 0.5639799 0.8484163 0.2592495 0.4614973 0.8564136 0.2416425 0.4562506 0.7134096 0.5211007 0.4685091 0.893483 0.2321646 0.3844318 0.780633 0.4924694 0.3848194 0.7709995 0.479192 0.4194459 0.8721023 0.331055 0.3603338 0.7974677 0.3454164 0.4947047 0.7988355 0.4706632 0.3746171 0.7948742 0.4284802 0.4296276 -0.9878537 -0.07782137 0.1344953 0.5996679 0.3899282 0.6988236 0.7206232 0.4465391 0.530382 0.4760873 0.3150845 0.8210133 0.4897646 0.1925748 0.850321 0.801963 0.3938897 0.4491175 0.8369166 0.3422992 0.4270853 0.8614236 0.3485414 0.3694163 0.7858886 0.3217685 0.528057 0.3277338 0.1736035 0.9286832 0.626518 0.2305144 0.7445391 -0.4544421 0.1205396 0.882583 -0.03998041 -0.08691573 0.9954131 0.3979079 0.4090967 0.8211634 0.06978726 0.1050658 0.9920136 -0.8054059 -0.4555412 -0.3792145 -0.7926232 -0.5188114 -0.3202863 -0.7671644 -0.4095051 -0.4937251 -0.9093776 -0.1903712 -0.369853 -0.7891555 -0.3032406 -0.534115 0.787652 0.2875372 -0.5449098 0.8395256 0.13881 -0.5252891 0.7023344 0.4573916 -0.5454534 0.635336 0.524128 -0.5671315 0.6339428 0.5320389 -0.5612941 0.487322 0.6599546 -0.5718193 0.5398307 0.5850121 -0.6052632 0.4949935 0.6126941 -0.6161067 0.4312843 0.6920852 -0.5788022 0.3826433 0.6862486 -0.6185848 0.2883794 0.7442405 -0.6024479 0.8063825 -0.2501678 -0.5358762 0.7311046 -0.4208127 -0.5370315 0.7595426 -0.3177154 -0.5675843 0.05291193 0.7970799 -0.6015514 0.1568774 0.7816535 -0.6036615 0.6892902 -0.5112001 -0.5133745 0.6867238 -0.5251523 -0.5026187 0.7468898 -0.4083475 -0.5247932 -0.04813539 0.7588763 -0.6494535 0.05820941 0.7965008 -0.6018291 -0.4056523 0.695523 -0.5930379 -0.2420827 0.7511521 -0.6141389 -0.2946929 0.6970912 -0.6536207 -0.4635478 0.6460822 -0.6063838 -0.5254125 0.556379 -0.6437268 -0.3932462 0.5132624 -0.7628364 -0.5153235 0.2976241 -0.8036552 -0.6673408 0.5135404 -0.5393816 -0.6846019 0.4680537 -0.5587897 -0.8610463 0.09846538 -0.4989026 -0.8640051 -0.01280438 -0.5033202 -0.8682761 -0.02188026 -0.4955986 -0.4693911 -0.7372819 -0.4858884 -0.5335282 -0.6904343 -0.4885163 -0.5242918 -0.6933068 -0.4944128 -0.8706137 -0.1188007 -0.4774078 -0.8952413 -0.3802751 -0.232237 -0.8635241 -0.1340153 -0.4861751 -0.842971 -0.2826003 -0.4577522 -0.7201126 -0.5194457 -0.4600155 -0.711362 -0.5198132 -0.473031 -0.6247457 -0.5952552 -0.5053356 -0.6171583 -0.6168168 -0.488521 0.3042417 -0.8214961 -0.4822666 0.3435166 -0.7781527 -0.5258086 -0.8476924 0.1153863 -0.5177874 -0.8041515 0.2364715 -0.5453639 0.5458062 -0.7226688 -0.424082 0.620633 -0.5827733 -0.5245857 0.5674515 -0.6174442 -0.5447582 0.5153947 -0.6964178 -0.4993704 -0.1577243 -0.8596669 -0.4858971 -0.1108788 -0.8455676 -0.5222274 0.01946949 -0.878206 -0.4778863 0.7492654 0.3685582 -0.5502421 0.8008588 0.276545 -0.5311763 0.7223138 0.3869847 -0.5731542 0.855947 0.1078574 -0.5056892 0.8430588 0.1532359 -0.5155294 0.8657596 -0.04718017 -0.4982312 0.8453437 0.008800029 -0.5341505 0.8288487 0.4407123 -0.3446484 0.7509822 0.5086565 -0.4210634 0.7016265 0.5802169 -0.4136045 0.7856754 0.465197 -0.4078061 0.7014803 0.5505948 -0.4525162 0.8158591 0.408747 -0.4090232 0.8643321 0.3077508 -0.397768 0.8737288 0.2534703 -0.4151517 0.905921 0.1684218 -0.3885115 0.5978037 0.670336 -0.4396367 0.8529549 -0.1337937 -0.5045464 0.8223189 0.4014568 -0.403267 0.9096395 0.08152109 -0.4073211 0.9235082 0.009736061 -0.3834552 0.4988291 0.7600547 -0.416517 0.519591 0.6834917 -0.5127031 0.6103101 0.6658015 -0.4292204 0.4276903 0.7866295 -0.4453034 0.8566765 -0.1313729 -0.4988454 0.9129537 -0.1535937 -0.3780536 0.9151755 -0.06050777 -0.3984879 0.7004621 0.581117 -0.4143139 0.6004676 0.6803845 -0.4201378 0.8685854 -0.2598116 -0.4219686 0.7592006 0.4220746 -0.495447 0.8041129 0.3784543 -0.4584486 0.7483674 0.4437065 -0.4930223 0.8432893 0.2684494 -0.465616 0.8595917 0.2508991 -0.4451424 0.8904092 0.07998448 -0.448078 0.2663702 0.7409723 -0.6164471 0.2666321 0.8557904 -0.4433172 0.2885003 0.8128771 -0.5059629 0.3546552 0.7968451 -0.4891397 0.4983803 0.7602021 -0.4167852 0.3703752 0.8275831 -0.4218156 0.4047329 0.8052268 -0.4333605 0.209222 0.7931231 -0.5719982 0.9032709 -0.1844872 -0.3873839 0.8745495 -0.3129562 -0.3704345 0.8739285 -0.3173102 -0.3681895 0.7760345 -0.3370331 -0.5330846 0.6852732 0.500441 -0.5291121 0.6521658 0.571995 -0.4974952 0.5104232 0.7052623 -0.4920095 0.5686759 0.6550686 -0.4974866 0.8871949 -0.03063923 -0.4603764 0.8801307 0.05373191 -0.4716811 0.1452871 0.7955149 -0.5882583 0.583817 0.6215152 -0.522376 0.1699132 0.8600791 -0.4810339 0.8607736 -0.2175775 -0.4601401 0.8480859 -0.1146727 -0.5173013 0.7403184 0.2866948 -0.6080583 0.7722066 0.2416325 -0.5876315 0.7908237 0.2352268 -0.5650365 0.7242622 0.3512551 -0.59335 0.3076286 0.8489538 -0.4297 0.2759303 0.8659296 -0.4171672 0.8029004 -0.4531187 -0.3873427 0.830206 0.07169383 -0.5528274 0.6268372 0.4699952 -0.6214336 0.6548087 0.4029491 -0.6394198 0.3889608 0.7415643 -0.5466186 0.149108 0.8953573 -0.4196453 0.1564269 0.8917459 -0.424641 0.1471893 0.8504093 -0.5051132 0.8383398 -0.279017 -0.4683333 0.5582262 0.5911073 -0.5822163 0.6104618 0.4820131 -0.6284901 0.7779063 -0.04565554 -0.6267196 0.8045678 0.05355608 -0.5914411 0.7855219 -0.1021637 -0.6103426 0.05425316 0.7976983 -0.6006113 0.03297734 0.8774136 -0.4786002 0.8284063 -0.4210371 -0.3694196 0.8147487 -0.3082743 -0.4910719 0.7943704 -0.3820155 -0.472271 0.7757527 -0.4989862 -0.3862909 0.7525576 -0.5465222 -0.3673833 0.7364941 0.1279649 -0.6642301 0.4683102 0.5986067 -0.6498889 0.4089835 0.7462746 -0.525173 0.3912146 0.6893166 -0.609749 0.2601582 0.812963 -0.5209693 0.1367953 0.8711959 -0.4714921 0.1436773 0.8620709 -0.4859944 0.2645042 0.8130283 -0.518674 0.6602969 -0.6551439 -0.3671438 0.6712178 -0.639107 -0.3755115 0.4480286 0.5413181 -0.7115091 0.5034362 0.4581041 -0.7325931 0.6370878 0.2606495 -0.7253834 0.5953113 0.3053333 -0.7432201 0.7163396 0.1224264 -0.6869274 0.6501954 0.1966504 -0.7338764 0.00882858 0.8662334 -0.4995617 -0.001578927 0.9092033 -0.4163495 0.4949314 0.3991768 -0.7718166 0.5590173 0.3140375 -0.7673854 0.7714372 -0.2966484 -0.5629249 0.7486836 -0.168021 -0.6412814 -0.06180465 0.8868378 -0.4579289 -0.0699132 0.7381627 -0.6709904 0.6769753 0.02409577 -0.7356113 -0.01173174 0.9059357 -0.4232529 0.006494164 0.8828403 -0.4696285 0.7632024 -0.5051276 -0.4029497 0.7569956 -0.4384827 -0.4844489 0.6678019 -0.607486 -0.430118 -0.1900255 0.7558109 -0.6266102 0.5382738 0.07487183 -0.8394377 0.4815486 0.07187753 -0.8734671 0.3954825 0.1548156 -0.9053319 0.3557634 0.5302263 -0.7696055 0.3249995 0.6871371 -0.649783 0.2617567 0.6183524 -0.7410289 0.2678509 0.6002586 -0.7536216 0.2243392 0.7532171 -0.6183334 0.2225156 0.7633514 -0.6064499 0.6482449 0.01137602 -0.761347 0.712893 -0.184274 -0.676629 0.639483 -0.1585329 -0.7522824 0.6069397 -0.07978576 -0.7907328 0.5678807 -0.733973 -0.3725522 0.4010142 0.374444 -0.8360499 0.2711257 0.1435 -0.9517871 0.2680982 0.1510785 -0.9514719 0.29202 0.2364932 -0.9267122 0.6822975 -0.4125418 -0.6035557 0.7160934 -0.4545122 -0.5297442 0.7043114 -0.3530716 -0.615862 -0.1399129 0.849304 -0.5090258 -0.1288105 0.9011366 -0.4139572 -0.1992854 0.8578729 -0.4736449 -0.1751123 0.7819325 -0.5982619 0.3312482 0.4602655 -0.8236688 0.09775531 0.8267688 -0.5539832 0.6758427 -0.2955005 -0.6752157 0.6524033 -0.5665138 -0.5034204 0.6589221 -0.6094467 -0.4409042 0.5787808 -0.7277337 -0.3679899 0.4825294 -0.7616893 -0.4324291 0.4723792 -0.8043856 -0.3603078 0.171754 0.6650503 -0.7267796 0.1627838 0.6886593 -0.7065762 0.4540874 -0.08557021 -0.8868384 0.3936855 -0.009792625 -0.9191931 0.05120146 0.8202967 -0.5696418 0.02598363 0.730881 -0.6820101 0.01355332 0.7493326 -0.6620552 0.561708 -0.2326273 -0.7939575 0.553735 -0.2961344 -0.7782558 -0.01927238 0.8572492 -0.5145411 -0.1618689 0.8895826 -0.4271315 -0.1617096 0.846869 -0.5066192 -0.09533005 0.8420428 -0.5309202 0.2144581 0.3134711 -0.9250641 0.2279527 0.3927878 -0.8909295 0.178325 0.4548492 -0.8725322 0.6580528 -0.4266623 -0.620424 0.557453 -0.2919012 -0.7772 0.5577576 -0.386519 -0.7345131 -0.2491108 0.8151761 -0.5229071 -0.2721438 0.8708185 -0.4094058 0.567271 -0.6945787 -0.4424524 0.1588129 0.02369737 -0.9870243 0.1625754 -0.01567858 -0.9865716 0.1609252 -0.01471722 -0.9868569 0.4319519 -0.1217668 -0.8936389 0.5702838 -0.5444943 -0.6150629 0.5729631 -0.5571745 -0.6010575 -0.3134359 0.8250783 -0.4701104 0.1359679 0.4536669 -0.8807379 0.06000834 0.5449159 -0.8363406 0.05969017 0.5490472 -0.8336572 0.08447325 0.1053472 -0.9908413 0.04046899 0.0227859 -0.998921 0.08029049 0.1017785 -0.9915617 0.0287171 -0.01291525 -0.9995042 -0.01755148 0.6405222 -0.7677391 0.1880881 -0.1145755 -0.9754462 0.1357529 -0.0678457 -0.988417 0.2916018 -0.1493967 -0.944801 0.4817262 -0.5057752 -0.7156336 0.4887033 -0.4568974 -0.7432455 0.5067763 -0.7137531 -0.4834609 0.4996013 -0.6615163 -0.5592806 0.3394799 -0.8572137 -0.3872182 -0.008519351 -0.06240171 -0.9980148 -0.01371288 -0.0524562 -0.9985291 -0.09082722 0.7609371 -0.6424369 0.4001329 -0.2943423 -0.8679034 0.4633054 -0.7516533 -0.4694311 0.443307 -0.8140276 -0.3752839 0.0379197 0.249049 -0.9677484 -0.01325416 -0.04164093 -0.9990448 -0.1825403 0.8384702 -0.5134657 -0.3138459 0.8463807 -0.4302796 -0.3051806 0.8281498 -0.4701412 -0.4094412 0.813597 -0.4128171 -0.3973667 0.7488906 -0.5303419 0.3543493 -0.8613329 -0.3640636 0.361959 -0.8557503 -0.3696988 0.3732535 -0.3344419 -0.8653499 -0.4179537 0.6618384 -0.622322 -0.4793643 0.7334209 -0.4819789 -0.4056013 0.695542 -0.5930507 -0.1581909 0.6850706 -0.7110935 -0.139303 0.7350608 -0.6635363 -0.114616 0.6288457 -0.7690359 0.1635278 -0.2430057 -0.9561417 0.1099765 -0.1509881 -0.9823991 0.284988 -0.3385688 -0.8967459 -0.233999 0.778509 -0.5823816 0.426666 -0.5406222 -0.7250406 0.4004311 -0.6491121 -0.6467678 0.1878688 -0.8660117 -0.4633888 0.1780478 -0.8424668 -0.5084767 -0.04030865 0.3924603 -0.9188853 0.01775634 0.2539381 -0.9670575 0.05324387 -0.1077578 -0.9927505 -0.001736104 -0.02712845 -0.9996305 0.2240622 -0.90426 -0.3634695 0.1772781 -0.8421629 -0.5092486 0.1942615 -0.9440623 -0.266475 -0.03415852 0.03289371 -0.998875 -0.08282887 0.4053061 -0.9104211 -0.143109 0.5380158 -0.8306978 0.003080844 -0.05898535 -0.9982541 0.01620042 -0.06223374 -0.9979301 -0.02259647 0.05070078 -0.9984583 0.3057262 -0.5009226 -0.8096964 0.337736 -0.6877371 -0.6426135 0.3157439 -0.7805318 -0.5395146 0.2810394 -0.8516172 -0.4424535 0.2916307 -0.7973007 -0.5284536 -0.2854676 0.7587078 -0.5855516 -0.3428865 0.7814711 -0.5212792 -0.4467324 0.7874786 -0.4246266 -0.4192589 0.7508054 -0.510405 -0.4334266 0.7528014 -0.4954107 0.01168489 -0.02648085 -0.999581 0.01514035 -0.03061014 -0.9994167 -0.3109933 0.6837987 -0.6600776 -0.2769678 0.6631979 -0.6953111 -0.5032584 0.7592126 -0.4127072 -0.4736107 0.7464739 -0.4674074 0.2616202 -0.6541842 -0.7096464 0.260098 -0.5282734 -0.8082551 -0.5827277 0.6631568 -0.4697355 -0.5093241 0.6551787 -0.5579695 0.209147 -0.9059857 -0.368032 0.2117854 -0.889953 -0.4038946 -0.04505252 0.06411361 -0.9969251 -0.08766448 0.1320261 -0.9873622 -0.1336197 0.307895 -0.9419907 -0.2963908 0.5285695 -0.7954665 -0.2859321 0.5192834 -0.8053495 0.01448607 -0.02335584 -0.9996223 0.04044765 -0.121278 -0.9917942 0.01713043 -0.09371423 -0.9954518 0.07182884 -0.2586702 -0.9632914 0.1131216 -0.2956147 -0.9485861 0.1704987 -0.492418 -0.8534956 -0.3918725 0.6490491 -0.6520516 -0.4504988 0.6802535 -0.5781922 -0.5582529 0.6671176 -0.4932624 -0.5815858 0.6658071 -0.4673959 -0.5669375 0.7048051 -0.4264172 -0.5709266 0.7029116 -0.4242149 0.1660388 -0.9201586 -0.3545975 0.02875715 -0.8722662 -0.4881852 -0.249133 0.359421 -0.8993049 0.03614151 -0.9305337 -0.3644185 0.0323289 -0.03909516 -0.9987124 0.0278939 -0.05508047 -0.9980923 0.02562534 -0.03029584 -0.9992125 0.03055328 -0.03374606 -0.9989634 0.1647065 -0.6829889 -0.7116165 0.1447038 -0.7328121 -0.6648665 0.1769891 -0.7963857 -0.5783119 0.07828706 -0.8520815 -0.5175213 0.06788885 -0.8668974 -0.4938421 0.08173364 -0.8804333 -0.4670729 -0.6190997 0.5266594 -0.5825337 -0.654757 0.6133732 -0.4416636 -0.675976 0.6116151 -0.411076 -0.3509787 0.5306322 -0.7715201 -0.4154229 0.5787781 -0.7017406 -0.5369732 0.6355104 -0.554785 0.1180134 -0.620382 -0.7753704 0.1145398 -0.542123 -0.8324563 -0.6502203 0.5233098 -0.5507817 0.005209028 -0.9251586 -0.3795452 0.01175415 -0.9491897 -0.3144848 -0.2177749 0.21563 -0.9518813 -0.2716284 0.3199806 -0.9076511 -0.0471217 0.02473324 -0.998583 0.02461773 -0.02682489 -0.9993371 -0.5538295 0.5655633 -0.6110737 -0.5174291 0.5030111 -0.6922767 -0.5269821 0.504123 -0.6842149 -0.3869673 0.3459021 -0.8547562 -0.4521033 0.3999403 -0.7972768 -0.4548611 0.4129808 -0.7890172 6.47025e-4 -0.3514417 -0.9362096 0.02524513 -0.4637945 -0.8855831 -0.6810464 0.6021749 -0.4166066 -0.6612824 0.5933842 -0.4589127 -0.08625435 -0.9305031 -0.3559837 -0.1322513 -0.9493775 -0.2849419 -0.2443647 0.1279239 -0.9612083 -0.1241795 0.03211128 -0.9917401 -0.02893888 -0.1444573 -0.9890878 -0.01979184 -0.07937794 -0.9966482 -0.01343017 -0.1463029 -0.9891487 -0.01139253 -0.7551863 -0.6554113 -0.02015429 -0.6773987 -0.73534 -0.008066415 -0.7507296 -0.6605604 -0.7446349 0.4780787 -0.4657892 0.001476943 -0.3524536 -0.9358282 -0.7045353 0.4914178 -0.5119948 -0.6949144 0.4791517 -0.5361974 -0.0608024 -0.6298756 -0.7743126 -0.7424933 0.5334181 -0.4051777 -0.1221907 -0.02414286 -0.992213 -0.01904606 -0.8734094 -0.4866141 -0.07048803 -0.8985098 -0.4332571 -0.1526035 -0.9230239 -0.3531841 -0.37599 0.1592946 -0.912829 -0.1228445 -0.08037668 -0.9891658 -0.1219279 -0.02401059 -0.9922485 -0.1054362 -0.08893024 -0.9904416 -0.03755503 -0.07263362 -0.9966514 -0.6172732 0.4281253 -0.6600627 -0.6929002 0.4526939 -0.5612108 -0.7639512 0.4918146 -0.4177285 -0.7581544 0.4689167 -0.4531215 -0.1156913 -0.8146951 -0.5682319 -0.1073721 -0.7842613 -0.6110691 -0.820517 0.4117324 -0.3965204 -0.1895543 -0.8883582 -0.4181972 -0.1679845 -0.882769 -0.4387485 -0.1934816 -0.9096006 -0.3676845 -0.5599274 0.2847279 -0.778082 -0.6302479 0.3228611 -0.7060796 -0.07984125 -0.373673 -0.9241179 -0.1760534 -0.5382968 -0.8241612 -0.1809055 -0.5693243 -0.801962 -0.1329297 -0.6217133 -0.7718824 -0.2478969 -0.8206866 -0.5148016 -0.2330715 -0.8601402 -0.4536921 -0.2851427 -0.8922821 -0.3500375 -0.5350025 0.2070515 -0.8190861 -0.3535441 0.1652098 -0.920713 -0.1728598 -0.8410766 -0.5125522 -0.1009252 -0.2451044 -0.9642292 -0.1716898 -0.7363212 -0.6544874 -0.3255314 -0.01032757 -0.9454748 -0.3790008 0.02680867 -0.925008 -0.8360526 0.3600497 -0.413981 -0.8188567 0.3645766 -0.4433484 -0.6970205 0.2796279 -0.6602807 -0.7401132 0.3450887 -0.5771883 -0.8661603 0.3006671 -0.3992065 -0.9129109 0.2671695 -0.3085679 -0.3941536 -0.8254709 -0.4040308 -0.1873415 -0.2800626 -0.9415244 -0.2577288 -0.3915449 -0.8833281 -0.806486 0.2825108 -0.5193921 -0.82678 0.288835 -0.4827103 -0.2142958 -0.2065389 -0.9546827 -0.2849662 -0.7231016 -0.6292204 -0.2886216 -0.7256544 -0.6245985 -0.2880911 -0.7907876 -0.5400543 -0.3369568 -0.8082748 -0.4828583 -0.3062038 -0.8569152 -0.4146512 -0.3388996 -0.8273856 -0.4478619 -0.3138975 -0.8773891 -0.3628454 -0.6357703 0.1362359 -0.7597605 -0.5725034 0.1488597 -0.8062759 -0.7099468 0.2337157 -0.6643437 -0.2840696 -0.612831 -0.7373891 -0.888944 0.2279574 -0.3972583 -0.3822001 -0.8547469 -0.3511852 -0.4993627 0.04407066 -0.8652716 -0.8783783 0.1924344 -0.4375167 -0.8928195 0.1928607 -0.4070357 -0.9135981 0.1236388 -0.3873654 -0.7834939 0.1588231 -0.6007599 -0.3630741 -0.4491751 -0.8163449 -0.3720114 -0.5513164 -0.7467649 -0.4687992 -0.8010716 -0.3721717 -0.4701129 -0.7998609 -0.3731172 -0.4675306 -0.7982941 -0.3796601 -0.4414672 -0.7454339 -0.4994348 -0.3569931 -0.1182951 -0.9265863 -0.6780333 0.06786578 -0.7318915 -0.6622379 -0.03534364 -0.7484597 -0.6726365 -0.02765828 -0.739456 -0.5742226 -0.03779667 -0.8178263 -0.4613215 -0.5818125 -0.6698334 -0.4469336 -0.6841408 -0.5763696 -0.440727 -0.7380894 -0.5108658 -0.4629344 -0.6956924 -0.5492758 -0.3561228 -0.117738 -0.9269922 -0.3507939 -0.234669 -0.9065727 -0.4116473 -0.4144933 -0.8116292 -0.3949967 -0.2742121 -0.8768041 -0.5077428 -0.1181103 -0.8533741 -0.7867203 0.141777 -0.6008082 -0.8436279 0.02599292 -0.5362987 -0.4789839 -0.7815287 -0.3997343 -0.9170598 0.01993483 -0.3982512 -0.9221462 -0.01226317 -0.3866472 -0.5668623 -0.7450366 -0.3515504 -0.7623744 -0.06332671 -0.6440304 -0.8352055 0.08275747 -0.5436756 -0.8739851 0.01204401 -0.4858036 -0.6335768 -0.6812015 -0.3668038 -0.6465874 -0.6593608 -0.3836252 -0.6156266 -0.6710369 -0.4131749 -0.5811744 -0.6839331 -0.4409898 -0.5872183 -0.185474 -0.7878923 -0.5521716 -0.2784363 -0.7858626 -0.5855867 -0.4139401 -0.6969518 -0.5441209 -0.4575086 -0.7032912 -0.6028783 -0.3525719 -0.7157031 -0.5324595 -0.5306811 -0.6594426 -0.5468229 -0.6647759 -0.5089772 -0.7006587 -0.6459785 -0.3029677 -0.6304343 -0.173272 -0.7566568 -0.704679 -0.2237805 -0.6733126 -0.7812314 -0.1541875 -0.6049 -0.5910988 -0.5674556 -0.5732333 -0.9139742 -0.112934 -0.3897399 -0.871077 -0.1312921 -0.473273 -0.8672857 -0.122143 -0.4825937 -0.9140912 -0.1457746 -0.3784009 -0.6914159 -0.3058441 -0.6545254 -0.7833234 -0.1555016 -0.6018502 -0.6895272 -0.5777963 -0.4366964 -0.686199 -0.509238 -0.5194302 -0.6999045 -0.6170576 -0.3596854 -0.7562804 -0.5288295 -0.3852007 -0.7087044 -0.5320369 -0.4633304 -0.7264522 -0.3489226 -0.5920476 -0.70672 -0.4329201 -0.5595775 -0.7112531 -0.4666592 -0.5256885 -0.7476402 -0.5530204 -0.3676992 -0.8962066 -0.2273604 -0.3809477 -0.8622407 -0.2380552 -0.4470692 -0.8551627 -0.2720561 -0.4412284 -0.8912963 -0.2704719 -0.3639177 -0.8270919 -0.3607826 -0.4309929 -0.8504059 -0.3700464 -0.3739994 -0.8170208 -0.3613969 -0.4492987 -0.8424045 -0.3982427 -0.3629842 -0.8149195 -0.375711 -0.4413021 -0.8036651 -0.2787536 -0.5257555 -0.8382002 -0.2859243 -0.4644004 -0.7507153 -0.4551436 -0.4788224 -0.8343329 -0.339182 -0.4345621 -0.7769064 -0.5001691 -0.3824231 - - - - - - - - - - - - - - -

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

-
-
-
-
- - - - - 0.001 0 0 0 0 -4.37114e-11 -0.001 0 0 0.001 -4.37114e-11 0 0 0 0 1 - - - 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 - - - - - - - -
\ No newline at end of file diff --git a/cram_boxy/cram_boxy_assembly_demo/resource/cup.dae b/cram_boxy/cram_boxy_assembly_demo/resource/cup.dae deleted file mode 100644 index a3138bcd5b..0000000000 --- a/cram_boxy/cram_boxy_assembly_demo/resource/cup.dae +++ /dev/null @@ -1,228 +0,0 @@ - - - - - Blender User - Blender 2.77.0 commit date:2016-04-05, commit time:18:12, hash:abf6f08 - - 2016-08-04T16:00:59 - 2016-08-04T16:00:59 - - Z_UP - - - - - - - 49.13434 - 1.777778 - 0.1 - 100 - - - - - - 0 - 0 - 0 - - - - - - - - - 1 1 1 - 1 - 0 - 0.00111109 - - - - - 0.000999987 - 1 - 0.1 - 0.1 - 1 - 1 - 1 - 2 - 0 - 1 - 1 - 1 - 1 - 1 - 0 - 2880 - 2 - 30.002 - 1.000799 - 0.04999995 - 29.99998 - 1 - 2 - 0 - 0 - 1 - 1 - 1 - 1 - 8192 - 1 - 1 - 0 - 1 - 1 - 1 - 3 - 0 - 0 - 0 - 0 - 0 - 1 - 1 - 1 - 3 - 0.15 - 75 - 1 - 1 - 0 - 1 - 1 - 0 - - - - - - - cup_eco_orange.png - - - - - - - - cup_eco_orange_png - - - - - cup_eco_orange_png-surface - - - - - - 0 0 0 1 - - - 0 0 0 1 - - - - - - 0.5 0.5 0.5 1 - - - 50 - - - 1 - - - - - - - - - - - - - - - - 0.04121112 0.001282632 0.04122036 0.04032254 0.002092301 0.04089105 0.04121881 -0.01009523 0.04124546 0.04194813 3.58745e-4 0.03791487 0.04049926 0.00854367 0.04224365 0.03957128 -0.01226919 0.04149955 0.03695958 -0.02071863 0.04013407 0.03983634 -0.01348978 0.03563654 0.04142665 -0.005996882 0.03499674 0.04095232 0.007705152 0.03582268 0.03890985 0.01481586 0.03888875 0.03766691 0.01714253 0.04219603 0.03442502 0.01998412 0.04181814 0.03687161 0.01286309 0.03966224 0.03933179 -0.004224359 0.03915637 0.03900408 0.004397213 0.0383771 0.04104793 -3.80519e-4 0.02996307 0.0382387 -0.01067101 0.03913158 0.03616821 -0.02167588 0.0416451 0.03436034 -0.02253895 0.04136705 0.03615468 -0.01668828 0.03918945 0.02597224 -0.03218019 0.04188072 0.03148138 -0.02811282 0.04111176 0.03811967 0.0138188 0.03016299 0.03886795 0.001601576 0.01943731 0.03712838 0.01119905 0.01994699 0.03214436 -0.02624136 0.03322231 0.03554451 -0.02095949 0.03162306 0.03287035 0.02467966 0.04254192 0.03394663 0.02384126 0.04045814 0.03923815 -0.006697356 0.02378344 0.03411465 0.02133899 0.02910017 0.0383796 0.002615153 0.03306543 0.03643882 -0.004104256 0.02289468 0.03759717 -0.008064687 0.03168123 0.03591722 -0.01531285 0.0195406 0.03032839 -0.02569764 0.03908854 0.03749507 0.00775206 0.03315985 0.03251183 0.01498317 0.02043819 0.03464752 0.01770544 0.03980249 0.03316414 -0.02022838 0.03329771 0.0345689 -0.01125472 0.02049279 0.0300315 -0.01863771 0.01480829 0.0352509 0.007330596 0.02066922 0.03576868 -0.001213729 0.01855534 0.03150868 -0.02335596 0.02107828 0.02792263 0.02754139 0.0424 0.02960741 0.02448093 0.03944927 0.02815419 0.029509 0.04262632 0.0309444 0.02715945 0.03921955 0.02450913 -0.03396904 0.04147124 0.02812832 -0.03036695 0.03350025 0.03640049 0.007082641 0.008945703 0.0380879 -0.003809571 0.01560068 0.03682428 0.002721011 0.007568299 0.03386914 0.02015548 0.02521765 0.03439044 -0.01546198 0.01242262 0.03715038 -0.009124696 0.01488471 0.0292862 -0.02523332 0.03253835 0.02149689 -0.03317743 0.04022043 0.02562922 -0.02889591 0.03294962 0.03358036 -0.005003631 0.006957769 0.01414948 -0.0387637 0.04206204 0.03440934 0.01460558 0.0117315 0.02813583 0.02763241 0.02778774 0.02881938 -0.02229946 0.02108019 0.02742165 0.0223031 0.01941341 0.03455084 -0.01131874 0.004308938 0.03619343 -0.004415571 0.004685103 0.03114449 -0.01516968 0.01085263 0.03062421 -0.008049011 -0.006268441 0.03266227 0.01150929 0.01285141 0.0284667 0.01912951 0.0120905 0.02995878 0.0153076 0.007268726 0.02256876 0.03219044 0.0431627 0.02097707 0.03169119 0.04133385 0.03262215 0.01822644 0.01249051 0.02868258 0.02404445 0.01449686 0.03087717 -0.02087259 0.01042401 0.03069138 -0.01765322 -8.12224e-4 0.02115857 -0.03587931 0.03656637 0.02416718 -0.03050917 0.02049839 0.02376276 0.03247177 0.04293471 0.02287697 0.03337454 0.03751689 0.03391033 0.01103472 4.36937e-4 0.03604048 0.001860082 7.39581e-4 0.03489381 0.003120899 -0.004112839 0.03284865 0.00118947 0.00122416 0.03371757 0.005972087 0.00977993 0.02651673 -0.02568364 0.008270978 0.02477663 -0.02059102 -0.002940058 0.02442437 -0.02402865 0.009108603 0.021842 0.02978581 0.03230857 0.02475243 0.02596604 0.02426815 0.01578497 -0.03862607 0.03891235 0.02041661 -0.03277093 0.03430813 0.01651877 -0.0355913 0.03979605 0.008727908 -0.03916567 0.04221093 0.02146881 -0.02807611 0.01481437 0.02433854 0.02848351 0.01550245 0.02204281 0.03264576 0.03011596 0.01880365 -0.030864 0.02030593 0.01601004 -0.03371381 0.01175004 0.01435321 -0.03574788 0.01965463 0.02008831 0.03462874 0.04234093 0.01351279 0.03638929 0.04349201 0.008757591 -0.04052227 0.03919529 0.00188148 -0.04110515 0.04008835 0.03502804 -0.008570969 -3.91072e-6 0.031017 -0.00113368 -0.009829223 0.0293681 0.0112428 -0.006565093 0.03037875 0.006032407 -0.009778201 0.03073215 0.01741415 -5.96249e-4 0.02794349 0.0220291 0.001277148 0.0292133 -0.01297533 -0.004842758 0.02545797 -0.02528375 9.8557e-4 0.02319455 0.02277159 9.44331e-4 0.02028143 0.02831673 0.01829016 0.02126991 -0.03013849 0.008701622 0.01603186 0.03316384 0.03446292 0.01278978 0.0350362 0.04150861 0.03325062 -0.01113414 -0.003560006 0.01691007 0.03601002 0.03507763 0.008081734 -0.0377255 0.02120947 0.03292566 -0.006426811 -0.01267558 0.03343725 -3.48183e-4 -0.01311421 0.03337901 0.005156338 -0.01160311 0.03074085 0.01103913 -0.01818746 0.02945911 0.01622629 -0.01200449 0.02603995 -0.02328127 -0.003166079 0.02870529 -0.01756685 -0.01104241 0.02917677 -0.004117429 -0.01892501 0.02678954 -0.009386897 -0.02440416 0.02613383 -0.01340848 -0.01941043 0.02656126 0.01737952 -0.004352152 0.02409029 0.02678704 0.004539489 0.01751947 0.03311353 0.01749664 0.01217418 0.03803449 0.04184222 0.01267719 -0.0344327 0.02513945 0.00904119 -0.0377146 0.04001277 0.02049982 -0.02609264 0.00281471 0.02990728 -0.01318299 -0.01670837 0.003233075 0.03889274 0.04429751 0.005906462 0.0366764 0.0426948 -7.10538e-4 -0.04059666 0.04309719 0.003200948 -0.03845489 0.04058194 -0.004724323 -0.03939926 0.04323011 0.02844172 0.00448513 -0.02258849 0.01463979 -0.02947437 0.001270473 0.03048509 -0.007987201 -0.02464497 0.03130584 -0.002428054 -0.02600842 0.03134429 0.002724468 -0.02533805 0.02654463 0.01143753 -0.02308279 0.02580165 -0.01696455 -0.01063585 0.01780456 -0.03051519 -4.63089e-4 0.01972019 -0.02785551 -0.008084475 0.01891124 0.0308569 0.006659984 -6.82211e-4 -0.0382775 0.02138853 0.0304917 0.008104324 -0.02554386 0.02572923 0.01573669 -0.01538616 0.02551692 0.02163732 -0.01344639 0.02049171 -0.0204038 -0.02275699 0.01707196 -0.02402794 -0.01990294 0.01035475 0.03788739 0.03367453 0.004267692 0.03936696 0.04127174 0.01814752 0.02628284 -0.00272423 0.02056401 0.02145618 -0.01891094 0.01433998 0.03105229 0.01544117 0.008977055 -0.03562259 0.009174525 0.009242177 -0.03265476 -0.00900036 0.01146894 0.03548401 0.01752346 0.01109635 0.03396081 0.02757143 0.02927559 0.01271873 -0.02472174 0.02625763 0.01812696 -0.02402949 0.02363449 -0.02380609 -0.01152962 0.02619463 -0.01685082 -0.02579206 0.005759954 -0.03617048 0.02634912 0.006439507 -0.03337645 0.00940448 0.01175761 -0.03219765 0.01026475 0.007582247 0.03575831 0.03568744 0.01932871 0.0293622 -0.001439511 0.02276396 0.02545303 -0.009145736 0.01522958 -0.02656924 -0.01245272 0.01388126 0.03318822 0.005948603 0.003780007 0.03878158 0.03376853 0.003049612 -0.0367003 0.01074856 0.03019648 -1.36525e-4 -0.03176337 0.02910661 0.003857731 -0.03793561 0.0218271 -0.01531356 -0.035501 -0.00537765 -0.04027128 0.04043245 -0.01633828 -0.03766471 0.0437498 0.02927851 -0.007157742 -0.031304 0.02696961 -0.01238471 -0.03385245 0.0279302 0.01336991 -0.02882307 0.02752834 0.008950889 -0.04192495 0.02793723 0.001021921 -0.02784359 0.02605831 -0.004997372 -0.03202825 0.02421754 -0.01126563 -0.03454464 0.02184408 0.02409034 -0.02115261 0.008453845 0.03259813 0.01199811 0.002594947 0.03445941 0.02037549 -0.001737475 -0.03622561 0.02577823 -0.002978384 -0.03813451 0.04054915 0.01657027 -0.02726852 -0.02202147 0.02009934 -0.02274358 -0.03022098 0.01358342 -0.03087615 -0.01001173 0.0118457 -0.03004705 -0.0196011 0.01612126 0.02987241 -0.01084101 0.01034015 0.03287982 -0.006946146 0.007962286 -0.02919882 -0.01565974 0.008326709 -0.03130388 -0.00139743 0.001143991 0.03627961 0.0360201 -0.003089308 0.03651779 0.0425992 -0.003814339 0.03903919 0.04480868 -0.00407499 0.03858405 0.03377646 -0.01290839 0.03477972 0.04457378 -0.004803121 -0.03956633 0.03284424 0.02701312 0.009612917 -0.02643305 0.01378697 0.028602 -0.003751754 0.01364737 0.02668941 -0.01859301 0.009544014 0.02991926 -0.006654739 0.008168816 0.03473132 0.004034817 0.005480289 0.03676277 0.01770335 0.002389907 -0.034653 0.01475375 0.02335387 -0.01788574 -0.03558814 0.002563655 -0.03237247 -6.56583e-4 -0.001532316 -0.03376674 0.009092986 -0.01033776 -0.0365374 0.04176354 -0.01902532 -0.0350759 0.04421758 0.02265429 0.01743805 -0.02599525 0.02239841 0.01623928 -0.03424894 0.02866601 -0.003515899 -0.03969109 0.02866542 -0.001339375 -0.04203253 0.02554583 -0.01281869 -0.04205304 0.02690362 -0.009137749 -0.04177343 0.02595412 0.003917872 -0.03811568 0.02615106 -0.003397464 -0.03724569 0.02134191 0.02112263 -0.03852826 0.02532565 0.01586228 -0.03789258 0.009921967 -0.02602636 -0.03043138 0.01629775 -0.02222198 -0.03067278 0.004947483 -0.03470385 -0.001664817 0.02329778 -0.01054733 -0.03889775 0.01811802 -0.01859891 -0.03849256 -0.001457571 0.03722167 0.01953125 -0.007780551 -0.03622978 0.03328174 0.02858239 0.003627121 -0.04197293 0.02753579 0.005255043 -0.04195761 0.02095079 -0.01934313 -0.04207181 0.01727116 -0.0226925 -0.04204064 0.01276862 -0.02578431 -0.04196941 0.01405417 -0.02635192 -0.03341501 0.01872843 0.02132409 -0.02919298 -0.001499593 -0.03624761 0.007468819 -0.008065879 -0.03698182 0.0203424 -0.005764424 -0.03328216 0.009421288 -0.01103574 -0.03242623 0.01347368 0.02702569 -0.006351888 -0.04203373 0.02562755 0.01283723 -0.04186296 0.02379274 0.01334953 -0.03613454 -0.007255971 0.0383802 0.04190301 -0.01481759 0.03500622 0.0451973 0.001490235 -0.03357225 -0.01124703 0.005642175 -0.03190666 -0.01883065 0.001662373 0.03287416 0.00526309 0.004434287 0.03102397 -0.007762074 -0.00400269 0.0344327 0.02189761 -0.006252825 0.03566533 0.0370807 -0.01066523 0.03461223 0.04265773 -0.01104271 -0.03845679 0.036085 0.02303075 -0.006865262 -0.04070413 0.02438259 -0.001399159 -0.04059314 0.01681113 0.02746051 -0.02467948 0.0119732 0.03070026 -0.02041429 0.001312077 0.03616333 0.008322775 0.006196022 -0.009589731 -0.04175382 0.004811406 9.62761e-4 -0.04163974 0.02283835 -0.01574945 -0.04206335 0.02245789 0.01034301 -0.04033285 0.01880586 0.02461278 -0.03322726 -0.01719844 -0.03332215 0.04197293 -0.0130648 -0.0345143 0.03352344 0.02369266 0.01709663 -0.04179656 0.008373916 -0.02911257 -0.03204804 0.005444943 0.03407055 -0.00673145 0.00643593 0.03249412 -0.01925522 0.01883721 0.01785266 -0.03922706 0.01700705 0.02152049 -0.03615909 0.02166509 1.26243e-5 -0.04110383 0.006295859 0.029428 -0.01877152 0.007594883 0.0268079 -0.03662222 0.01299101 0.02463084 -0.0351333 -0.001486063 -0.02924638 -0.02232861 -0.002369701 -0.03006559 -0.01795995 0.006496667 -0.02744662 -0.02869063 -0.00569123 -0.03514224 0.003077566 -0.006404995 -0.03337514 -0.00968486 -0.006655812 0.03652912 0.01849174 -0.01084113 0.0368281 0.03285014 -0.01170891 0.03374826 0.03561562 -0.00859332 0.03329622 0.02025884 -0.01322388 -0.03310632 0.02522832 0.01876831 -0.01376068 -0.04121136 0.001555919 0.013601 -0.04147791 0.01929545 0.02274727 -0.04167056 0.009331762 0.03011947 -0.03292363 0.01273012 0.02753853 -0.04153364 -0.003070592 -0.03119146 -0.008018732 -0.006971657 0.03222554 0.004602134 -0.01597255 0.03514903 0.0432682 -0.02376866 0.02764874 0.0449447 -0.01870954 0.03029036 0.04301673 -0.01872664 -0.03527283 0.03924489 -0.01852321 -0.03454715 0.03196734 -0.01344597 -0.03568863 0.02366876 -0.02018243 -0.03655362 0.04391342 0.0210908 0.02186757 -0.04160392 0.01136964 -0.02682453 -0.03925734 0.01959961 0.01292139 -0.04073286 0.01305478 -0.02150267 -0.03987705 0.01355248 -0.0230835 -0.03594553 0.01318711 -0.02357506 -0.03124427 0.01305222 -0.02333295 -0.03149747 0.006583452 -0.02558302 -0.03841239 -0.009644269 -0.03395825 8.90062e-4 -0.01396918 -0.03390181 0.01234221 -0.01721698 0.03069829 0.03406792 -0.0198459 -0.03074938 0.03507894 0.01417279 0.008519649 -0.04015344 0.0152114 -0.005285561 -0.04048955 0.007228016 -0.0226587 -0.04082125 -3.44989e-4 0.03473341 -0.005529403 -0.00481534 0.0354706 0.004576981 -0.02549582 0.02790182 0.04474192 -0.02429074 -0.03192657 0.04424268 -0.02615171 -0.0267778 0.0435537 0.01090884 0.02186089 -0.04013687 0.01317387 0.02295339 -0.03883719 0.009927034 -0.02528566 -0.04194802 0.001145362 -0.03146427 -0.02643293 0.007474958 -0.02778112 -0.04188716 -4.88176e-4 -0.02992701 -0.03753697 -2.5626e-4 0.03295814 -0.0230599 -0.00235325 0.03137004 -0.008675456 -0.008561074 -0.03012698 -0.009137034 -0.01455396 -0.02917212 7.7243e-4 -0.01800751 -0.02863049 0.0119065 -0.02295249 -0.02891528 0.04169631 -0.001045525 -0.03242236 -0.01963424 -3.92803e-4 -0.003444194 -0.03941637 0.006617784 -0.0149213 -0.04023253 -0.01271539 0.03478461 0.01958864 -0.011599 0.03379762 0.004024147 -0.02481412 -0.03054827 0.03957694 -0.02282845 -0.03158426 0.03153204 0.005229592 0.01803553 -0.03956568 -3.76565e-4 0.008102476 -0.03923165 4.04403e-4 -0.02771204 -0.03510433 0.002405881 0.02906972 -0.02917379 -0.01318019 0.03165918 0.02181911 -0.0137524 0.02974408 0.005256116 -0.01850563 0.03291356 0.03167778 0.005323648 0.02565932 -0.03905117 -0.005029559 0.02549445 -0.03924614 -0.00201404 -0.02353727 -0.04045927 -0.00202763 -0.02597081 -0.03920626 0.004670321 0.03059625 -0.04137396 0.004983723 0.03059875 -0.0383048 -0.005841791 0.03082489 -0.04120522 -0.01261729 0.02855193 -0.04112201 0.004086792 0.03149819 -0.03365826 -0.004921078 0.03416556 -0.008473336 -0.005091786 0.03325235 -0.01834082 -0.02200788 0.03134965 0.04091495 -0.01983511 -0.03226947 0.02371168 0.00237745 0.02791512 -0.03702729 -0.009414315 -0.02774739 -0.02475637 -0.007323563 0.03047657 -0.01100164 -0.01090061 0.0290389 -0.01487571 -0.0204463 -0.03148949 0.01711654 -0.007738351 -0.03088057 -0.02527326 -0.00415337 -0.02810221 -0.03049206 -0.01135063 0.03345215 -0.002838909 -0.01544475 -0.03063315 -0.007109999 -0.0154103 0.03229707 0.005154013 -0.02001059 0.03054195 0.01853942 -0.02459466 0.02540606 0.04334682 -0.02255398 0.02656894 0.03392195 -0.02212417 -0.02642613 0.01888084 -0.01573789 -0.0295394 -0.01524895 -0.01695114 0.02942097 0.02106082 -0.02860158 -0.02221608 0.04119491 -0.02639156 -0.02360129 0.0295605 -0.03012371 -0.02480387 0.03730571 -0.02741163 -0.02792459 0.034653 -0.03185206 -0.02106422 0.04461491 -0.02699184 -0.02774399 0.04391252 -0.03258806 -0.01691174 0.0440191 -0.01052981 0.01632237 -0.03873938 -0.007012486 -0.01714587 -0.03968113 -0.007721185 0.0281288 -0.03458243 -0.001864135 0.0288093 -0.03353285 -0.0138958 -0.028122 -0.009762465 -0.01372498 -0.02635812 -0.02295148 -0.02094829 -0.03003799 0.01029056 7.47729e-4 -0.02882462 -0.04183322 -0.02706605 -0.02610665 0.02117699 -0.02456444 0.02821308 0.03253895 -0.007478296 -0.02816331 -0.04170173 -0.01075816 -0.01613497 -0.04154461 -0.02980369 0.02213418 0.04554909 -0.00642699 -0.0266813 -0.03717482 -0.01078051 0.03141546 -0.02541196 -0.001626074 0.03128898 -0.0390774 -0.007827579 0.03192037 -0.03004008 -0.0154345 0.03165936 -1.86869e-4 -0.02061498 -0.02332764 -0.01209503 -0.02246218 -0.02284449 -0.003480792 -0.02832251 0.02533733 0.04114633 -0.01398366 0.003107488 -0.03872776 -0.01680606 -0.007920861 -0.03900086 -0.00581783 -0.02884387 -0.04151046 -0.01009374 -0.0297178 -0.02976977 -0.03235965 -0.02220237 0.04183566 -0.005853593 0.02736592 -0.03782236 -0.01136934 -0.02345329 -0.03943085 -0.01781463 -0.01764583 -0.03959876 -0.01075154 0.03295832 -0.007190942 -0.02185028 0.02506744 0.01467466 -0.01906353 0.02654355 0.006581127 -0.02581274 -0.02137899 0.01134151 -0.02838373 0.02083599 0.0430516 -0.02732503 0.02159172 0.03526002 -0.0310111 0.01856654 0.04519057 -0.01226091 0.03185588 -0.01424121 -0.01551866 0.02690201 -0.01405179 -0.02476036 0.0228064 0.02215027 -0.03081399 -0.02137327 0.0213865 -0.03264915 -0.02006793 0.03141188 -0.03318715 0.01834356 0.04284083 -0.0354923 0.01346248 0.0453543 -0.01119804 -0.02558755 -0.03658747 -0.01956713 -0.02325606 -0.01827412 -0.02418315 -0.02634614 0.00159496 -0.02259635 -0.02590674 -0.01017445 -0.02847242 -0.02312737 0.01058793 -0.02923899 0.02302825 0.03090167 -0.02519863 0.02661424 0.02440398 -0.03483492 -0.01758503 0.04209655 -0.03645342 -0.008888065 0.04505032 -0.03290545 -0.01451307 0.04134595 -0.02952587 -0.01929771 0.03033167 -0.02429866 0.02543807 0.0043931 -0.02484065 0.0264849 0.01725417 -0.03354543 0.01274693 0.0447961 -0.03231978 0.01381808 0.04289752 -0.03057891 0.01654165 0.0355733 -0.03431761 -0.01044756 0.04328304 -0.01770752 0.02910518 -0.0128979 -0.02836292 0.01752465 0.01920515 -0.03180944 -0.01326543 0.02514654 -0.03388255 -0.006831407 0.02830642 -0.0143516 0.02240318 -0.03891229 -0.02436733 0.02143192 0.005694091 -0.01415342 0.02554064 -0.03574699 -0.03519821 0.003868401 0.04379361 -0.03352195 0.009744703 0.03669089 -0.02935481 -0.01557946 0.01049244 -0.03279614 0.01611256 0.02511626 -0.03543841 0.01126253 0.03083568 -0.03675413 0.007003068 0.04557228 -0.008480131 -0.02876287 -0.04199671 -0.008400678 -0.0286715 -0.04210263 -0.01281851 -0.02804213 -0.04160934 -0.01212352 -0.02762454 -0.03903728 -0.01794296 -0.02628636 -0.03150027 -0.02007824 0.02394777 -0.01099544 -0.03736627 -0.008992254 0.04156345 -0.03489643 -0.013071 0.02227288 -0.03692632 -0.00195378 0.04499328 -0.03818428 -0.002311348 0.04203921 -0.02973467 0.02076679 0.0198906 -0.03060436 0.0134117 0.0197466 -0.0353192 -0.00483793 0.04344934 -0.03493893 -0.002574861 0.03512829 -0.01828104 -0.02333188 -0.02597111 -0.01780003 -0.0219801 -0.0363813 -0.0197032 -0.02619493 -0.02183341 -0.02867108 0.02035492 0.004320383 -0.02753269 -0.01684075 -9.48066e-4 -0.03685528 0.008919239 0.04320883 -0.03638422 -0.007347047 0.02292919 -0.0130127 0.02947461 -0.03536272 -0.01409947 0.03014016 -0.02890038 -0.01861906 0.02738821 -0.02622425 -0.02107441 0.02783542 -0.001493692 -0.01688235 0.02438193 -0.03221833 -0.02497965 -0.01769417 -0.01831924 -0.03203707 -0.01751023 0.01043862 -0.03173196 -0.01017582 0.01356631 -0.03404694 0.002745449 0.02673542 -0.03305464 0.007972002 0.02593934 -0.02113658 0.01584464 -0.03864538 -0.02540755 0.007772207 -0.03864896 -0.02530026 -0.002625882 -0.03887385 -0.02713531 -0.02201437 -0.004052281 -0.02993839 -0.01829385 -0.004706263 -0.02604603 0.02291786 -0.002595603 -0.03791397 0.001863539 0.04029923 -0.03057515 -0.009162127 -0.003695189 -0.03289294 0.01487207 0.01707857 -0.02806329 0.01604366 0.004715621 -0.02003014 -0.01838153 -0.0384432 -0.02549964 0.01731377 -0.01643568 -0.03299522 -0.003561615 0.01307141 -0.03642159 0.004166841 0.02348285 -0.03713077 -0.001463115 0.02574825 -0.02357965 0.02428525 -0.01995193 -0.02193087 0.02544134 -0.01740676 -0.02352529 0.02486097 -0.009978115 -0.02432924 -0.02313107 -0.01878112 -0.02894562 -0.01140969 -0.01257163 -0.03544533 0.008637905 0.02325117 -0.0310744 0.01004886 0.008924603 -0.03586649 -0.006595671 0.01494127 -0.03367233 -0.01257073 0.006471633 -0.03283774 0.003284037 0.01306819 -0.0190742 0.02056312 -0.03782618 -0.01986241 -0.02398496 -0.04145121 -0.03184455 -0.004838883 -5.92676e-4 -0.0363807 -0.002640366 0.01618534 -0.02289795 -0.01721823 -0.0362609 -0.02549695 -0.01413106 -0.03464651 -0.02533733 -0.01561337 -0.02429354 -0.02125459 0.02127528 -0.02641254 -0.02578574 -0.02054941 -0.02489984 -0.02230238 -0.02322369 -0.03220254 -0.02783548 -0.01130253 -0.02532213 -0.02900689 0.01289772 -0.003711938 -0.01771044 0.02740579 -0.03039437 -0.01618677 0.02744054 -0.04106533 -0.02987861 0.01747936 -0.006665229 -0.03201937 0.01324588 -0.001373469 -0.02771091 -0.0195685 -0.01777136 -0.03208446 -0.01346647 -0.007386684 -0.03428924 0.01014101 0.01423281 -0.0359683 0.005392491 0.01683825 -0.03226584 0.01403379 0.005975544 -0.0311346 0.008079349 9.44295e-4 -0.03200268 0.00236845 -8.15881e-4 -0.02049928 0.0214709 -0.03411442 -0.03090876 -0.01270461 -0.02376687 -0.02626883 0.0211361 -0.01434457 -0.02604812 0.01513165 -0.02502006 -0.02914148 0.01040685 -0.01492458 -0.03477764 -0.004344463 -0.001489996 -0.0342186 -0.007567703 -0.003439486 -0.03566569 5.28313e-4 0.008729398 -0.01066434 0.01050305 -0.04131293 -0.02580171 0.01883524 -0.04099076 -0.03127056 0.004525959 -0.04103893 -0.02356189 0.02276617 -0.03119677 -0.02636265 0.02001029 -0.02364295 -0.02985829 -0.006861925 -0.01909035 -0.03126639 -0.001507937 -0.01073634 -0.03530782 0.005448639 0.01198309 -0.03449153 0.004043579 -0.003838062 -0.02529245 -0.01018047 -0.03860718 -0.02463394 -0.01971089 -0.03858518 -0.02506858 -0.0199939 -0.04137831 -0.02909159 -0.01264023 -0.04120665 -0.0307874 0.003309965 -0.01409238 -0.02210146 0.02302038 -0.04086935 -0.02763724 -0.01706284 -0.03342795 -0.03243082 -0.009818077 -0.01778733 -0.02999889 0.01576268 -0.01049435 -0.0305581 0.0143482 -0.01609879 -0.03262215 0.01084095 -0.006177902 -0.02423894 0.01509618 -0.03727728 -0.02898371 0.00532484 -0.03600531 -0.02795171 0.001752197 -0.03780269 -0.03452801 -0.00140804 -0.008445978 -0.02535676 0.01510429 -0.03535711 -0.02909958 0.00737971 -0.02574646 -0.03314524 -0.004383444 -0.02316516 -0.03158217 -0.00649321 -0.03789818 -0.03022837 8.24393e-5 -0.02347987 -0.03314173 0.002977609 -0.02424263 -0.03218334 0.009452998 -0.01893281 -0.02775621 -0.004507899 -0.03775846 -0.02812063 0.01641339 -0.03474211 -0.0289793 -0.006054997 -0.03473061 -0.02787601 0.01021534 -0.03433054 -0.02958768 3.18229e-4 -0.03537642 -0.03138035 0.009073793 -0.03150695 -0.03234803 -0.001040339 -0.03643912 -0.03218376 0.003944933 -0.03590452 -0.03103446 0.01026552 -0.04055923 -0.03027427 0.0129655 -0.04096156 -0.03178244 -0.005843997 -0.04111582 -0.01824915 -0.004848599 -0.04132801 -0.03247088 -0.002261459 -0.04106044 - - - - - - - - - - 0.4995402 1.52597e-4 0.8662908 -0.7039831 -0.09366297 0.7040137 0.7702479 -0.1473475 0.6204894 0.9986433 0.03527998 0.03830134 0.3961345 0.05243134 0.9166943 -0.157753 -0.02917617 0.9870475 0.8861178 -0.4595239 0.06027489 0.9372413 -0.3290874 -0.11524 0.9856701 -0.1270198 -0.1109973 0.9754788 0.2077733 -0.07260465 0.9259874 0.3773717 -0.01174992 0.5861809 0.3005829 0.7523576 -0.5480034 -0.3820703 0.7441201 -0.8743741 -0.3634222 0.3215499 -0.96246 0.06961476 0.2623448 -0.9616006 -0.1702669 0.2152522 0.9856918 0.01870793 -0.1675169 -0.893812 0.2280995 0.3860967 0.5236501 -0.3330571 0.7841323 -0.4964628 0.3703557 0.785087 -0.8527658 0.4059961 0.328569 0.07278764 -0.006195306 0.9973283 0.6591619 -0.6159156 0.4314553 0.9135807 0.37471 -0.1579959 0.9827331 0.0693385 -0.1715456 0.9394075 0.3014369 -0.1632465 0.7578226 -0.6365393 -0.1432572 0.8501981 -0.5017322 -0.1594617 0.4725052 0.3534786 0.8073362 0.8121138 0.5823659 0.03634822 0.9682906 -0.167918 -0.1849784 0.8108458 0.5589978 -0.1733515 -0.9826512 -0.07574814 0.1692889 -0.9785523 0.1008338 0.1796332 -0.9637296 0.2019748 0.1744467 0.9004127 -0.3957445 -0.1806746 -0.7147226 0.635465 0.2921576 -0.9538176 -0.252333 0.1629727 -0.8827952 -0.4431372 0.1558915 -0.8375009 -0.4672756 0.2832769 -0.8407503 0.5162063 0.1633096 -0.9357449 0.3035731 0.1795131 -0.8348841 0.5207496 0.1782933 -0.9604282 -0.2194305 0.1715464 -0.9845693 -0.02566635 0.173103 0.7776912 -0.6009848 -0.1844277 -0.3403797 -0.4609912 0.8195297 -0.7069718 -0.6692199 0.2287701 0.4802865 0.5181308 0.7077184 0.6994768 0.7135768 -0.03924804 0.4916626 -0.731329 0.4726797 0.6457861 -0.7508636 -0.138435 0.963325 0.2208948 -0.1523497 0.9824398 -0.0792275 -0.1689231 0.9875962 0.06177049 -0.1443551 0.8281143 0.5305193 -0.1810413 0.8911184 -0.4205796 -0.1703559 0.9549261 -0.2434544 -0.1698412 -0.7366724 0.6515238 0.1811925 -0.4621499 0.7844311 0.4136247 -0.6307821 0.7596974 0.1580312 -0.9773355 0.127111 0.169288 0.2213831 -0.523702 0.8226334 0.9023003 0.3982756 -0.1650173 0.6746008 0.7233708 -0.147134 -0.7520913 0.6321193 0.1865044 -0.7443774 -0.6500103 0.1529346 0.9306963 -0.3323588 -0.1527813 0.9809367 -0.112584 -0.1583928 -0.8848478 0.4317269 0.1750895 -0.9547326 0.2402778 0.1753634 -0.9276674 -0.3372697 0.1602573 -0.806921 -0.5712231 0.1502753 -0.8710946 -0.4652125 0.1573903 -0.1541526 -0.2784879 0.9479882 -0.4587374 -0.8166081 0.3503019 0.8394001 0.5201998 -0.1574791 0.7450743 0.6506468 -0.1467075 0.8148572 -0.5541945 -0.1699298 0.8484895 -0.500939 -0.1706623 0.4908416 -0.8661068 -0.09451818 0.6054722 -0.7765328 -0.1743566 0.42785 0.6303457 0.6477721 0.5206871 0.852064 -0.0535916 0.9330783 0.3229792 -0.1582699 0.9804759 0.0247507 -0.1950758 0.9820389 0.08520889 -0.1683425 -0.9852788 -0.04654163 0.164498 -0.9698883 -0.1834791 0.1601628 0.703066 -0.6940323 -0.1549754 -0.7618239 0.6257076 0.1676732 -0.7120969 0.6815475 0.1685557 -0.5522448 -0.82295 0.1333383 -0.6506754 -0.7426001 0.1586403 0.3557305 -0.934586 -0.002227842 -0.4888607 0.8567118 0.1644998 -0.3880574 0.9185196 0.07571923 -0.01492381 -0.0363788 0.9992267 -0.602824 0.7794412 0.1705132 0.6153567 0.7761008 -0.1378548 0.5249301 0.8398272 -0.1383435 -0.4696882 0.8672905 0.1649249 0.409072 -0.8979198 -0.1624813 0.320024 -0.9340698 -0.158425 0.3932437 0.8531419 0.3427949 0.08523964 0.05298101 0.9949509 0.1545484 -0.9857958 0.06573802 0.03970479 -0.9968324 0.06891119 0.9599557 -0.2378373 -0.1480494 -0.9849459 0.02447634 0.1711211 -0.9177967 -0.3650373 0.156196 -0.9678794 -0.1890956 0.1656876 0.8581342 0.4909597 -0.1502147 0.772207 0.6187545 -0.1443577 -0.8947536 0.4144164 0.1663586 0.6956336 -0.6966103 -0.1755793 -0.6999633 -0.6994751 0.1441738 -0.5560271 -0.8184301 0.1449351 0.5592342 -0.8132762 -0.1607447 -0.3845965 -0.9154387 0.1185651 -0.2516598 -0.9023864 0.349809 0.9052084 -0.3843321 -0.1813468 0.3758735 0.9229289 -0.08319509 0.1634913 -0.9749048 -0.1511005 0.9633569 -0.1968158 -0.1822278 0.9857648 -0.02475088 -0.1662982 0.9741438 0.1564416 -0.1630033 0.9273222 0.3450487 -0.1449656 0.8641966 0.4801974 -0.1502486 0.7453486 -0.6403308 -0.1855589 0.8324002 -0.5286161 -0.1663579 -0.9743539 0.1272037 0.1856173 -0.9402616 0.2841629 0.1875091 -0.8872302 0.4288284 0.1700847 -0.8234801 -0.5465146 0.1523233 0.6542394 0.7442099 -0.13462 0.4446293 0.8862068 -0.1301629 0.2725954 0.9284176 0.2524529 -0.3047895 0.9386003 0.1616571 -0.1739913 0.9229077 0.3434657 -0.6051702 0.7767201 0.1745712 0.9018126 -0.396933 -0.1708161 0.09070438 0.3917503 0.9155897 -0.09564602 -0.8755854 0.4734997 0.01086497 -0.6381963 0.769797 -0.01092582 0.9602538 0.2789143 0.1341016 0.4796101 0.8671742 -0.9795364 -0.1325743 0.151435 -0.4333764 0.8861631 0.1640115 0.9434833 -0.282581 -0.1731683 0.9790935 -0.09338939 -0.1807054 0.9826253 0.07742708 -0.1686794 -0.9132422 -0.387191 0.1267747 -0.8233385 0.5433277 0.164039 0.4865379 -0.8579572 -0.1648955 0.5670145 -0.8070778 -0.1646811 0.5040834 0.8538319 -0.1298891 -0.04583972 -0.9882711 -0.1456679 0.9585554 0.2304525 -0.1675213 -0.8399148 -0.5223336 0.147346 0.7719767 0.6202366 -0.1391358 -0.7110514 0.6830343 0.1669436 -0.5772086 0.7996931 0.1652916 0.2114366 0.9718517 -0.1039177 0.07605427 0.9960606 0.04559588 -0.5617631 -0.8169018 0.1307433 -0.6909568 -0.710245 0.1346511 -0.3978841 -0.9078059 0.1325772 0.2268807 -0.962 -0.1519252 0.2640845 -0.9525416 -0.1514068 0.279127 0.9531397 -0.1166742 -0.2585302 -0.9573339 0.1291278 0.904234 0.3939161 -0.1648973 0.8226621 0.550832 -0.1407522 0.701313 -0.6931032 -0.1666377 0.8263701 -0.536254 -0.1718845 -0.1188422 0.9813486 0.1511011 -0.1544596 0.9761387 0.1526285 -0.3154483 0.9361819 0.1550995 -0.164712 -0.9805507 0.1067255 0.5215122 0.8429101 -0.1323923 0.65396 0.7436246 -0.1391358 -0.4672246 0.8694425 0.1605331 0.3698933 0.9204301 -0.1264412 0.05771106 0.9934487 -0.0986368 0.06778252 -0.9868598 -0.1466739 0.9829563 -0.05380499 -0.1757895 0.9780969 0.112187 -0.1753304 -0.79699 0.5477971 0.2544117 -0.1768574 -0.9839314 0.02450668 -0.2331029 -0.7921779 0.5640189 0.9535655 -0.2370714 -0.185769 0.8946768 -0.4182991 -0.1567782 0.8995544 0.4035863 -0.1670928 0.6447221 0.1805832 -0.7427808 -0.9860028 0.006500482 0.1666023 -0.9652796 0.2253814 0.1320549 -0.9087055 0.3665952 0.1996558 0.6828753 0.7185222 -0.1319361 -0.2330457 -0.9652965 0.1178657 -0.0631749 -0.9915413 0.1133791 0.08966499 0.9853386 0.1451486 0.1288531 0.9439362 0.3039432 0.5268773 -0.834141 -0.1631232 0.663064 -0.7307559 -0.162302 0.4090194 -0.9004409 -0.1480185 0.3631714 -0.9186405 -0.1555838 0.4895642 0.8641918 -0.1161879 0.3211547 0.9406356 -0.109839 -0.2567242 0.9538347 0.1558595 -0.2469601 0.9568331 0.1532361 0.01052898 -0.9955254 0.09390652 0.168986 -0.9522671 0.2542268 -0.06302136 0.6573145 0.7509768 -0.13169 0.9882097 -0.07809847 0.3043687 -0.6300095 0.7144563 -0.1606204 -0.9783717 -0.1303458 -0.9461838 -0.2996976 0.1221374 -0.4304979 -0.8941392 0.1232348 -0.4748423 -0.8707628 0.1276602 -0.3055225 -0.9444921 0.1207929 0.2177857 0.9699338 -0.1086181 0.1289119 0.9862188 -0.1037033 -0.04397815 0.9864107 0.158303 0.7941983 -0.5856003 -0.1622394 -0.07245296 0.9864777 0.1470118 0.04370313 0.9882959 0.1461553 0.3120906 0.8856404 0.3438612 0.1687996 0.1662055 0.9715362 -0.8040798 -0.5804988 0.1283622 -0.7826251 -0.583154 0.2177824 0.9586326 -0.2023105 -0.2002352 0.6688662 -0.06979817 -0.7400988 0.5994018 -0.3314716 -0.7285906 0.7946379 -0.21382 -0.5681828 -0.888118 -0.1292501 0.4410681 -0.9369781 0.1614785 0.3098336 0.7618235 0.6434085 -0.07516908 0.8595319 0.4806103 -0.1738352 -0.4098384 0.8943872 0.1791765 -0.5765632 0.7966045 0.1816485 0.122932 -0.9811064 -0.1493923 -0.7878208 0.3630556 0.4975228 -0.6300131 0.6160656 0.4728074 -0.04187184 0.9929316 -0.1110582 0.2457994 0.9597899 0.1355956 0.6835326 0.2108858 -0.6987921 0.4968822 0.1213136 -0.859297 0.5217896 -0.4206179 -0.74217 0.4026714 -0.5255116 -0.7494621 0.2080798 -0.6615034 -0.720497 0.4887635 -0.8592961 -0.1507338 -0.6697381 -0.7309591 0.1309567 -0.05819934 -0.9885961 -0.1388911 -0.2342022 -0.9620784 -0.1398376 0.1901353 0.9729556 0.131172 0.345995 0.9300389 0.1237549 0.498802 -0.07867789 -0.8631375 0.5388132 0.2707342 -0.7977365 -0.8440221 -0.4253529 0.3266522 -0.2738467 0.9606761 0.04593104 -0.1346819 0.4286138 0.893393 0.05209624 -0.9882115 -0.143959 0.1835123 -0.9715195 -0.1499106 -0.04458761 -0.9931666 0.1078527 -0.1508561 -0.9822283 0.1116696 0.11692 -0.9874264 0.1063908 0.2092673 -0.9750144 0.07452684 0.3312512 -0.915534 0.2281891 -0.3137392 -0.9419808 -0.1193308 -0.5327475 0.1467375 0.8334556 -0.5857797 0.03540188 0.8096969 0.5399446 0.8326842 -0.12287 0.3828632 0.915942 -0.1202761 0.03366297 0.9942339 -0.101813 -0.01559531 0.008697926 -0.9998406 -0.01565635 0.008728444 -0.9998394 0.4604447 -0.3377876 -0.8209082 -0.5594491 -0.229383 0.7964925 0.6311417 0.763718 -0.1356283 0.482104 0.7546359 0.4450848 0.4082592 0.9035295 0.1302266 0.5583483 0.343066 -0.7553496 0.2895991 -0.9441803 -0.1570225 0.161081 0.9810436 -0.1077332 0.2087527 0.9718598 -0.1091374 -0.5555134 -0.5077812 0.6584552 -0.6308 -0.7216554 0.2851403 -0.05945163 -0.02362191 0.9979518 -0.2714414 -0.9556297 0.114418 -0.3039414 -0.8825867 0.3586929 -0.4894327 -0.8439105 0.219706 -0.001281738 0.9887776 0.1493893 0.03787434 0.986747 0.1577843 -0.2271836 0.9623869 0.1489939 -0.1694098 -0.9771507 -0.128362 -0.1874783 -0.9727324 -0.136542 -0.1967262 0.9751771 -0.1016286 -0.34166 0.9370244 -0.07248258 0.3963249 -0.9154905 0.06930953 0.2883149 -0.9526265 0.0968374 0.4205863 0.8985184 0.1255868 -0.3138306 0.2334121 0.920342 -0.01568681 0.008758962 -0.9998386 0.3859175 0.5464189 -0.7432994 0.3447754 0.9308052 -0.1213749 0.3105615 0.616362 -0.7236363 0.1069385 0.9859766 0.1281186 0.2120153 -0.9723958 0.09744709 -0.457666 0.8751383 0.1570823 0.2664285 -0.2953603 0.9174848 0.5507235 -0.8081856 0.2086614 -0.4959619 -0.8417711 -0.2131742 -0.4857763 -0.8655894 -0.1215585 -0.3824623 -0.9143753 -0.132818 -0.4324535 -0.7764937 0.458303 0.553775 0.6268079 -0.5481289 0.3507581 -0.9035236 -0.2461991 -0.1711792 -0.1662963 0.9711042 -0.3863442 0.607945 0.6936433 -0.5070534 0.8277539 0.2402507 -0.2737541 0.8275798 0.4900718 0.05990964 0.9503449 0.3053776 -0.2395415 0.8378918 0.4904665 -0.289655 -0.9482225 -0.1302852 -0.3848531 -0.914339 -0.1259852 0.5380602 -0.839899 0.07114112 0.5851772 0.8035733 0.1088013 0.08743625 -0.003692746 0.9961633 0.09183061 -0.03155624 0.9952746 -0.08499526 0.3388519 0.9369927 0.0140081 0.9946708 -0.1021466 -0.1364829 0.9863882 -0.09171086 -0.5167462 0.5777535 0.6318024 -0.5396416 -0.4089276 0.7359111 0.5009527 0.4114075 0.7614396 -0.09894382 -0.2678381 0.9583699 -0.4051169 -0.6573917 0.635387 0.1069392 -0.3073281 -0.9455757 0.05865764 -0.9870784 -0.1491162 0.2208362 -0.638826 -0.7369754 0.03186231 -0.9849247 -0.170024 0.01815903 0.9946877 -0.1013243 0.03469973 -0.9938716 0.1049537 0.2554121 0.9581997 0.1289115 0.4548231 0.8817824 0.1248833 0.5413264 0.8327887 0.1158829 0.6519473 0.7466173 0.1323915 -0.01361143 -0.9895479 -0.1435613 0.05066144 -0.0275281 0.9983365 0.07269662 -0.0571013 0.9957181 -0.3916521 0.9160624 -0.08624702 -0.3210588 0.9434916 -0.08212631 -0.6797292 -0.7252336 -0.1095648 -0.6104426 -0.7844929 -0.1092277 0.06631743 0.022767 0.9975389 0.05313372 -0.008179068 0.9985539 -0.0666846 0.9659353 0.2500445 -0.1422781 -0.9826409 0.1190534 0.4299195 -0.8980182 0.09344881 0.4424069 -0.8925657 0.08719342 -0.5300832 0.844245 -0.07913553 -0.1216198 -0.5787091 0.8064146 0.06921762 -0.3259151 0.9428618 0.04892152 0.2142109 0.9755616 0.02697873 0.7305629 0.6823124 0.1460661 0.7133313 -0.6854366 0.2255395 0.9689347 -0.1014775 -0.1187202 0.6836025 -0.7201341 -0.2082297 0.6119019 -0.7630311 0.1700544 0.9777828 -0.1225662 -0.138894 0.9856567 -0.09586161 -0.1319019 0.9853277 -0.1083109 -0.6061105 0.7947494 0.03167885 -0.5447358 -0.8313714 -0.1099299 -0.09970676 -0.8893651 0.4461933 0.2620093 0.9568148 0.1259232 0.2047231 -0.9737473 0.09952324 0.3584794 -0.9291594 0.09030652 -0.5531623 -0.8271952 -0.09879094 -0.1898009 -0.9728096 -0.1327294 0.1313869 0.9824877 0.1321194 -0.3468231 0.930752 -0.1158213 -0.4255548 -0.8968879 -0.1203968 -0.4970929 0.8628016 -0.09204518 -0.5755234 0.8135395 -0.08322471 0.6726449 -0.664893 0.3247557 0.6695252 -0.7390473 0.07446628 0.6712771 0.732774 0.1114878 -0.4238805 -0.8987279 -0.1123104 0.5490387 -0.8314014 0.08560603 0.8180737 0.5560948 0.1466764 0.7662156 0.6356849 0.09390765 -0.7865128 -0.6157573 -0.04733538 -0.7308145 -0.6798169 -0.06131321 -0.331592 -0.2322517 0.9143883 -0.4405983 -0.3157769 0.8403322 0.7703613 0.3285983 0.5464127 0.02777242 0.01492387 0.9995029 0.02914553 -0.07391673 0.9968385 0.2223616 -0.9506984 0.2161663 0.01614445 -0.9839282 0.1778334 0.4434077 0.8883414 0.1193285 0.4358409 0.8924651 0.1163992 -0.567081 -0.8153869 -0.116462 0.0461753 -0.6364135 -0.7699648 -0.7158653 -0.6912056 -0.09885263 -0.6768726 0.7314703 -0.08243077 0.05352979 0.09021329 -0.9944829 -0.0162971 0.008423209 -0.9998318 -0.2844985 0.2859023 0.9150522 0.1779578 0.8998912 0.3981544 -0.2976174 0.9533708 -0.05008101 0.01709061 0.9874427 -0.1570508 -0.1770699 0.9803853 -0.08655124 -0.498503 0.8632093 -0.07977753 0.6414535 0.7585863 0.1143861 0.7137822 0.6932123 0.0998587 -0.7660952 0.6420038 0.03048872 0.02038651 -0.01733464 0.9996419 0.00589019 -0.0446496 0.9989855 -0.09348064 -0.7976527 -0.5958285 -0.2675905 -0.9534742 -0.1388614 -0.8172619 -0.5591037 0.1395928 0.1369084 -0.7973402 0.5877965 0.2565704 0.5152771 0.8177171 0.1956577 0.1606523 0.9674239 -0.3249659 0.939099 -0.1117604 0.6703324 -0.7379944 0.0775808 0.6072414 -0.7901433 0.08325648 0.786656 0.609402 0.09900337 0.7943236 -0.5841072 0.16694 0.7895994 -0.6092904 0.07278889 0.518161 -0.3001293 0.8008942 -0.3665633 0.9270138 -0.0792272 0.5051496 -0.8591387 0.08188229 0.7630784 -0.640909 0.08334863 -0.8434545 -0.5306955 -0.08334743 -0.8669309 -0.4901398 -0.0905202 -0.8586925 0.5061329 0.0804795 -0.6139236 0.245954 0.7500697 0.348069 0.8728733 0.3419651 0.6281791 0.7698803 0.1125857 -0.6597396 -0.7423864 -0.1166454 -0.6180443 -0.7795824 -0.1013543 -0.7680421 -0.6332395 -0.09549403 -0.7968947 0.5987622 -0.08026629 -0.7082274 0.7014521 -0.07986861 -0.9054023 -0.3744356 0.2001119 -0.3090646 -0.09546303 0.9462378 0.9265523 0.3527369 0.1306817 0.8602256 0.5022916 0.08783543 -0.6846963 0.7254698 -0.06988877 -0.6990464 0.7114983 -0.07144582 0.6048352 -0.2130565 0.7673209 0.8987991 -0.400843 0.1774403 0.8820592 -0.4662992 0.06735533 0.8904321 0.2319164 0.3915936 -0.5301171 0.8445861 -0.07516855 0.8437299 -0.5309706 0.07867813 0.9348094 0.3445641 0.08606469 0.9782691 0.19038 0.08212769 0.224709 -0.3625924 0.9044516 0.7566614 -0.6493256 0.07641994 0.4217181 -0.8237512 0.3789298 0.8882886 -0.1227172 0.4425878 0.9561119 -0.2866383 0.06073361 0.8916997 0.4433778 0.09103769 -0.8969337 0.4359997 -0.07358217 -0.9464098 0.3130996 -0.07922857 -0.4245792 -0.02414041 0.905069 0.09674668 0.9868772 -0.1292804 -0.1141411 -0.200571 0.9730072 -0.2868505 -0.7668269 -0.5741894 -0.3111401 -0.9503582 0.003357052 -0.4698802 -0.8756692 -0.1114271 0.6618015 -0.7454843 0.07919645 -0.97534 -0.2019165 0.08911669 -0.9406708 -0.3298238 -0.0797168 -0.2343557 -0.04141432 0.9712685 -0.9872946 -0.03213661 0.1556171 -0.8215281 0.5658344 -0.07016468 0.9109759 -0.4052376 0.07684803 0.9228692 0.09698992 0.3727001 0.9966822 0.04297041 0.06912499 0.6122391 0.7823818 0.1142016 0.5471152 0.7540345 0.3634515 -0.5820056 -0.8063235 -0.1054141 -0.8234878 0.5606601 -0.08676481 0.8552033 0.5091484 0.09692829 -0.9768721 0.2070081 0.05356025 -0.9856885 -0.1497592 -0.07739746 -0.3737651 0.9180087 -0.1325131 -0.4395674 0.8962561 -0.05920714 -0.5781286 0.8121818 -0.07828217 -0.6134703 0.7885906 -0.04217779 0.5530765 -0.8270206 0.1007147 0.798569 0.5901525 0.118354 -0.8863626 -0.455282 -0.08414077 0.9566466 0.2776918 0.08783346 0.9914684 -0.1019332 0.08124136 0.9659567 -0.2452506 0.08234024 0.2486725 -0.1718856 0.9532143 0.3761844 -0.1273277 0.9177544 0.2073187 -0.002166867 0.9782711 -0.7683152 -0.6350694 -0.07986813 -0.8423514 -0.5310894 -0.09158712 -0.7669453 0.6382767 -0.06631803 -0.9942206 0.1073356 0.00213629 0.9520455 0.2927094 0.08905494 -0.9105451 0.4078302 -0.06769192 0.8651589 -0.4968835 0.06787472 0.5077466 0.4833923 0.7131097 0.8231697 -0.5629916 0.07370436 0.9933196 0.08401769 0.07910418 -0.9897143 0.1265335 -0.06674593 -0.9891502 0.002410948 -0.1468878 -0.7067247 0.7041306 -0.06885045 -0.7194657 0.6881833 0.09366422 -0.6970612 0.7123209 -0.08188331 -0.6730041 -0.7290979 -0.1244258 0.9160537 0.3904581 0.09158706 -0.9586133 0.2762002 -0.06909584 0.9469084 -0.313978 0.06915569 -0.9832595 -0.1600108 -0.08716207 -0.9467598 -0.3117514 -0.08035647 0.9905889 -0.1136531 0.07626718 0.5059178 -0.5358267 0.6759712 -0.4009366 -0.5788355 -0.71007 0.9877046 0.1316003 0.08438658 -0.9969576 -0.02139365 -0.07495415 0.734556 0.5833662 0.346571 0.8364909 0.4938254 0.2375281 0.8035543 0.5836291 0.1169517 0.7226623 -0.6874127 0.07226926 -0.7538353 -0.6495802 -0.09888362 -0.6578074 -0.7475333 -0.09210646 0.9053176 0.4167379 0.08203524 0.9082515 -0.4120398 0.07281881 -0.5722706 0.8119401 -0.1151499 -0.3466705 0.6224749 -0.7016728 -0.8638395 0.4999923 -0.06155675 -0.9210203 0.3852793 -0.05728524 -0.8045085 -0.5841621 -0.1073349 -0.9248256 -0.3709618 -0.08417212 -0.951724 0.2978315 -0.07428234 -0.9807435 0.1743883 -0.08792662 -0.9089475 0.4097787 -0.0767858 0.9643558 -0.2534341 0.07608515 0.9935398 -0.08230918 0.07812815 0.6777646 -0.7022103 0.2180272 -0.9152997 -0.3918048 -0.09335803 -0.7932883 0.6053199 -0.06543338 0.8647727 -0.4970726 0.07132428 0.9389088 -0.3349736 0.07901298 -0.9951387 -0.0629 -0.07577908 -0.9757321 -0.2010305 -0.08679682 -0.9966483 0.04196316 -0.07022345 -0.01577836 0.008789479 -0.9998369 -0.5432705 0.4356907 -0.7176566 -0.6459704 0.05847483 -0.7611196 -0.7094824 0.7022188 -0.05936002 -0.7926161 0.6053498 -0.07288002 0.9733877 0.2143381 0.08109021 0.9949787 0.05685675 0.08237063 -0.9804576 0.1760649 -0.08777302 -0.9871814 0.1471647 -0.06177127 0.5680288 0.2356104 0.7885627 -0.758109 -0.6520226 -0.01171952 -0.6121902 -0.5108656 -0.6035227 -0.6318457 -0.294727 -0.7168731 0.988203 -0.1319028 0.07782328 -0.524867 0.5718663 -0.630463 -0.8208088 -0.561733 -0.1035815 -0.9633211 -0.2544645 -0.08520805 -0.8822313 0.4605109 -0.09796804 -0.8913083 0.4492706 -0.06103801 -0.9484184 0.3123958 -0.05395811 0.6415736 -0.4029749 0.6526826 0.892951 -0.187874 0.4090746 0.6287277 -0.03289973 0.7769293 -0.9970307 -0.03180092 -0.07013303 0.8212149 -0.5000597 0.2748573 0.9668025 -0.2482697 0.06045758 -0.988323 -0.1301019 -0.07931852 -0.9670146 -0.2516649 -0.03933978 0.9972745 -0.01168882 0.07284921 -0.9923718 0.09961253 -0.07263416 -0.9562211 0.2831247 -0.07403904 0.6925526 0.1190572 0.7114748 -0.8535029 0.5196217 -0.0390647 0.9351669 0.2439088 0.2568489 0.9131653 -0.3472476 0.2134208 0.9543927 0.006805717 0.2984766 -0.9561437 0.2894464 -0.04483306 -0.9983518 -0.01062071 -0.05639988 -0.9903832 0.09793657 -0.09772288 -0.9161953 0.1921202 -0.3516761 -0.718242 0.3075128 -0.6241509 -0.7087262 -0.1889774 -0.6797021 -0.01614457 0.008331656 -0.999835 -0.7622716 -0.01315361 -0.6471236 -0.01571404 0.008748769 -0.9998384 -0.01572 0.008754134 -0.9998381 -0.01571911 0.008749723 -0.9998382 -0.01571869 0.008751094 -0.9998382 - - - - - - - - - - 0.167584 0.001978099 0.170813 0.005488336 0.122597 0.001978099 0.387122 0.645634 0.383443 0.632545 0.415832 0.649596 0.387122 0.645634 0.34213 0.645873 0.383443 0.632545 0.167584 0.001978099 0.196213 0.004784286 0.170813 0.005488336 0.122597 0.001978099 0.170813 0.005488336 0.113986 0.008504092 0.122597 0.001978099 0.113986 0.008504092 0.08069568 0.01884698 0.34213 0.645873 0.328605 0.623663 0.358262 0.621048 0.34213 0.645873 0.358262 0.621048 0.383443 0.632545 0.34213 0.645873 0.300013 0.64156 0.328605 0.623663 0.415832 0.649596 0.383443 0.632545 0.412445 0.62415 0.415832 0.649596 0.412445 0.62415 0.440557 0.636203 0.415832 0.649596 0.440557 0.636203 0.449773 0.649278 0.196213 0.004784286 0.230222 0.01596677 0.241495 0.02878135 0.163344 0.664088 0.208431 0.666263 0.180244 0.674518 0.196213 0.004784286 0.213504 0.01910185 0.170813 0.005488336 0.137777 0.669205 0.1127099 0.675849 0.08099538 0.666249 0.137777 0.669205 0.1467649 0.679272 0.1127099 0.675849 0.137777 0.669205 0.180244 0.674518 0.1467649 0.679272 0.383443 0.632545 0.358262 0.621048 0.380399 0.601017 0.383443 0.632545 0.380399 0.601017 0.412445 0.62415 0.08099538 0.666249 0.1127099 0.675849 0.0871939 0.67571 0.3335 0.646893 0.29623 0.647557 0.300013 0.64156 0.113986 0.008504092 0.0734086 0.02914637 0.07679396 0.02199417 0.08099538 0.666249 0.06335675 0.675267 0.04026657 0.666424 0.08099538 0.666249 0.0871939 0.67571 0.06335675 0.675267 0.07679396 0.02199417 0.03527379 0.06236189 0.05140006 0.04054886 0.07679396 0.02199417 0.0734086 0.02914637 0.03527379 0.06236189 0.29623 0.647557 0.270666 0.645482 0.300013 0.64156 0.412445 0.62415 0.436487 0.60161 0.440557 0.636203 0.412445 0.62415 0.380399 0.601017 0.388055 0.559238 0.412445 0.62415 0.388055 0.559238 0.425976 0.561127 0.412445 0.62415 0.425976 0.561127 0.436487 0.60161 0.300013 0.64156 0.277981 0.614182 0.298922 0.607805 0.300013 0.64156 0.298922 0.607805 0.328605 0.623663 0.300013 0.64156 0.270666 0.645482 0.277981 0.614182 0.230222 0.01596677 0.260007 0.03492617 0.241495 0.02878135 0.449773 0.649278 0.476158 0.642273 0.479476 0.650516 0.449773 0.649278 0.440557 0.636203 0.476158 0.642273 0.358262 0.621048 0.355301 0.576576 0.380399 0.601017 0.358262 0.621048 0.328605 0.623663 0.355301 0.576576 0.440557 0.636203 0.436487 0.60161 0.466123 0.59727 0.440557 0.636203 0.466123 0.59727 0.476158 0.642273 0.1127099 0.675849 0.1467649 0.679272 0.139499 0.700269 0.1127099 0.675849 0.139499 0.700269 0.112491 0.740354 0.1127099 0.675849 0.112491 0.740354 0.09719699 0.705355 0.1127099 0.675849 0.09719699 0.705355 0.0871939 0.67571 0.328605 0.623663 0.298922 0.607805 0.321105 0.559831 0.328605 0.623663 0.321105 0.559831 0.355301 0.576576 0.0871939 0.67571 0.09719699 0.705355 0.06335675 0.675267 0.0734086 0.02914637 0.0967074 0.02201199 0.06111174 0.04508578 0.04026657 0.666424 0.02759939 0.67537 0.001978099 0.664088 0.380399 0.601017 0.355301 0.576576 0.388055 0.559238 0.1467649 0.679272 0.159795 0.700098 0.139499 0.700269 0.1467649 0.679272 0.180244 0.674518 0.159795 0.700098 0.180244 0.674518 0.187786 0.750857 0.159795 0.700098 0.180244 0.674518 0.208431 0.666263 0.199348 0.674166 0.180244 0.674518 0.199348 0.674166 0.187786 0.750857 0.06335675 0.675267 0.04906409 0.698516 0.02759939 0.67537 0.06335675 0.675267 0.08408218 0.749619 0.05456787 0.771913 0.06335675 0.675267 0.05456787 0.771913 0.04906409 0.698516 0.06335675 0.675267 0.09719699 0.705355 0.08408218 0.749619 0.139499 0.700269 0.159795 0.700098 0.157595 0.749626 0.139499 0.700269 0.123738 0.757675 0.112491 0.740354 0.139499 0.700269 0.157595 0.749626 0.123738 0.757675 0.09719699 0.705355 0.112491 0.740354 0.08408218 0.749619 0.298922 0.607805 0.289222 0.565989 0.321105 0.559831 0.298922 0.607805 0.277981 0.614182 0.289222 0.565989 0.241495 0.02878135 0.260007 0.03492617 0.271347 0.05449169 0.208431 0.666263 0.226015 0.675867 0.199348 0.674166 0.208431 0.666263 0.238194 0.664299 0.226015 0.675867 0.260007 0.03492617 0.279107 0.05357235 0.271347 0.05449169 0.479476 0.650516 0.476158 0.642273 0.489198 0.637296 0.479476 0.650516 0.489198 0.637296 0.498471 0.650752 0.05140006 0.04054886 0.03527379 0.06236189 0.0282377 0.06815159 0.651014 0.001978099 0.651973 0.02943396 0.62066 0.0151962 0.270666 0.645482 0.261581 0.615301 0.277981 0.614182 0.388055 0.559238 0.409542 0.51755 0.425976 0.561127 0.388055 0.559238 0.355301 0.576576 0.366592 0.544085 0.388055 0.559238 0.392287 0.512146 0.409542 0.51755 0.388055 0.559238 0.366592 0.544085 0.392287 0.512146 0.436487 0.60161 0.425976 0.561127 0.461388 0.581888 0.436487 0.60161 0.461388 0.581888 0.466123 0.59727 0.159795 0.700098 0.187786 0.750857 0.157595 0.749626 0.321105 0.559831 0.289222 0.565989 0.320392 0.531596 0.321105 0.559831 0.345544 0.541304 0.355301 0.576576 0.321105 0.559831 0.320392 0.531596 0.345544 0.541304 0.476158 0.642273 0.466123 0.59727 0.489198 0.637296 0.02759939 0.67537 0.04906409 0.698516 0.02915817 0.701368 0.06111174 0.04508578 0.03147494 0.08005559 0.03527379 0.06236189 0.484713 0.669743 0.468098 0.695651 0.449769 0.668465 0.484713 0.669743 0.482535 0.69591 0.468098 0.695651 0.355301 0.576576 0.345544 0.541304 0.366592 0.544085 0.112491 0.740354 0.123738 0.757675 0.108254 0.803532 0.112491 0.740354 0.108254 0.803532 0.08408218 0.749619 0.03527379 0.06236189 0.03147494 0.08005559 0.009264111 0.1091549 0.03527379 0.06236189 0.009264111 0.1091549 0.0282377 0.06815159 0.425976 0.561127 0.439282 0.528487 0.461388 0.581888 0.425976 0.561127 0.409542 0.51755 0.439282 0.528487 0.466123 0.59727 0.490861 0.591939 0.489198 0.637296 0.466123 0.59727 0.461388 0.581888 0.490861 0.591939 0.04906409 0.698516 0.04030507 0.746915 0.02915817 0.701368 0.04906409 0.698516 0.05456787 0.771913 0.04030507 0.746915 0.199348 0.674166 0.216578 0.755242 0.187786 0.750857 0.199348 0.674166 0.226015 0.675867 0.216578 0.755242 0.277981 0.614182 0.261581 0.615301 0.289222 0.565989 0.345544 0.541304 0.336676 0.499375 0.364015 0.500796 0.345544 0.541304 0.364015 0.500796 0.366592 0.544085 0.345544 0.541304 0.320392 0.531596 0.336676 0.499375 0.08408218 0.749619 0.06815266 0.78772 0.05456787 0.771913 0.08408218 0.749619 0.108254 0.803532 0.09563386 0.855881 0.08408218 0.749619 0.09563386 0.855881 0.06815266 0.78772 0.187786 0.750857 0.173758 0.780804 0.157595 0.749626 0.187786 0.750857 0.216578 0.755242 0.203768 0.784147 0.187786 0.750857 0.188502 0.803106 0.173758 0.780804 0.187786 0.750857 0.203768 0.784147 0.188502 0.803106 0.482535 0.69591 0.484013 0.741117 0.468098 0.695651 0.271347 0.05449169 0.279107 0.05357235 0.289683 0.07566756 0.271347 0.05449169 0.289683 0.07566756 0.287858 0.08194977 0.509608 0.67037 0.53712 0.674654 0.502711 0.682215 0.366592 0.544085 0.364015 0.500796 0.392287 0.512146 0.461388 0.581888 0.439282 0.528487 0.453571 0.531437 0.461388 0.581888 0.453571 0.531437 0.476517 0.539288 0.461388 0.581888 0.476517 0.539288 0.490861 0.591939 0.320392 0.531596 0.289222 0.565989 0.298894 0.523708 0.320392 0.531596 0.298894 0.523708 0.311478 0.479114 0.320392 0.531596 0.311478 0.479114 0.336676 0.499375 0.62066 0.0151962 0.651973 0.02943396 0.632376 0.04264885 0.62066 0.0151962 0.632376 0.04264885 0.569104 0.03086686 0.62066 0.0151962 0.569104 0.03086686 0.571972 0.001978099 0.279107 0.05357235 0.290809 0.07094091 0.289683 0.07566756 0.724846 0.315643 0.736891 0.328494 0.705401 0.33706 0.724846 0.315643 0.705401 0.33706 0.707361 0.315455 0.409542 0.51755 0.425008 0.483742 0.439282 0.528487 0.409542 0.51755 0.392287 0.512146 0.388778 0.485073 0.409542 0.51755 0.393677 0.465807 0.425008 0.483742 0.409542 0.51755 0.388778 0.485073 0.393677 0.465807 0.123738 0.757675 0.1325049 0.826508 0.108254 0.803532 0.123738 0.757675 0.157595 0.749626 0.151767 0.792761 0.123738 0.757675 0.151767 0.792761 0.1325049 0.826508 0.157595 0.749626 0.173758 0.780804 0.151767 0.792761 0.289222 0.565989 0.279746 0.515194 0.298894 0.523708 0.289222 0.565989 0.260767 0.563716 0.279746 0.515194 0.05456787 0.771913 0.04604047 0.842252 0.03290635 0.794351 0.05456787 0.771913 0.03290635 0.794351 0.04030507 0.746915 0.05456787 0.771913 0.06815266 0.78772 0.04604047 0.842252 0.736891 0.328494 0.72909 0.374464 0.705401 0.33706 0.502711 0.682215 0.53712 0.674654 0.533157 0.710532 0.502711 0.682215 0.533157 0.710532 0.521112 0.742544 0.502711 0.682215 0.521112 0.742544 0.510202 0.761929 0.651973 0.02943396 0.641457 0.06384766 0.632376 0.04264885 0.651973 0.02943396 0.653932 0.07031428 0.641457 0.06384766 0.449769 0.668465 0.468098 0.695651 0.447254 0.692126 0.449769 0.668465 0.430337 0.671805 0.399007 0.664844 0.03147494 0.08005559 0.007678568 0.130607 0.009264111 0.1091549 0.449769 0.668465 0.447254 0.692126 0.430337 0.671805 0.392287 0.512146 0.364015 0.500796 0.388778 0.485073 0.484013 0.741117 0.470288 0.78988 0.457056 0.768514 0.04030507 0.746915 0.01705819 0.771598 0.0146113 0.699627 0.490861 0.591939 0.476517 0.539288 0.493987 0.543184 0.72909 0.374464 0.70426 0.366619 0.705401 0.33706 0.72909 0.374464 0.717627 0.424063 0.70426 0.366619 0.468098 0.695651 0.444997 0.74781 0.447254 0.692126 0.468098 0.695651 0.457056 0.768514 0.444997 0.74781 0.632376 0.04264885 0.534166 0.06307005 0.569104 0.03086686 0.632376 0.04264885 0.565341 0.069579 0.534166 0.06307005 0.632376 0.04264885 0.641457 0.06384766 0.565341 0.069579 0.707361 0.315455 0.705401 0.33706 0.692985 0.31869 0.290809 0.07094091 0.299395 0.08546715 0.306283 0.111487 0.290809 0.07094091 0.306283 0.111487 0.289683 0.07566756 0.663925 0.03855228 0.665561 0.07447135 0.656634 0.04483896 0.653932 0.07031428 0.642426 0.09160816 0.641457 0.06384766 0.653932 0.07031428 0.645919 0.118799 0.642426 0.09160816 0.653932 0.07031428 0.654489 0.09175449 0.645919 0.118799 0.364015 0.500796 0.336676 0.499375 0.347498 0.482244 0.364015 0.500796 0.393677 0.465807 0.388778 0.485073 0.364015 0.500796 0.347498 0.482244 0.393677 0.465807 0.439282 0.528487 0.425008 0.483742 0.453571 0.531437 0.108254 0.803532 0.122849 0.870261 0.09563386 0.855881 0.108254 0.803532 0.1325049 0.826508 0.122849 0.870261 0.151767 0.792761 0.1718789 0.857806 0.151174 0.870338 0.151767 0.792761 0.173758 0.780804 0.1718789 0.857806 0.151767 0.792761 0.151174 0.870338 0.1325049 0.826508 0.173758 0.780804 0.188502 0.803106 0.1718789 0.857806 0.453571 0.531437 0.450152 0.479541 0.468363 0.486889 0.453571 0.531437 0.468363 0.486889 0.476517 0.539288 0.453571 0.531437 0.425008 0.483742 0.450152 0.479541 0.06815266 0.78772 0.09563386 0.855881 0.07617866 0.850051 0.06815266 0.78772 0.07617866 0.850051 0.04604047 0.842252 0.298894 0.523708 0.281211 0.486292 0.311478 0.479114 0.298894 0.523708 0.279746 0.515194 0.281211 0.486292 0.216578 0.755242 0.217621 0.828524 0.203768 0.784147 0.510202 0.761929 0.538523 0.766303 0.525914 0.835338 0.510202 0.761929 0.521112 0.742544 0.538523 0.766303 0.569104 0.03086686 0.534166 0.06307005 0.522366 0.04234015 0.569104 0.03086686 0.522366 0.04234015 0.521014 0.0216794 0.53712 0.674654 0.556337 0.702049 0.533157 0.710532 0.53712 0.674654 0.569594 0.674152 0.556337 0.702049 0.656634 0.04483896 0.665561 0.07447135 0.657591 0.07730257 0.336676 0.499375 0.337278 0.46816 0.347498 0.482244 0.336676 0.499375 0.311478 0.479114 0.337278 0.46816 0.521014 0.0216794 0.522366 0.04234015 0.492163 0.02587866 0.705401 0.33706 0.70426 0.366619 0.682504 0.348214 0.705401 0.33706 0.682504 0.348214 0.692985 0.31869 0.447254 0.692126 0.444997 0.74781 0.430337 0.671805 0.521112 0.742544 0.533157 0.710532 0.538523 0.766303 0.641457 0.06384766 0.571347 0.09434705 0.565341 0.069579 0.641457 0.06384766 0.642426 0.09160816 0.571347 0.09434705 0.347498 0.482244 0.35577 0.431956 0.379813 0.430146 0.347498 0.482244 0.337278 0.46816 0.35577 0.431956 0.347498 0.482244 0.379813 0.430146 0.393677 0.465807 0.425008 0.483742 0.401598 0.43607 0.424719 0.409868 0.425008 0.483742 0.424719 0.409868 0.445281 0.434309 0.425008 0.483742 0.445281 0.434309 0.450152 0.479541 0.425008 0.483742 0.393677 0.465807 0.401598 0.43607 0.311478 0.479114 0.281211 0.486292 0.28909 0.469811 0.311478 0.479114 0.28909 0.469811 0.311646 0.438533 0.311478 0.479114 0.311646 0.438533 0.337278 0.46816 0.09563386 0.855881 0.122849 0.870261 0.110658 0.906226 0.09563386 0.855881 0.08955609 0.927768 0.0738331 0.90782 0.09563386 0.855881 0.0738331 0.90782 0.07617866 0.850051 0.09563386 0.855881 0.110658 0.906226 0.08955609 0.927768 0.188502 0.803106 0.196169 0.84929 0.1718789 0.857806 0.188502 0.803106 0.203768 0.784147 0.196169 0.84929 0.203768 0.784147 0.217621 0.828524 0.196169 0.84929 0.476517 0.539288 0.468363 0.486889 0.487134 0.499733 0.735166 0.427135 0.719846 0.467612 0.717627 0.424063 0.533157 0.710532 0.556337 0.702049 0.538523 0.766303 0.70426 0.366619 0.717627 0.424063 0.69004 0.417777 0.70426 0.366619 0.69004 0.417777 0.682504 0.348214 0.393677 0.465807 0.379813 0.430146 0.401598 0.43607 0.692985 0.31869 0.682504 0.348214 0.661831 0.322671 0.692985 0.31869 0.661831 0.322671 0.66668 0.315891 0.430337 0.671805 0.444997 0.74781 0.41951 0.730794 0.430337 0.671805 0.41951 0.730794 0.400855 0.673329 0.430337 0.671805 0.400855 0.673329 0.399007 0.664844 0.1325049 0.826508 0.151174 0.870338 0.122849 0.870261 0.470288 0.78988 0.475157 0.837141 0.456741 0.816084 0.470288 0.78988 0.456741 0.816084 0.457056 0.768514 0.337278 0.46816 0.311646 0.438533 0.328936 0.416023 0.337278 0.46816 0.328936 0.416023 0.35577 0.431956 0.66668 0.315891 0.661831 0.322671 0.625849 0.315464 0.665561 0.07447135 0.662421 0.10457 0.657591 0.07730257 0.306283 0.111487 0.316147 0.152157 0.307503 0.1415719 0.654489 0.09175449 0.657887 0.129064 0.645919 0.118799 0.399007 0.664844 0.377683 0.672867 0.345681 0.66482 0.007678568 0.130607 0.006712853 0.1838369 0.001978099 0.16796 0.399007 0.664844 0.400855 0.673329 0.377683 0.672867 0.122849 0.870261 0.144516 0.921086 0.110658 0.906226 0.122849 0.870261 0.151174 0.870338 0.144516 0.921086 0.457056 0.768514 0.456741 0.816084 0.434192 0.824188 0.457056 0.768514 0.434192 0.824188 0.444997 0.74781 0.379813 0.430146 0.349394 0.384495 0.371378 0.379027 0.379813 0.430146 0.371378 0.379027 0.391762 0.381622 0.379813 0.430146 0.391762 0.381622 0.401598 0.43607 0.379813 0.430146 0.35577 0.431956 0.349394 0.384495 0.35577 0.431956 0.328936 0.416023 0.349394 0.384495 0.450152 0.479541 0.445281 0.434309 0.468363 0.486889 0.151174 0.870338 0.171947 0.923328 0.144516 0.921086 0.151174 0.870338 0.1718789 0.857806 0.171947 0.923328 0.07617866 0.850051 0.0738331 0.90782 0.06010425 0.872896 0.07617866 0.850051 0.06010425 0.872896 0.04604047 0.842252 0.492163 0.02587866 0.486003 0.05604368 0.456001 0.04852426 0.492163 0.02587866 0.522366 0.04234015 0.486003 0.05604368 0.492163 0.02587866 0.456001 0.04852426 0.475863 0.0236209 0.717627 0.424063 0.719846 0.467612 0.698705 0.4604 0.717627 0.424063 0.698705 0.4604 0.69004 0.417777 0.642426 0.09160816 0.57201 0.129007 0.571347 0.09434705 0.642426 0.09160816 0.645919 0.118799 0.57201 0.129007 0.401598 0.43607 0.391762 0.381622 0.413015 0.380733 0.401598 0.43607 0.413015 0.380733 0.424719 0.409868 0.1718789 0.857806 0.196169 0.84929 0.189227 0.892983 0.1718789 0.857806 0.189227 0.892983 0.171947 0.923328 0.468363 0.486889 0.466574 0.428493 0.487134 0.499733 0.468363 0.486889 0.445281 0.434309 0.466574 0.428493 0.475157 0.837141 0.46414 0.916737 0.449912 0.906748 0.04604047 0.842252 0.06010425 0.872896 0.04591798 0.920867 0.475157 0.837141 0.449912 0.906748 0.456741 0.816084 0.661831 0.322671 0.682504 0.348214 0.65701 0.355499 0.661831 0.322671 0.630785 0.327094 0.625849 0.315464 0.661831 0.322671 0.65701 0.355499 0.630785 0.327094 0.525914 0.835338 0.538523 0.766303 0.545758 0.849883 0.217621 0.828524 0.211592 0.90722 0.196169 0.84929 0.525914 0.835338 0.545758 0.849883 0.535195 0.914293 0.538523 0.766303 0.556337 0.702049 0.561931 0.777711 0.538523 0.766303 0.561931 0.777711 0.545758 0.849883 0.534166 0.06307005 0.486003 0.05604368 0.522366 0.04234015 0.534166 0.06307005 0.523803 0.09085357 0.451987 0.08987325 0.534166 0.06307005 0.451987 0.08987325 0.486003 0.05604368 0.534166 0.06307005 0.565341 0.069579 0.523803 0.09085357 0.682504 0.348214 0.69004 0.417777 0.666111 0.419225 0.682504 0.348214 0.666111 0.419225 0.65701 0.355499 0.556337 0.702049 0.569594 0.674152 0.575499 0.729577 0.556337 0.702049 0.575499 0.729577 0.561931 0.777711 0.424719 0.409868 0.431246 0.383926 0.452575 0.386579 0.424719 0.409868 0.413015 0.380733 0.431246 0.383926 0.424719 0.409868 0.452575 0.386579 0.445281 0.434309 0.311646 0.438533 0.28909 0.469811 0.286856 0.436635 0.311646 0.438533 0.314235 0.380019 0.328936 0.416023 0.311646 0.438533 0.286856 0.436635 0.314235 0.380019 0.475863 0.0236209 0.456001 0.04852426 0.442666 0.0331276 0.400855 0.673329 0.41951 0.730794 0.391931 0.728197 0.400855 0.673329 0.391931 0.728197 0.377683 0.672867 0.445281 0.434309 0.452575 0.386579 0.466574 0.428493 0.565341 0.069579 0.571347 0.09434705 0.523803 0.09085357 0.41951 0.730794 0.399561 0.794765 0.391931 0.728197 0.41951 0.730794 0.420237 0.789696 0.399561 0.794765 0.41951 0.730794 0.444997 0.74781 0.420237 0.789696 0.569594 0.674152 0.596926 0.669703 0.589889 0.697459 0.569594 0.674152 0.589889 0.697459 0.575499 0.729577 0.328936 0.416023 0.314235 0.380019 0.349394 0.384495 0.196169 0.84929 0.211592 0.90722 0.189227 0.892983 0.719846 0.467612 0.702721 0.49242 0.698705 0.4604 0.719846 0.467612 0.730783 0.538716 0.718587 0.522206 0.719846 0.467612 0.718587 0.522206 0.702721 0.49242 0.444997 0.74781 0.434192 0.824188 0.420237 0.789696 0.456741 0.816084 0.440509 0.878039 0.434192 0.824188 0.456741 0.816084 0.449912 0.906748 0.440509 0.878039 0.69004 0.417777 0.698705 0.4604 0.679013 0.464476 0.69004 0.417777 0.679013 0.464476 0.666111 0.419225 0.65701 0.355499 0.631035 0.356946 0.630785 0.327094 0.65701 0.355499 0.666111 0.419225 0.631035 0.356946 0.571347 0.09434705 0.529956 0.11428 0.523803 0.09085357 0.571347 0.09434705 0.57201 0.129007 0.529956 0.11428 0.391762 0.381622 0.371378 0.379027 0.380342 0.356171 0.391762 0.381622 0.380342 0.356171 0.396035 0.331639 0.391762 0.381622 0.396035 0.331639 0.413015 0.380733 0.06010425 0.872896 0.06558108 0.97158 0.04591798 0.920867 0.06010425 0.872896 0.0738331 0.90782 0.06558108 0.97158 0.657887 0.129064 0.647348 0.147536 0.645919 0.118799 0.657887 0.129064 0.660702 0.190954 0.647348 0.147536 0.001978099 0.16796 0.006712853 0.1838369 0.01356285 0.229785 0.371378 0.379027 0.352563 0.358071 0.380342 0.356171 0.371378 0.379027 0.349394 0.384495 0.352563 0.358071 0.349394 0.384495 0.331811 0.348011 0.352563 0.358071 0.349394 0.384495 0.314235 0.380019 0.331811 0.348011 0.413015 0.380733 0.433739 0.367645 0.431246 0.383926 0.413015 0.380733 0.396035 0.331639 0.41609 0.315745 0.413015 0.380733 0.41609 0.315745 0.433739 0.367645 0.110658 0.906226 0.144516 0.921086 0.130607 0.941794 0.110658 0.906226 0.130607 0.941794 0.106602 0.958171 0.110658 0.906226 0.106602 0.958171 0.08955609 0.927768 0.0738331 0.90782 0.08955609 0.927768 0.08167737 0.967924 0.0738331 0.90782 0.08167737 0.967924 0.06558108 0.97158 0.466574 0.428493 0.452575 0.386579 0.476095 0.397876 0.730783 0.538716 0.71845 0.57005 0.718587 0.522206 0.698705 0.4604 0.702721 0.49242 0.679013 0.464476 0.575499 0.729577 0.585061 0.791564 0.561931 0.777711 0.575499 0.729577 0.589889 0.697459 0.608743 0.758534 0.575499 0.729577 0.608743 0.758534 0.585061 0.791564 0.377683 0.672867 0.362546 0.73268 0.353324 0.674803 0.377683 0.672867 0.391931 0.728197 0.362546 0.73268 0.377683 0.672867 0.353324 0.674803 0.345681 0.66482 0.442666 0.0331276 0.400796 0.06100189 0.36865 0.04714107 0.442666 0.0331276 0.456001 0.04852426 0.400796 0.06100189 0.286856 0.436635 0.290742 0.362479 0.314235 0.380019 0.456001 0.04852426 0.486003 0.05604368 0.44812 0.07273757 0.456001 0.04852426 0.41017 0.07963246 0.400796 0.06100189 0.456001 0.04852426 0.44812 0.07273757 0.41017 0.07963246 0.702721 0.49242 0.718587 0.522206 0.692763 0.530474 0.702721 0.49242 0.668767 0.516501 0.679013 0.464476 0.702721 0.49242 0.692763 0.530474 0.668767 0.516501 0.434192 0.824188 0.440509 0.878039 0.412885 0.893075 0.434192 0.824188 0.410148 0.836747 0.420237 0.789696 0.434192 0.824188 0.412885 0.893075 0.410148 0.836747 0.596926 0.669703 0.615388 0.696457 0.589889 0.697459 0.596926 0.669703 0.632503 0.670594 0.615388 0.696457 0.307503 0.1415719 0.316147 0.152157 0.306909 0.177162 0.630785 0.327094 0.597911 0.315455 0.625849 0.315464 0.630785 0.327094 0.631035 0.356946 0.600068 0.359185 0.630785 0.327094 0.600068 0.359185 0.597911 0.315455 0.316147 0.152157 0.316705 0.180043 0.29991 0.216031 0.66895 0.115194 0.669715 0.178964 0.662028 0.140156 0.645919 0.118799 0.617321 0.14528 0.57201 0.129007 0.645919 0.118799 0.647348 0.147536 0.617321 0.14528 0.144516 0.921086 0.171947 0.923328 0.1646119 0.936538 0.144516 0.921086 0.1646119 0.936538 0.130607 0.941794 0.718587 0.522206 0.71845 0.57005 0.692763 0.530474 0.486003 0.05604368 0.451987 0.08987325 0.44812 0.07273757 0.545758 0.849883 0.561931 0.777711 0.563004 0.854015 0.545758 0.849883 0.563004 0.854015 0.562693 0.913004 0.545758 0.849883 0.562693 0.913004 0.535195 0.914293 0.561931 0.777711 0.579658 0.865654 0.563004 0.854015 0.561931 0.777711 0.585061 0.791564 0.579658 0.865654 0.666111 0.419225 0.679013 0.464476 0.656998 0.473563 0.666111 0.419225 0.656998 0.473563 0.642413 0.420134 0.666111 0.419225 0.642413 0.420134 0.631035 0.356946 0.420237 0.789696 0.410148 0.836747 0.399561 0.794765 0.391931 0.728197 0.399561 0.794765 0.382045 0.774917 0.391931 0.728197 0.382045 0.774917 0.362546 0.73268 0.314235 0.380019 0.309956 0.341166 0.331811 0.348011 0.314235 0.380019 0.290742 0.362479 0.309956 0.341166 0.08955609 0.927768 0.106602 0.958171 0.08167737 0.967924 0.399561 0.794765 0.410148 0.836747 0.387239 0.835609 0.399561 0.794765 0.387239 0.835609 0.368238 0.798389 0.399561 0.794765 0.368238 0.798389 0.382045 0.774917 0.589889 0.697459 0.615388 0.696457 0.608743 0.758534 0.345681 0.66482 0.353324 0.674803 0.323909 0.67206 0.006712853 0.1838369 0.0237689 0.240414 0.01356285 0.229785 0.345681 0.66482 0.323909 0.67206 0.288893 0.66482 0.171947 0.923328 0.189227 0.892983 0.195475 0.935138 0.171947 0.923328 0.195475 0.935138 0.190409 0.967819 0.171947 0.923328 0.190409 0.967819 0.1646119 0.936538 0.380342 0.356171 0.352563 0.358071 0.366845 0.324766 0.380342 0.356171 0.375422 0.315455 0.396035 0.331639 0.380342 0.356171 0.366845 0.324766 0.375422 0.315455 0.352563 0.358071 0.329959 0.315488 0.344548 0.316563 0.352563 0.358071 0.344548 0.316563 0.366845 0.324766 0.352563 0.358071 0.331811 0.348011 0.329959 0.315488 0.431246 0.383926 0.433739 0.367645 0.452575 0.386579 0.130607 0.941794 0.1646119 0.936538 0.141616 0.982649 0.130607 0.941794 0.1127279 0.978918 0.106602 0.958171 0.130607 0.941794 0.141616 0.982649 0.1127279 0.978918 0.452575 0.386579 0.464128 0.329012 0.476095 0.397876 0.452575 0.386579 0.443423 0.331631 0.464128 0.329012 0.452575 0.386579 0.433739 0.367645 0.443423 0.331631 0.449912 0.906748 0.424905 0.950643 0.440509 0.878039 0.449912 0.906748 0.450006 0.949413 0.424905 0.950643 0.449912 0.906748 0.46414 0.916737 0.450006 0.949413 0.523803 0.09085357 0.480904 0.106818 0.451987 0.08987325 0.523803 0.09085357 0.529956 0.11428 0.480904 0.106818 0.331811 0.348011 0.309956 0.341166 0.329959 0.315488 0.106602 0.958171 0.1127279 0.978918 0.08167737 0.967924 0.06558108 0.97158 0.08432877 0.985219 0.0523923 0.983347 0.06558108 0.97158 0.08167737 0.967924 0.08432877 0.985219 0.06558108 0.97158 0.0523923 0.983347 0.04591798 0.920867 0.46414 0.916737 0.459402 0.979507 0.450006 0.949413 0.433739 0.367645 0.41609 0.315745 0.443423 0.331631 0.44812 0.07273757 0.451987 0.08987325 0.41017 0.07963246 0.631035 0.356946 0.61452 0.414864 0.600068 0.359185 0.631035 0.356946 0.642413 0.420134 0.61452 0.414864 0.353324 0.674803 0.336498 0.704808 0.323909 0.67206 0.353324 0.674803 0.362546 0.73268 0.336498 0.704808 0.396035 0.331639 0.39506 0.315629 0.401475 0.315661 0.396035 0.331639 0.401475 0.315661 0.41609 0.315745 0.396035 0.331639 0.375422 0.315455 0.39506 0.315629 0.290742 0.362479 0.304058 0.315455 0.309956 0.341166 0.36865 0.04714107 0.321796 0.05833345 0.321939 0.04384905 0.36865 0.04714107 0.321832 0.07607889 0.321796 0.05833345 0.36865 0.04714107 0.400796 0.06100189 0.3557 0.07097887 0.36865 0.04714107 0.3557 0.07097887 0.321832 0.07607889 0.211592 0.90722 0.195475 0.935138 0.189227 0.892983 0.211592 0.90722 0.210631 0.947998 0.195475 0.935138 0.535195 0.914293 0.562693 0.913004 0.541885 0.955163 0.440509 0.878039 0.424905 0.950643 0.412885 0.893075 0.679013 0.464476 0.668767 0.516501 0.656998 0.473563 0.57201 0.129007 0.516989 0.132288 0.529956 0.11428 0.57201 0.129007 0.567964 0.1582469 0.516989 0.132288 0.57201 0.129007 0.617321 0.14528 0.567964 0.1582469 0.362546 0.73268 0.382045 0.774917 0.368238 0.798389 0.362546 0.73268 0.368238 0.798389 0.351444 0.798308 0.362546 0.73268 0.351444 0.798308 0.329437 0.783784 0.362546 0.73268 0.329437 0.783784 0.336498 0.704808 0.366845 0.324766 0.344548 0.316563 0.355564 0.315497 0.366845 0.324766 0.355564 0.315497 0.375422 0.315455 0.41609 0.315745 0.431417 0.315928 0.443423 0.331631 0.911023 0.08555769 0.911367 0.100163 0.90318 0.07036185 0.1646119 0.936538 0.1789399 0.975173 0.141616 0.982649 0.1646119 0.936538 0.190409 0.967819 0.1789399 0.975173 0.597911 0.315455 0.600068 0.359185 0.585195 0.327983 0.316705 0.180043 0.300761 0.223589 0.29991 0.216031 0.597911 0.315455 0.585195 0.327983 0.554527 0.317391 0.451987 0.08987325 0.480904 0.106818 0.443006 0.120522 0.451987 0.08987325 0.443006 0.120522 0.413075 0.104134 0.451987 0.08987325 0.413075 0.104134 0.41017 0.07963246 0.585061 0.791564 0.611562 0.818616 0.599836 0.87024 0.585061 0.791564 0.599836 0.87024 0.579658 0.865654 0.585061 0.791564 0.608743 0.758534 0.611562 0.818616 0.410148 0.836747 0.412885 0.893075 0.387239 0.835609 0.608743 0.758534 0.615388 0.696457 0.634926 0.75287 0.608743 0.758534 0.634926 0.75287 0.611562 0.818616 0.615388 0.696457 0.644693 0.692712 0.634926 0.75287 0.615388 0.696457 0.632503 0.670594 0.644693 0.692712 0.632503 0.670594 0.662432 0.670933 0.644693 0.692712 0.662028 0.140156 0.669715 0.178964 0.662107 0.170087 0.647348 0.147536 0.660702 0.190954 0.630255 0.169989 0.647348 0.147536 0.630255 0.169989 0.617321 0.14528 0.910088 0.157123 0.905036 0.171766 0.910336 0.14608 0.1127279 0.978918 0.09881228 0.992524 0.08432877 0.985219 0.1127279 0.978918 0.120461 0.992282 0.09881228 0.992524 0.1127279 0.978918 0.08432877 0.985219 0.08167737 0.967924 0.1127279 0.978918 0.141616 0.982649 0.120461 0.992282 0.195475 0.935138 0.210631 0.947998 0.190409 0.967819 0.400796 0.06100189 0.41017 0.07963246 0.3557 0.07097887 0.692763 0.530474 0.71845 0.57005 0.699527 0.585179 0.692763 0.530474 0.699527 0.585179 0.679137 0.569453 0.692763 0.530474 0.679137 0.569453 0.668767 0.516501 0.642413 0.420134 0.656998 0.473563 0.628691 0.458467 0.642413 0.420134 0.628691 0.458467 0.61452 0.414864 0.617321 0.14528 0.630255 0.169989 0.567964 0.1582469 0.916391 0.126128 0.911367 0.100163 0.915642 0.106508 0.916391 0.126128 0.828282 0.160665 0.821914 0.119079 0.916391 0.126128 0.821914 0.119079 0.911367 0.100163 0.916391 0.126128 0.894584 0.183579 0.828282 0.160665 0.916391 0.126128 0.910336 0.14608 0.894584 0.183579 0.329959 0.315488 0.309956 0.341166 0.31831 0.31546 0.905036 0.171766 0.894584 0.183579 0.910336 0.14608 0.141616 0.982649 0.1789399 0.975173 0.16686 0.991715 0.184316 0.06162035 0.209905 0.07541525 0.163495 0.06782978 0.309956 0.341166 0.304058 0.315455 0.31831 0.31546 0.71845 0.57005 0.721546 0.639126 0.709927 0.618624 0.71845 0.57005 0.709927 0.618624 0.699527 0.585179 0.563004 0.854015 0.579658 0.865654 0.562693 0.913004 0.529956 0.11428 0.516989 0.132288 0.480904 0.106818 0.0181598 0.206025 0.03087484 0.233161 0.0237689 0.240414 0.323909 0.67206 0.336498 0.704808 0.315547 0.705286 0.323909 0.67206 0.315547 0.705286 0.296712 0.673016 0.911367 0.100163 0.821914 0.119079 0.90318 0.07036185 0.443423 0.331631 0.431417 0.315928 0.448219 0.316122 0.443423 0.331631 0.448219 0.316122 0.464128 0.329012 0.41017 0.07963246 0.360899 0.0933907 0.3557 0.07097887 0.41017 0.07963246 0.413075 0.104134 0.360899 0.0933907 0.668767 0.516501 0.649372 0.516966 0.656998 0.473563 0.668767 0.516501 0.679137 0.569453 0.656922 0.566321 0.668767 0.516501 0.656922 0.566321 0.649372 0.516966 0.656998 0.473563 0.649372 0.516966 0.628691 0.458467 0.480904 0.106818 0.516989 0.132288 0.443006 0.120522 0.1789399 0.975173 0.196517 0.987648 0.16686 0.991715 0.1789399 0.975173 0.190409 0.967819 0.211099 0.97564 0.1789399 0.975173 0.211099 0.97564 0.196517 0.987648 0.163495 0.06782978 0.169125 0.07857257 0.141896 0.07319128 0.163495 0.06782978 0.209905 0.07541525 0.169125 0.07857257 0.894584 0.183579 0.87317 0.2114959 0.828282 0.160665 0.894584 0.183579 0.887429 0.197943 0.87317 0.2114959 0.190409 0.967819 0.210631 0.947998 0.211099 0.97564 0.562693 0.913004 0.591828 0.913903 0.585644 0.984797 0.562693 0.913004 0.56433 0.978768 0.541885 0.955163 0.562693 0.913004 0.585644 0.984797 0.56433 0.978768 0.562693 0.913004 0.579658 0.865654 0.591828 0.913903 0.412885 0.893075 0.377618 0.922241 0.372862 0.905297 0.412885 0.893075 0.424905 0.950643 0.410925 0.944887 0.412885 0.893075 0.410925 0.944887 0.377618 0.922241 0.412885 0.893075 0.372862 0.905297 0.387239 0.835609 0.579658 0.865654 0.599836 0.87024 0.591828 0.913903 0.516989 0.132288 0.567964 0.1582469 0.499667 0.1488969 0.516989 0.132288 0.449212 0.151762 0.443006 0.120522 0.516989 0.132288 0.499667 0.1488969 0.449212 0.151762 0.600068 0.359185 0.61452 0.414864 0.594342 0.42052 0.600068 0.359185 0.594342 0.42052 0.573705 0.364927 0.600068 0.359185 0.573705 0.364927 0.585195 0.327983 0.644693 0.692712 0.662432 0.670933 0.666152 0.698974 0.644693 0.692712 0.666152 0.698974 0.652969 0.75971 0.644693 0.692712 0.652969 0.75971 0.634926 0.75287 0.336498 0.704808 0.317343 0.738016 0.315547 0.705286 0.336498 0.704808 0.329437 0.783784 0.317343 0.738016 0.127195 0.07216089 0.114686 0.09006828 0.0953443 0.09267836 0.127195 0.07216089 0.141896 0.07319128 0.114686 0.09006828 0.90318 0.07036185 0.821914 0.119079 0.807973 0.06941205 0.90318 0.07036185 0.807973 0.06941205 0.877311 0.03174108 0.90318 0.07036185 0.877311 0.03174108 0.895171 0.05369436 0.141896 0.07319128 0.169125 0.07857257 0.114686 0.09006828 0.699527 0.585179 0.672334 0.619717 0.679137 0.569453 0.699527 0.585179 0.709927 0.618624 0.688279 0.652984 0.699527 0.585179 0.688279 0.652984 0.672334 0.619717 0.541885 0.955163 0.56433 0.978768 0.548315 0.982857 0.368238 0.798389 0.387239 0.835609 0.36718 0.866292 0.368238 0.798389 0.36718 0.866292 0.351444 0.798308 0.634926 0.75287 0.645666 0.821767 0.611562 0.818616 0.634926 0.75287 0.652969 0.75971 0.645666 0.821767 0.585195 0.327983 0.550524 0.325339 0.554527 0.317391 0.585195 0.327983 0.573705 0.364927 0.550524 0.325339 0.669715 0.178964 0.670617 0.221774 0.663185 0.201817 0.669715 0.178964 0.663185 0.201817 0.662107 0.170087 0.29991 0.216031 0.300761 0.223589 0.271718 0.259019 0.630255 0.169989 0.643033 0.200456 0.61424 0.199669 0.630255 0.169989 0.660702 0.190954 0.643033 0.200456 0.630255 0.169989 0.61424 0.199669 0.581252 0.17956 0.630255 0.169989 0.581252 0.17956 0.567964 0.1582469 0.660702 0.190954 0.661438 0.206187 0.643033 0.200456 0.01356285 0.229785 0.0237689 0.240414 0.01795387 0.244992 0.448219 0.316122 0.46703 0.316806 0.464128 0.329012 0.895171 0.05369436 0.877311 0.03174108 0.884481 0.03507184 0.721546 0.639126 0.72142 0.651301 0.714336 0.652012 0.464128 0.329012 0.470468 0.316515 0.477941 0.349967 0.709927 0.618624 0.714336 0.652012 0.688279 0.652984 0.3557 0.07097887 0.332501 0.08159059 0.321832 0.07607889 0.3557 0.07097887 0.360899 0.0933907 0.332501 0.08159059 0.387239 0.835609 0.372862 0.905297 0.36718 0.866292 0.61452 0.414864 0.628691 0.458467 0.594342 0.42052 0.209905 0.07541525 0.239518 0.0897296 0.220139 0.08671289 0.209905 0.07541525 0.220139 0.08671289 0.169125 0.07857257 0.0953443 0.09267836 0.114686 0.09006828 0.08398777 0.112705 0.459402 0.979507 0.440772 0.971138 0.450006 0.949413 0.459402 0.979507 0.439933 0.986705 0.440772 0.971138 0.424905 0.950643 0.450006 0.949413 0.43795 0.952699 0.06536537 0.125196 0.07511168 0.112265 0.07608926 0.112796 0.424905 0.950643 0.437487 0.953721 0.440772 0.971138 0.424905 0.950643 0.440772 0.971138 0.4141 0.983149 0.424905 0.950643 0.4141 0.983149 0.410925 0.944887 0.567964 0.1582469 0.491088 0.164562 0.499667 0.1488969 0.567964 0.1582469 0.536492 0.181671 0.491088 0.164562 0.567964 0.1582469 0.581252 0.17956 0.536492 0.181671 0.662432 0.670933 0.694174 0.670299 0.687785 0.705656 0.662432 0.670933 0.687785 0.705656 0.666152 0.698974 0.315547 0.705286 0.28825 0.700855 0.296712 0.673016 0.315547 0.705286 0.317343 0.738016 0.28825 0.700855 0.450006 0.949413 0.440772 0.971138 0.43795 0.952699 0.169125 0.07857257 0.220139 0.08671289 0.202705 0.1082 0.169125 0.07857257 0.202705 0.1082 0.148147 0.104125 0.169125 0.07857257 0.148147 0.104125 0.114686 0.09006828 0.114686 0.09006828 0.07950848 0.135752 0.08398777 0.112705 0.114686 0.09006828 0.148147 0.104125 0.07950848 0.135752 0.679137 0.569453 0.672334 0.619717 0.656922 0.566321 0.628691 0.458467 0.626179 0.513824 0.605628 0.475091 0.628691 0.458467 0.649372 0.516966 0.626179 0.513824 0.628691 0.458467 0.605628 0.475091 0.594342 0.42052 0.300761 0.223589 0.272739 0.26585 0.271718 0.259019 0.554527 0.317391 0.550524 0.325339 0.512752 0.322808 0.0237689 0.240414 0.0362336 0.261236 0.01795387 0.244992 0.0237689 0.240414 0.0566495 0.268579 0.0362336 0.261236 0.0237689 0.240414 0.03087484 0.233161 0.0566495 0.268579 0.220139 0.08671289 0.25546 0.121078 0.202705 0.1082 0.220139 0.08671289 0.239518 0.0897296 0.25546 0.121078 0.239518 0.0897296 0.25967 0.112126 0.25546 0.121078 0.540822 0.995206 0.548315 0.982857 0.563364 0.993572 0.87317 0.2114959 0.855636 0.224104 0.844362 0.222375 0.87317 0.2114959 0.844362 0.222375 0.828282 0.160665 0.360899 0.0933907 0.413075 0.104134 0.382971 0.121936 0.360899 0.0933907 0.321999 0.09697848 0.332501 0.08159059 0.360899 0.0933907 0.339072 0.128435 0.321999 0.09697848 0.360899 0.0933907 0.382971 0.121936 0.339072 0.128435 0.649372 0.516966 0.656922 0.566321 0.631617 0.58325 0.649372 0.516966 0.631617 0.58325 0.626179 0.513824 0.611562 0.818616 0.645666 0.821767 0.626644 0.87421 0.611562 0.818616 0.626644 0.87421 0.599836 0.87024 0.351444 0.798308 0.36718 0.866292 0.345838 0.872258 0.351444 0.798308 0.345838 0.872258 0.329437 0.783784 0.329437 0.783784 0.345838 0.872258 0.319247 0.834786 0.329437 0.783784 0.302314 0.791752 0.317343 0.738016 0.329437 0.783784 0.319247 0.834786 0.302314 0.791752 0.296712 0.673016 0.28825 0.700855 0.27399 0.675474 0.296712 0.673016 0.27399 0.675474 0.260767 0.668914 0.548315 0.982857 0.56433 0.978768 0.563364 0.993572 0.440772 0.971138 0.439933 0.986705 0.4141 0.983149 0.289182 0.33973 0.288241 0.357366 0.28729 0.358374 0.56433 0.978768 0.585644 0.984797 0.563364 0.993572 0.443006 0.120522 0.449212 0.151762 0.409847 0.130582 0.443006 0.120522 0.409847 0.130582 0.413075 0.104134 0.877311 0.03174108 0.807973 0.06941205 0.850955 0.01336938 0.148147 0.104125 0.202705 0.1082 0.155387 0.165864 0.148147 0.104125 0.110055 0.138151 0.07950848 0.135752 0.148147 0.104125 0.155387 0.165864 0.110055 0.138151 0.413075 0.104134 0.409847 0.130582 0.382971 0.121936 0.499667 0.1488969 0.491088 0.164562 0.449212 0.151762 0.594342 0.42052 0.570183 0.418058 0.573705 0.364927 0.594342 0.42052 0.605628 0.475091 0.579086 0.479354 0.594342 0.42052 0.579086 0.479354 0.570183 0.418058 0.317343 0.738016 0.302314 0.791752 0.28825 0.700855 0.643033 0.200456 0.661438 0.206187 0.644722 0.2246429 0.643033 0.200456 0.612748 0.2167659 0.61424 0.199669 0.643033 0.200456 0.644722 0.2246429 0.612748 0.2167659 0.202705 0.1082 0.25546 0.121078 0.240307 0.143562 0.202705 0.1082 0.2010239 0.165771 0.155387 0.165864 0.202705 0.1082 0.240307 0.143562 0.2010239 0.165771 0.08398777 0.112705 0.07950848 0.135752 0.06775808 0.138332 0.321832 0.07607889 0.332501 0.08159059 0.321956 0.08733189 0.410925 0.944887 0.388819 0.972068 0.377618 0.922241 0.410925 0.944887 0.4141 0.983149 0.388819 0.972068 0.599836 0.87024 0.626644 0.87421 0.606633 0.955382 0.599836 0.87024 0.606633 0.955382 0.591828 0.913903 0.36718 0.866292 0.372862 0.905297 0.345838 0.872258 0.652969 0.75971 0.666152 0.698974 0.671163 0.753909 0.652969 0.75971 0.671163 0.753909 0.672469 0.819747 0.652969 0.75971 0.672469 0.819747 0.645666 0.821767 0.573705 0.364927 0.54393 0.372066 0.550524 0.325339 0.573705 0.364927 0.570183 0.418058 0.54393 0.372066 0.666152 0.698974 0.687785 0.705656 0.671163 0.753909 0.25546 0.121078 0.270408 0.1431739 0.269801 0.1841329 0.25546 0.121078 0.25967 0.112126 0.270408 0.1431739 0.25546 0.121078 0.269801 0.1841329 0.240307 0.143562 0.07950848 0.135752 0.110055 0.138151 0.07603275 0.172322 0.07950848 0.135752 0.07603275 0.172322 0.06631207 0.172393 0.07950848 0.135752 0.06631207 0.172393 0.06775808 0.138332 0.688279 0.652984 0.656372 0.65443 0.656725 0.642205 0.850955 0.01336938 0.777271 0.001978099 0.818839 0.001978099 0.688279 0.652984 0.656725 0.642205 0.672334 0.619717 0.850955 0.01336938 0.750683 0.01154315 0.777271 0.001978099 0.850955 0.01336938 0.807973 0.06941205 0.750683 0.01154315 0.656922 0.566321 0.672334 0.619717 0.651828 0.624021 0.656922 0.566321 0.651828 0.624021 0.631617 0.58325 0.591828 0.913903 0.606633 0.955382 0.585644 0.984797 0.626179 0.513824 0.608999 0.526822 0.605628 0.475091 0.626179 0.513824 0.631617 0.58325 0.611187 0.565957 0.626179 0.513824 0.611187 0.565957 0.608999 0.526822 0.550524 0.325339 0.527509 0.336671 0.512752 0.322808 0.550524 0.325339 0.54393 0.372066 0.527509 0.336671 0.61424 0.199669 0.612748 0.2167659 0.581692 0.2049109 0.61424 0.199669 0.581692 0.2049109 0.581252 0.17956 0.563364 0.993572 0.585644 0.984797 0.594468 0.994642 0.850175 0.228549 0.834882 0.232452 0.844362 0.222375 0.585644 0.984797 0.606286 0.986605 0.594468 0.994642 0.585644 0.984797 0.606633 0.955382 0.606286 0.986605 0.372862 0.905297 0.377618 0.922241 0.347043 0.934073 0.372862 0.905297 0.347043 0.934073 0.345838 0.872258 0.645666 0.821767 0.646157 0.883777 0.626644 0.87421 0.645666 0.821767 0.66006 0.899446 0.646157 0.883777 0.645666 0.821767 0.672469 0.819747 0.66006 0.899446 0.581252 0.17956 0.555608 0.207347 0.536492 0.181671 0.581252 0.17956 0.581692 0.2049109 0.555608 0.207347 0.001996994 0.317462 0.02023088 0.316661 0.02518945 0.3353 0.672334 0.619717 0.656725 0.642205 0.651828 0.624021 0.382971 0.121936 0.409847 0.130582 0.387612 0.157095 0.382971 0.121936 0.387612 0.157095 0.339072 0.128435 0.377618 0.922241 0.369494 0.955216 0.347043 0.934073 0.377618 0.922241 0.388819 0.972068 0.369494 0.955216 0.409847 0.130582 0.449212 0.151762 0.387612 0.157095 0.605628 0.475091 0.608999 0.526822 0.582048 0.506446 0.605628 0.475091 0.582048 0.506446 0.579086 0.479354 0.491088 0.164562 0.536492 0.181671 0.459635 0.187584 0.491088 0.164562 0.459635 0.187584 0.449212 0.151762 0.570183 0.418058 0.579086 0.479354 0.563776 0.476098 0.570183 0.418058 0.563776 0.476098 0.541838 0.42463 0.570183 0.418058 0.541838 0.42463 0.54393 0.372066 0.694174 0.670299 0.717361 0.669703 0.708795 0.706857 0.694174 0.670299 0.708795 0.706857 0.687785 0.705656 0.2823 0.2389799 0.271718 0.259019 0.262979 0.262279 0.28825 0.700855 0.302314 0.791752 0.283955 0.76523 0.28825 0.700855 0.283955 0.76523 0.27399 0.675474 0.4141 0.983149 0.380401 0.988869 0.388819 0.972068 0.449212 0.151762 0.459635 0.187584 0.427456 0.1887699 0.449212 0.151762 0.427456 0.1887699 0.387612 0.157095 0.687785 0.705656 0.685987 0.757301 0.671163 0.753909 0.687785 0.705656 0.708795 0.706857 0.685987 0.757301 0.740992 0.635695 0.767297 0.632977 0.749561 0.642813 0.740992 0.635695 0.748501 0.545012 0.760673 0.587021 0.740992 0.635695 0.760673 0.587021 0.767297 0.632977 0.644722 0.2246429 0.66311 0.222541 0.636172 0.245774 0.02518945 0.3353 0.04754698 0.34493 0.03499859 0.355105 0.644722 0.2246429 0.62541 0.234977 0.612748 0.2167659 0.0566495 0.268579 0.07917177 0.291126 0.05280345 0.271909 0.0566495 0.268579 0.05280345 0.271909 0.0362336 0.261236 0.749561 0.642813 0.767297 0.632977 0.788468 0.643598 0.0566495 0.268579 0.09563857 0.294021 0.07917177 0.291126 0.240307 0.143562 0.269801 0.1841329 0.2335129 0.205923 0.240307 0.143562 0.2335129 0.205923 0.2010239 0.165771 0.110055 0.138151 0.1012549 0.1920869 0.07603275 0.172322 0.110055 0.138151 0.155387 0.165864 0.1012549 0.1920869 0.626644 0.87421 0.646375 0.977458 0.623278 0.972919 0.626644 0.87421 0.646157 0.883777 0.646375 0.977458 0.626644 0.87421 0.623278 0.972919 0.606633 0.955382 0.345838 0.872258 0.324939 0.876156 0.319247 0.834786 0.345838 0.872258 0.347043 0.934073 0.329476 0.928108 0.345838 0.872258 0.329476 0.928108 0.324939 0.876156 0.536492 0.181671 0.555608 0.207347 0.528662 0.209367 0.536492 0.181671 0.528662 0.209367 0.459635 0.187584 0.671163 0.753909 0.685987 0.757301 0.672469 0.819747 0.02023088 0.316661 0.03667086 0.318417 0.04754698 0.34493 0.321999 0.09697848 0.339072 0.128435 0.322128 0.12357 0.834882 0.232452 0.808382 0.237151 0.844362 0.222375 0.581692 0.2049109 0.612748 0.2167659 0.57213 0.233653 0.581692 0.2049109 0.57213 0.233653 0.555608 0.207347 0.54393 0.372066 0.519923 0.370766 0.527509 0.336671 0.54393 0.372066 0.541838 0.42463 0.519923 0.370766 0.844362 0.222375 0.775812 0.235244 0.761827 0.1879889 0.844362 0.222375 0.808382 0.237151 0.775812 0.235244 0.844362 0.222375 0.761827 0.1879889 0.828282 0.160665 0.271718 0.259019 0.272739 0.26585 0.249884 0.282916 0.271718 0.259019 0.249884 0.282916 0.262979 0.262279 0.606633 0.955382 0.623278 0.972919 0.606286 0.986605 0.388819 0.972068 0.362475 0.982197 0.369494 0.955216 0.388819 0.972068 0.380401 0.988869 0.362475 0.982197 0.631617 0.58325 0.590841 0.595692 0.611187 0.565957 0.631617 0.58325 0.630867 0.647104 0.6038 0.613104 0.631617 0.58325 0.651828 0.624021 0.630867 0.647104 0.631617 0.58325 0.6038 0.613104 0.590841 0.595692 0.579086 0.479354 0.582048 0.506446 0.565233 0.497271 0.579086 0.479354 0.565233 0.497271 0.563776 0.476098 0.302314 0.791752 0.29901 0.886997 0.289159 0.853453 0.302314 0.791752 0.319247 0.834786 0.29901 0.886997 0.302314 0.791752 0.289159 0.853453 0.283955 0.76523 0.527509 0.336671 0.519923 0.370766 0.502711 0.338035 0.527509 0.336671 0.502711 0.338035 0.512752 0.322808 0.256763 0.320786 0.246193 0.334799 0.23395 0.317033 0.155387 0.165864 0.2010239 0.165771 0.181275 0.219622 0.155387 0.165864 0.181275 0.219622 0.137702 0.2308149 0.155387 0.165864 0.137702 0.2308149 0.1012549 0.1920869 0.651828 0.624021 0.656725 0.642205 0.630867 0.647104 0.339072 0.128435 0.323404 0.149545 0.322128 0.12357 0.339072 0.128435 0.369878 0.1664389 0.323404 0.149545 0.339072 0.128435 0.387612 0.157095 0.369878 0.1664389 0.555608 0.207347 0.57213 0.233653 0.528662 0.209367 0.612748 0.2167659 0.62541 0.234977 0.57213 0.233653 0.03667086 0.318417 0.06304121 0.316352 0.05824565 0.327257 0.03667086 0.318417 0.05824565 0.327257 0.04754698 0.34493 0.270408 0.1431739 0.279175 0.154842 0.27709 0.1874009 0.270408 0.1431739 0.27709 0.1874009 0.269801 0.1841329 0.656725 0.642205 0.656372 0.65443 0.630867 0.647104 0.07603275 0.172322 0.07631027 0.209343 0.06631207 0.172393 0.07603275 0.172322 0.1012549 0.1920869 0.09930247 0.234826 0.07603275 0.172322 0.09930247 0.234826 0.07631027 0.209343 0.608999 0.526822 0.585675 0.52352 0.582048 0.506446 0.608999 0.526822 0.611187 0.565957 0.585675 0.52352 0.646157 0.883777 0.66006 0.899446 0.646375 0.977458 0.319247 0.834786 0.324939 0.876156 0.29901 0.886997 0.685987 0.757301 0.704915 0.783232 0.693478 0.815043 0.685987 0.757301 0.693478 0.815043 0.672469 0.819747 0.685987 0.757301 0.708795 0.706857 0.704915 0.783232 0.748501 0.545012 0.767595 0.514582 0.760673 0.587021 0.748501 0.545012 0.76035 0.456006 0.767595 0.514582 0.955862 0.636667 0.937682 0.635935 0.93989 0.604981 0.955862 0.636667 0.93989 0.604981 0.959534 0.599206 0.481095 0.653215 0.453932 0.660555 0.462936 0.652068 0.262979 0.262279 0.249884 0.282916 0.2358109 0.287699 0.2010239 0.165771 0.2335129 0.205923 0.181275 0.219622 0.808382 0.237151 0.782431 0.237809 0.775812 0.235244 0.611187 0.565957 0.590841 0.595692 0.581781 0.551915 0.611187 0.565957 0.581781 0.551915 0.585675 0.52352 0.387612 0.157095 0.427456 0.1887699 0.369878 0.1664389 0.672469 0.819747 0.678325 0.896606 0.66006 0.899446 0.672469 0.819747 0.693478 0.815043 0.678325 0.896606 0.959534 0.599206 0.93989 0.604981 0.943399 0.552913 0.959534 0.599206 0.943399 0.552913 0.951632 0.523074 0.03499859 0.355105 0.05946135 0.408385 0.0408113 0.408703 0.03499859 0.355105 0.04754698 0.34493 0.06560856 0.368794 0.03499859 0.355105 0.06560856 0.368794 0.05946135 0.408385 0.23395 0.317033 0.218612 0.327409 0.199524 0.316967 0.249884 0.282916 0.215631 0.305442 0.2358109 0.287699 0.23395 0.317033 0.246193 0.334799 0.218612 0.327409 0.04754698 0.34493 0.05824565 0.327257 0.06560856 0.368794 0.369494 0.955216 0.362475 0.982197 0.343462 0.981205 0.369494 0.955216 0.343462 0.981205 0.347043 0.934073 0.324939 0.876156 0.329476 0.928108 0.304972 0.911108 0.324939 0.876156 0.304972 0.911108 0.29901 0.886997 0.459635 0.187584 0.494483 0.222247 0.44786 0.215981 0.459635 0.187584 0.44786 0.215981 0.427456 0.1887699 0.459635 0.187584 0.528662 0.209367 0.494483 0.222247 0.528662 0.209367 0.57213 0.233653 0.530388 0.239284 0.528662 0.209367 0.530388 0.239284 0.494483 0.222247 0.256763 0.36918 0.2359949 0.375179 0.246193 0.334799 0.256763 0.36918 0.249594 0.401268 0.2359949 0.375179 0.519923 0.370766 0.541838 0.42463 0.519805 0.403237 0.06304121 0.316352 0.07647037 0.326713 0.05824565 0.327257 0.07917177 0.291126 0.09563857 0.294021 0.127291 0.309302 0.06304121 0.316352 0.111117 0.315903 0.07647037 0.326713 0.767297 0.632977 0.797668 0.632754 0.788468 0.643598 0.767297 0.632977 0.777695 0.589612 0.797668 0.632754 0.767297 0.632977 0.760673 0.587021 0.777695 0.589612 0.656372 0.65443 0.61487 0.656764 0.630867 0.647104 0.606286 0.986605 0.623278 0.972919 0.63879 0.990258 0.582048 0.506446 0.585675 0.52352 0.565233 0.497271 0.563776 0.476098 0.529138 0.48219 0.523275 0.431413 0.563776 0.476098 0.523275 0.431413 0.541838 0.42463 0.563776 0.476098 0.565233 0.497271 0.529138 0.48219 0.541838 0.42463 0.523275 0.431413 0.519805 0.403237 0.462936 0.652068 0.430858 0.659041 0.435097 0.65151 0.937682 0.635935 0.909837 0.63601 0.919887 0.606714 0.462936 0.652068 0.453932 0.660555 0.430858 0.659041 0.937682 0.635935 0.919887 0.606714 0.93989 0.604981 0.788468 0.643598 0.797668 0.632754 0.813908 0.640005 0.09563857 0.294021 0.121259 0.30084 0.127291 0.309302 0.1012549 0.1920869 0.137702 0.2308149 0.09930247 0.234826 0.380401 0.988869 0.343572 0.992331 0.362475 0.982197 0.623278 0.972919 0.646375 0.977458 0.63879 0.990258 0.347043 0.934073 0.343462 0.981205 0.329476 0.928108 0.585675 0.52352 0.559995 0.54838 0.565233 0.497271 0.585675 0.52352 0.581781 0.551915 0.559995 0.54838 0.0408113 0.408703 0.05946135 0.408385 0.05147218 0.450991 0.760673 0.587021 0.767595 0.514582 0.777695 0.589612 0.246193 0.334799 0.2359949 0.375179 0.218612 0.327409 0.05824565 0.327257 0.07647037 0.326713 0.06560856 0.368794 0.93989 0.604981 0.919887 0.606714 0.922137 0.541751 0.93989 0.604981 0.922137 0.541751 0.943399 0.552913 0.2358109 0.287699 0.215631 0.305442 0.21284 0.297737 0.797668 0.632754 0.777695 0.589612 0.800957 0.568424 0.797668 0.632754 0.800957 0.568424 0.82667 0.580275 0.797668 0.632754 0.82667 0.580275 0.813908 0.640005 0.269801 0.1841329 0.257579 0.221025 0.2335129 0.205923 0.269801 0.1841329 0.27709 0.1874009 0.257579 0.221025 0.951632 0.523074 0.943399 0.552913 0.936281 0.487829 0.704915 0.783232 0.714293 0.819257 0.693478 0.815043 0.362475 0.982197 0.343572 0.992331 0.343462 0.981205 0.66006 0.899446 0.678325 0.896606 0.671696 0.982636 0.66006 0.899446 0.671696 0.982636 0.646375 0.977458 0.909837 0.63601 0.870533 0.640558 0.893068 0.611816 0.435097 0.65151 0.430858 0.659041 0.3957 0.655161 0.909837 0.63601 0.893068 0.611816 0.919887 0.606714 0.777695 0.589612 0.767595 0.514582 0.790355 0.510595 0.777695 0.589612 0.790355 0.510595 0.800957 0.568424 0.218612 0.327409 0.207985 0.397435 0.1893399 0.374291 0.218612 0.327409 0.2359949 0.375179 0.207985 0.397435 0.218612 0.327409 0.1893399 0.374291 0.199524 0.316967 0.21284 0.297737 0.215631 0.305442 0.190079 0.310454 0.21284 0.297737 0.190079 0.310454 0.1778219 0.304291 0.630867 0.647104 0.61487 0.656764 0.6038 0.613104 0.606332 0.66527 0.616691 0.662589 0.606673 0.665659 0.323404 0.149545 0.323074 0.177258 0.32107 0.159767 0.782431 0.237809 0.771906 0.237676 0.775812 0.235244 0.323404 0.149545 0.369878 0.1664389 0.333304 0.174517 0.323404 0.149545 0.333304 0.174517 0.323074 0.177258 0.646375 0.977458 0.671696 0.982636 0.63879 0.990258 0.369878 0.1664389 0.427456 0.1887699 0.363288 0.1975679 0.369878 0.1664389 0.363288 0.1975679 0.333304 0.174517 0.693478 0.815043 0.696463 0.884977 0.678325 0.896606 0.693478 0.815043 0.714293 0.819257 0.696463 0.884977 0.07647037 0.326713 0.111117 0.315903 0.110328 0.329721 0.07647037 0.326713 0.09228128 0.405749 0.06560856 0.368794 0.07647037 0.326713 0.110328 0.329721 0.09228128 0.405749 0.127291 0.309302 0.121259 0.30084 0.154713 0.311154 0.111117 0.315903 0.138513 0.316839 0.1367689 0.328522 0.111117 0.315903 0.1367689 0.328522 0.110328 0.329721 0.249594 0.401268 0.225915 0.418598 0.2359949 0.375179 0.249594 0.401268 0.248358 0.429592 0.225915 0.418598 0.2359949 0.375179 0.225915 0.418598 0.207985 0.397435 0.919887 0.606714 0.905884 0.544301 0.922137 0.541751 0.919887 0.606714 0.893068 0.611816 0.905884 0.544301 0.339102 0.65332 0.361264 0.653902 0.372654 0.659975 0.813908 0.640005 0.82667 0.580275 0.844176 0.606871 0.813908 0.640005 0.844176 0.606871 0.836078 0.640082 0.329476 0.928108 0.312328 0.941161 0.304972 0.911108 0.329476 0.928108 0.317276 0.982067 0.312328 0.941161 0.329476 0.928108 0.343462 0.981205 0.317276 0.982067 0.427456 0.1887699 0.401617 0.204532 0.363288 0.1975679 0.427456 0.1887699 0.44786 0.215981 0.401617 0.204532 0.248358 0.429592 0.242913 0.480459 0.222715 0.480264 0.248358 0.429592 0.222715 0.480264 0.225915 0.418598 0.767595 0.514582 0.784231 0.465391 0.790355 0.510595 0.767595 0.514582 0.76035 0.456006 0.784231 0.465391 0.06560856 0.368794 0.09228128 0.405749 0.05946135 0.408385 0.199524 0.316967 0.181313 0.325019 0.173983 0.315455 0.199524 0.316967 0.1893399 0.374291 0.181313 0.325019 0.143427 0.304789 0.1778219 0.304291 0.154713 0.311154 0.836078 0.640082 0.844176 0.606871 0.870533 0.640558 0.110328 0.329721 0.114943 0.403743 0.09228128 0.405749 0.110328 0.329721 0.1367689 0.328522 0.114943 0.403743 0.63879 0.990258 0.671696 0.982636 0.672233 0.995442 0.6038 0.613104 0.584954 0.635827 0.578793 0.610536 0.6038 0.613104 0.578793 0.610536 0.590841 0.595692 0.6038 0.613104 0.61487 0.656764 0.584954 0.635827 0.590841 0.595692 0.56028 0.601466 0.559995 0.54838 0.590841 0.595692 0.559995 0.54838 0.581781 0.551915 0.590841 0.595692 0.578793 0.610536 0.56028 0.601466 0.565233 0.497271 0.543477 0.504354 0.529138 0.48219 0.565233 0.497271 0.559995 0.54838 0.543477 0.504354 0.678325 0.896606 0.682659 0.968892 0.671696 0.982636 0.678325 0.896606 0.696463 0.884977 0.682659 0.968892 0.757594 0.421925 0.779126 0.396643 0.76035 0.456006 0.757594 0.421925 0.757264 0.397433 0.779126 0.396643 0.05946135 0.408385 0.0735827 0.452183 0.05147218 0.450991 0.05946135 0.408385 0.09228128 0.405749 0.0735827 0.452183 0.800957 0.568424 0.790355 0.510595 0.81198 0.522207 0.800957 0.568424 0.81198 0.522207 0.82667 0.580275 0.893068 0.611816 0.864363 0.573067 0.884964 0.569384 0.893068 0.611816 0.884964 0.569384 0.905884 0.544301 0.893068 0.611816 0.870533 0.640558 0.864363 0.573067 0.1778219 0.304291 0.190079 0.310454 0.154713 0.311154 0.870533 0.640558 0.844176 0.606871 0.864363 0.573067 0.138513 0.316839 0.173983 0.315455 0.1367689 0.328522 0.61487 0.656764 0.588193 0.658557 0.584954 0.635827 0.2335129 0.205923 0.231648 0.247888 0.199744 0.264806 0.2335129 0.205923 0.257579 0.221025 0.231648 0.247888 0.2335129 0.205923 0.199744 0.264806 0.181275 0.219622 0.181275 0.219622 0.1586509 0.264407 0.137702 0.2308149 0.181275 0.219622 0.199744 0.264806 0.1586509 0.264407 0.343462 0.981205 0.343572 0.992331 0.317276 0.982067 0.494483 0.222247 0.472437 0.234022 0.44786 0.215981 0.03792107 0.486275 0.06897908 0.512118 0.05440068 0.509124 0.03792107 0.486275 0.05147218 0.450991 0.06897908 0.512118 0.242913 0.480459 0.232196 0.507918 0.222715 0.480264 0.529138 0.48219 0.543477 0.504354 0.524327 0.51052 0.173983 0.315455 0.181313 0.325019 0.1531 0.335842 0.173983 0.315455 0.1531 0.335842 0.1367689 0.328522 0.05147218 0.450991 0.0735827 0.452183 0.06897908 0.512118 0.790355 0.510595 0.814235 0.453692 0.81198 0.522207 0.790355 0.510595 0.784231 0.465391 0.814235 0.453692 0.225915 0.418598 0.202255 0.429169 0.207985 0.397435 0.225915 0.418598 0.222715 0.480264 0.202255 0.429169 0.922137 0.541751 0.936281 0.487829 0.943399 0.552913 0.922137 0.541751 0.914798 0.484472 0.936281 0.487829 0.922137 0.541751 0.905884 0.544301 0.914798 0.484472 0.07631027 0.209343 0.096309 0.243603 0.08191215 0.234808 0.07631027 0.209343 0.09930247 0.234826 0.096309 0.243603 0.76035 0.456006 0.779126 0.396643 0.784231 0.465391 0.936281 0.487829 0.914798 0.484472 0.917698 0.400523 0.936281 0.487829 0.917698 0.400523 0.944603 0.421451 0.82667 0.580275 0.838047 0.519559 0.844176 0.606871 0.82667 0.580275 0.81198 0.522207 0.838047 0.519559 0.844176 0.606871 0.838047 0.519559 0.864363 0.573067 0.181313 0.325019 0.1893399 0.374291 0.1605139 0.402721 0.181313 0.325019 0.1605139 0.402721 0.1531 0.335842 0.1367689 0.328522 0.138475 0.393174 0.114943 0.403743 0.1367689 0.328522 0.1531 0.335842 0.138475 0.393174 0.255783 0.549319 0.235877 0.576835 0.2407439 0.566851 0.559995 0.54838 0.56028 0.601466 0.539003 0.578331 0.559995 0.54838 0.544741 0.567705 0.536335 0.538835 0.559995 0.54838 0.536335 0.538835 0.543477 0.504354 0.44786 0.215981 0.41396 0.2229 0.401617 0.204532 0.03848677 0.532959 0.05440068 0.509124 0.04853868 0.567371 0.543477 0.504354 0.536335 0.538835 0.524327 0.51052 0.784231 0.465391 0.804473 0.418751 0.814235 0.453692 0.784231 0.465391 0.779126 0.396643 0.804473 0.418751 0.207985 0.397435 0.202255 0.429169 0.178187 0.404087 0.207985 0.397435 0.178187 0.404087 0.1893399 0.374291 0.905884 0.544301 0.884964 0.569384 0.891466 0.501745 0.905884 0.544301 0.891466 0.501745 0.914798 0.484472 0.09228128 0.405749 0.117106 0.435478 0.0926662 0.468423 0.09228128 0.405749 0.0926662 0.468423 0.0735827 0.452183 0.09228128 0.405749 0.114943 0.403743 0.117106 0.435478 0.1893399 0.374291 0.178187 0.404087 0.1605139 0.402721 0.864363 0.573067 0.865112 0.518847 0.884964 0.569384 0.864363 0.573067 0.838047 0.519559 0.865112 0.518847 0.1531 0.335842 0.1605139 0.402721 0.138475 0.393174 0.257579 0.221025 0.250232 0.239723 0.231648 0.247888 0.672233 0.995442 0.671696 0.982636 0.690933 0.991544 0.333304 0.174517 0.324021 0.205214 0.323074 0.177258 0.333304 0.174517 0.363288 0.1975679 0.324021 0.205214 0.757264 0.397433 0.7562 0.366942 0.779126 0.396643 0.81198 0.522207 0.814235 0.453692 0.831617 0.465537 0.81198 0.522207 0.831617 0.465537 0.838047 0.519559 0.884964 0.569384 0.865112 0.518847 0.891466 0.501745 0.114943 0.403743 0.132858 0.430953 0.117106 0.435478 0.114943 0.403743 0.1605139 0.402721 0.132858 0.430953 0.114943 0.403743 0.138475 0.393174 0.1605139 0.402721 0.05588179 0.197588 0.05834388 0.2150689 0.05551218 0.197904 0.754695 0.235224 0.775812 0.235244 0.771906 0.237676 0.754695 0.235224 0.761827 0.1879889 0.775812 0.235244 0.754695 0.235224 0.726509 0.219796 0.761827 0.1879889 0.312328 0.941161 0.317276 0.982067 0.297012 0.982733 0.7562 0.366942 0.779206 0.325494 0.791519 0.331556 0.7562 0.366942 0.791519 0.331556 0.786729 0.372746 0.7562 0.366942 0.786729 0.372746 0.779126 0.396643 0.696463 0.884977 0.700204 0.946366 0.682659 0.968892 0.944603 0.421451 0.917698 0.400523 0.932425 0.360606 0.401617 0.204532 0.389907 0.2287189 0.360746 0.214882 0.401617 0.204532 0.360746 0.214882 0.363288 0.1975679 0.401617 0.204532 0.41396 0.2229 0.389907 0.2287189 0.779126 0.396643 0.803608 0.368208 0.804473 0.418751 0.779126 0.396643 0.786729 0.372746 0.803608 0.368208 0.914798 0.484472 0.891466 0.501745 0.901473 0.451381 0.914798 0.484472 0.901473 0.451381 0.917698 0.400523 0.584954 0.635827 0.56506 0.617692 0.578793 0.610536 0.584954 0.635827 0.574134 0.659444 0.56506 0.617692 0.584954 0.635827 0.588193 0.658557 0.574134 0.659444 0.363288 0.1975679 0.360746 0.214882 0.324021 0.205214 0.232196 0.507918 0.239176 0.537359 0.210194 0.523526 0.232196 0.507918 0.193955 0.502136 0.222715 0.480264 0.232196 0.507918 0.210194 0.523526 0.193955 0.502136 0.05440068 0.509124 0.06265038 0.563758 0.04853868 0.567371 0.05440068 0.509124 0.06897908 0.512118 0.06265038 0.563758 0.0735827 0.452183 0.08773958 0.523251 0.06897908 0.512118 0.0735827 0.452183 0.0926662 0.468423 0.08773958 0.523251 0.202255 0.429169 0.18323 0.439978 0.164688 0.42918 0.202255 0.429169 0.164688 0.42918 0.178187 0.404087 0.202255 0.429169 0.197817 0.473088 0.18323 0.439978 0.202255 0.429169 0.222715 0.480264 0.197817 0.473088 0.891466 0.501745 0.865112 0.518847 0.882858 0.470314 0.891466 0.501745 0.882858 0.470314 0.901473 0.451381 0.838047 0.519559 0.860082 0.463914 0.865112 0.518847 0.838047 0.519559 0.831617 0.465537 0.860082 0.463914 0.1605139 0.402721 0.164688 0.42918 0.132858 0.430953 0.1605139 0.402721 0.178187 0.404087 0.164688 0.42918 0.137702 0.2308149 0.1586509 0.264407 0.09930247 0.234826 0.671696 0.982636 0.696796 0.976839 0.690933 0.991544 0.671696 0.982636 0.682659 0.968892 0.696796 0.976839 0.578793 0.610536 0.56506 0.617692 0.56028 0.601466 0.222715 0.480264 0.193955 0.502136 0.197817 0.473088 0.06897908 0.512118 0.08909839 0.588247 0.06265038 0.563758 0.06897908 0.512118 0.08773958 0.523251 0.08909839 0.588247 0.865112 0.518847 0.860082 0.463914 0.882858 0.470314 0.317276 0.982067 0.308997 0.990601 0.297012 0.982733 0.239176 0.537359 0.2407439 0.566851 0.2239429 0.554309 0.239176 0.537359 0.2239429 0.554309 0.210194 0.523526 0.04853868 0.567371 0.06265038 0.563758 0.05808454 0.591898 0.917698 0.400523 0.908176 0.366716 0.932425 0.360606 0.917698 0.400523 0.901473 0.451381 0.890469 0.407191 0.917698 0.400523 0.890469 0.407191 0.908176 0.366716 0.117106 0.435478 0.124345 0.500828 0.111415 0.508223 0.117106 0.435478 0.111415 0.508223 0.0926662 0.468423 0.117106 0.435478 0.132858 0.430953 0.144635 0.460824 0.117106 0.435478 0.144635 0.460824 0.124345 0.500828 0.750683 0.01154315 0.807973 0.06941205 0.759936 0.08270537 0.750683 0.01154315 0.699398 0.0510779 0.73667 0.01624286 0.750683 0.01154315 0.678998 0.108098 0.699398 0.0510779 0.750683 0.01154315 0.759936 0.08270537 0.678998 0.108098 0.56028 0.601466 0.542348 0.622905 0.529209 0.594056 0.56028 0.601466 0.529209 0.594056 0.539003 0.578331 0.56028 0.601466 0.56506 0.617692 0.542348 0.622905 0.682659 0.968892 0.700204 0.946366 0.696796 0.976839 0.814235 0.453692 0.804473 0.418751 0.821759 0.392439 0.814235 0.453692 0.821759 0.392439 0.843753 0.424994 0.814235 0.453692 0.843753 0.424994 0.831617 0.465537 0.0926662 0.468423 0.111415 0.508223 0.08773958 0.523251 0.18323 0.439978 0.164427 0.448425 0.164688 0.42918 0.18323 0.439978 0.157269 0.510988 0.164427 0.448425 0.18323 0.439978 0.193955 0.502136 0.157269 0.510988 0.18323 0.439978 0.197817 0.473088 0.193955 0.502136 0.164688 0.42918 0.164427 0.448425 0.132858 0.430953 0.132858 0.430953 0.164427 0.448425 0.144635 0.460824 0.09930247 0.234826 0.1586509 0.264407 0.128762 0.264399 0.09930247 0.234826 0.128762 0.264399 0.096309 0.243603 0.324021 0.205214 0.360746 0.214882 0.335721 0.224184 0.324021 0.205214 0.335721 0.224184 0.324625 0.225898 0.689068 0.175754 0.726509 0.219796 0.705594 0.204468 0.726509 0.219796 0.689068 0.175754 0.761827 0.1879889 0.235877 0.576835 0.2239429 0.554309 0.2407439 0.566851 0.235877 0.576835 0.218537 0.591052 0.2239429 0.554309 0.831617 0.465537 0.843753 0.424994 0.860082 0.463914 0.882858 0.470314 0.890469 0.407191 0.901473 0.451381 0.882858 0.470314 0.860082 0.463914 0.890469 0.407191 0.860082 0.463914 0.862464 0.411202 0.890469 0.407191 0.860082 0.463914 0.843753 0.424994 0.862464 0.411202 0.56506 0.617692 0.550879 0.66071 0.542348 0.622905 0.56506 0.617692 0.574134 0.659444 0.550879 0.66071 0.04684156 0.620545 0.07095199 0.626072 0.06002205 0.64622 0.04684156 0.620545 0.05808454 0.591898 0.07095199 0.626072 0.05808454 0.591898 0.06265038 0.563758 0.08909839 0.588247 0.05808454 0.591898 0.08909839 0.588247 0.07095199 0.626072 0.932425 0.360606 0.908176 0.366716 0.932422 0.330063 0.804473 0.418751 0.803608 0.368208 0.821759 0.392439 0.08773958 0.523251 0.111415 0.508223 0.101088 0.564852 0.08773958 0.523251 0.101088 0.564852 0.08909839 0.588247 0.164427 0.448425 0.157269 0.510988 0.144635 0.460824 0.774447 0.316985 0.806733 0.315455 0.779206 0.325494 0.786729 0.372746 0.791519 0.331556 0.803608 0.368208 0.2239429 0.554309 0.203013 0.53853 0.210194 0.523526 0.2239429 0.554309 0.196835 0.560605 0.203013 0.53853 0.2239429 0.554309 0.218537 0.591052 0.196835 0.560605 0.210194 0.523526 0.203013 0.53853 0.183941 0.52094 0.210194 0.523526 0.183941 0.52094 0.193955 0.502136 0.193955 0.502136 0.183941 0.52094 0.157269 0.510988 0.144635 0.460824 0.157269 0.510988 0.124345 0.500828 0.250232 0.239723 0.2285889 0.260176 0.231648 0.247888 0.928483 0.315455 0.932422 0.330063 0.906813 0.318149 0.231648 0.247888 0.2285889 0.260176 0.199744 0.264806 0.199744 0.264806 0.189869 0.278985 0.1758829 0.274895 0.199744 0.264806 0.2285889 0.260176 0.189869 0.278985 0.199744 0.264806 0.1758829 0.274895 0.1586509 0.264407 0.111415 0.508223 0.135245 0.528698 0.101088 0.564852 0.111415 0.508223 0.124345 0.500828 0.135245 0.528698 0.124345 0.500828 0.157269 0.510988 0.135245 0.528698 0.73667 0.01624286 0.699398 0.0510779 0.713666 0.0342313 0.932422 0.330063 0.907018 0.32575 0.906813 0.318149 0.932422 0.330063 0.908176 0.366716 0.907018 0.32575 0.779206 0.325494 0.806733 0.315455 0.791519 0.331556 0.890469 0.407191 0.862464 0.411202 0.877389 0.364605 0.890469 0.407191 0.877389 0.364605 0.908176 0.366716 0.08909839 0.588247 0.122005 0.586727 0.112189 0.644898 0.08909839 0.588247 0.101088 0.564852 0.122005 0.586727 0.08909839 0.588247 0.112189 0.644898 0.08760559 0.657367 0.08909839 0.588247 0.08760559 0.657367 0.07095199 0.626072 0.843753 0.424994 0.848751 0.374327 0.862464 0.411202 0.843753 0.424994 0.821759 0.392439 0.848751 0.374327 0.157269 0.510988 0.150994 0.591748 0.135245 0.528698 0.157269 0.510988 0.177157 0.571353 0.150994 0.591748 0.157269 0.510988 0.183941 0.52094 0.177157 0.571353 0.1586509 0.264407 0.151129 0.274139 0.128762 0.264399 0.1586509 0.264407 0.1758829 0.274895 0.151129 0.274139 0.218537 0.591052 0.2287189 0.621252 0.203141 0.634694 0.218537 0.591052 0.203141 0.634694 0.196835 0.560605 0.203013 0.53853 0.196835 0.560605 0.183941 0.52094 0.821759 0.392439 0.823358 0.330369 0.848751 0.374327 0.821759 0.392439 0.803608 0.368208 0.823358 0.330369 0.862464 0.411202 0.848751 0.374327 0.877389 0.364605 0.2287189 0.621252 0.212126 0.659691 0.203141 0.634694 0.2287189 0.621252 0.228765 0.659607 0.212126 0.659691 0.06002205 0.64622 0.08760559 0.657367 0.05860716 0.657266 0.06002205 0.64622 0.07095199 0.626072 0.08760559 0.657367 0.791519 0.331556 0.823358 0.330369 0.803608 0.368208 0.791519 0.331556 0.806733 0.315455 0.823358 0.330369 0.183941 0.52094 0.196835 0.560605 0.177157 0.571353 0.806733 0.315455 0.829189 0.318219 0.823358 0.330369 0.908176 0.366716 0.887742 0.330299 0.907018 0.32575 0.908176 0.366716 0.877389 0.364605 0.887742 0.330299 0.196835 0.560605 0.203141 0.634694 0.177157 0.571353 0.101088 0.564852 0.135245 0.528698 0.122005 0.586727 0.135245 0.528698 0.150994 0.591748 0.122005 0.586727 0.906813 0.318149 0.907018 0.32575 0.868213 0.324152 0.907018 0.32575 0.887742 0.330299 0.868213 0.324152 0.848751 0.374327 0.848472 0.327153 0.868213 0.324152 0.848751 0.374327 0.868213 0.324152 0.877389 0.364605 0.848751 0.374327 0.823358 0.330369 0.848472 0.327153 0.177157 0.571353 0.203141 0.634694 0.174387 0.621149 0.177157 0.571353 0.174387 0.621149 0.150994 0.591748 0.823358 0.330369 0.829189 0.318219 0.848472 0.327153 0.877389 0.364605 0.868213 0.324152 0.887742 0.330299 0.122005 0.586727 0.133877 0.639677 0.112189 0.644898 0.122005 0.586727 0.150994 0.591748 0.133877 0.639677 0.150994 0.591748 0.153643 0.638064 0.133877 0.639677 0.150994 0.591748 0.174387 0.621149 0.153643 0.638064 0.203141 0.634694 0.178178 0.657149 0.174387 0.621149 0.203141 0.634694 0.212126 0.659691 0.188827 0.659013 0.203141 0.634694 0.188827 0.659013 0.178178 0.657149 0.699398 0.0510779 0.678998 0.108098 0.682218 0.07466048 0.829189 0.318219 0.853927 0.317402 0.848472 0.327153 0.689068 0.175754 0.677855 0.1491259 0.731261 0.144028 0.689068 0.175754 0.731261 0.144028 0.761827 0.1879889 0.08760559 0.657367 0.112189 0.644898 0.114421 0.657721 0.868213 0.324152 0.848472 0.327153 0.853927 0.317402 0.174387 0.621149 0.178178 0.657149 0.153643 0.638064 0.112189 0.644898 0.128574 0.657871 0.114421 0.657721 0.112189 0.644898 0.133877 0.639677 0.128574 0.657871 0.153643 0.638064 0.178178 0.657149 0.155434 0.658468 0.153643 0.638064 0.155434 0.658468 0.133877 0.639677 0.133877 0.639677 0.155434 0.658468 0.128574 0.657871 0.677855 0.1491259 0.67483 0.135028 0.678998 0.108098 0.677855 0.1491259 0.678998 0.108098 0.731261 0.144028 0.678998 0.108098 0.759936 0.08270537 0.731261 0.144028 0.678998 0.108098 0.67944 0.08542895 0.682218 0.07466048 0.828282 0.160665 0.761827 0.1879889 0.821914 0.119079 0.821914 0.119079 0.761827 0.1879889 0.731261 0.144028 0.821914 0.119079 0.731261 0.144028 0.759936 0.08270537 0.821914 0.119079 0.759936 0.08270537 0.807973 0.06941205 - - - - - - - - - - - - - - - 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 -

0 0 0 1 1 1 2 2 2 0 0 3 3 3 4 4 4 5 0 0 6 2 2 7 3 3 8 0 0 9 4 4 10 1 1 11 2 2 12 1 1 13 5 5 14 2 2 15 5 5 16 6 6 17 2 2 18 7 7 19 8 8 20 2 2 21 8 8 22 3 3 23 2 2 24 6 6 25 7 7 26 4 4 27 3 3 28 9 9 29 4 4 30 9 9 31 10 10 32 4 4 33 10 10 34 11 11 35 4 4 36 11 11 37 12 12 38 4 4 39 12 12 40 13 13 41 4 4 42 13 13 43 1 1 44 1 1 45 14 14 46 5 5 47 1 1 48 15 15 49 14 14 50 1 1 51 13 13 52 15 15 53 3 3 54 8 8 55 16 16 56 3 3 57 16 16 58 9 9 59 5 5 60 14 14 61 17 17 62 5 5 63 18 18 64 6 6 65 5 5 66 19 19 67 18 18 68 5 5 69 20 20 70 19 19 71 5 5 72 17 17 73 20 20 74 18 18 75 21 21 76 22 22 77 18 18 78 19 19 79 21 21 80 18 18 81 22 22 82 6 6 83 9 9 84 23 23 85 10 10 86 9 9 87 16 16 88 24 24 89 9 9 90 24 24 91 25 25 92 9 9 93 25 25 94 23 23 95 6 6 96 26 26 97 27 27 98 6 6 99 27 27 100 7 7 101 6 6 102 22 22 103 26 26 104 11 11 105 28 28 106 12 12 107 11 11 108 29 29 109 28 28 110 11 11 111 10 10 112 29 29 113 8 8 114 30 30 115 16 16 116 8 8 117 7 7 118 30 30 119 10 10 120 23 23 121 31 31 122 10 10 123 31 31 124 29 29 125 14 14 126 15 15 127 32 32 128 14 14 129 32 32 130 33 33 131 14 14 132 33 33 133 34 34 134 14 14 135 34 34 136 17 17 137 7 7 138 27 27 139 35 35 140 7 7 141 35 35 142 30 30 143 17 17 144 34 34 145 20 20 146 19 19 147 20 20 148 36 36 149 19 19 150 36 36 151 21 21 152 16 16 153 30 30 154 24 24 155 15 15 156 37 37 157 32 32 158 15 15 159 13 13 160 37 37 161 13 13 162 38 38 163 37 37 164 13 13 165 12 12 166 39 39 167 13 13 168 39 39 169 38 38 170 20 20 171 40 40 172 36 36 173 20 20 174 41 41 175 42 42 176 20 20 177 42 42 178 40 40 179 20 20 180 34 34 181 41 41 182 32 32 183 37 37 184 43 43 185 32 32 186 44 44 187 33 33 188 32 32 189 43 43 190 44 44 191 34 34 192 33 33 193 41 41 194 27 27 195 45 45 196 35 35 197 27 27 198 26 26 199 45 45 200 12 12 201 28 28 202 46 46 203 12 12 204 47 47 205 39 39 206 12 12 207 46 46 208 47 47 209 28 28 210 48 48 211 46 46 212 28 28 213 29 29 214 49 49 215 28 28 216 49 49 217 48 48 218 22 22 219 21 21 220 50 50 221 22 22 222 50 50 223 51 51 224 22 22 225 51 51 226 26 26 227 24 24 228 52 52 229 25 25 230 24 24 231 30 30 232 53 53 233 24 24 234 54 54 235 52 52 236 24 24 237 53 53 238 54 54 239 23 23 240 25 25 241 55 55 242 23 23 243 55 55 244 31 31 245 37 37 246 38 38 247 43 43 248 35 35 249 45 45 250 56 56 251 35 35 252 57 57 253 30 30 254 35 35 255 56 56 256 57 57 257 29 29 258 31 31 259 49 49 260 36 36 261 40 40 262 58 58 263 36 36 264 59 59 265 21 21 266 36 36 267 60 60 268 59 59 269 36 36 270 58 58 271 60 60 272 30 30 273 57 57 274 53 53 275 33 33 276 44 44 277 61 61 278 33 33 279 61 61 280 41 41 281 21 21 282 59 59 283 62 62 284 21 21 285 62 62 286 50 50 287 25 25 288 63 63 289 55 55 290 25 25 291 52 52 292 63 63 293 31 31 294 64 64 295 49 49 296 31 31 297 55 55 298 64 64 299 40 40 300 65 65 301 58 58 302 40 40 303 42 42 304 65 65 305 39 39 306 66 66 307 38 38 308 39 39 309 47 47 310 66 66 311 26 26 312 51 51 313 45 45 314 57 57 315 67 67 316 68 68 317 57 57 318 68 68 319 53 53 320 57 57 321 56 56 322 67 67 323 41 41 324 69 69 325 42 42 326 41 41 327 61 61 328 70 70 329 41 41 330 70 70 331 69 69 332 38 38 333 71 71 334 43 43 335 38 38 336 66 66 337 72 72 338 38 38 339 73 73 340 71 71 341 38 38 342 72 72 343 73 73 344 58 58 345 65 65 346 60 60 347 46 46 348 48 48 349 74 74 350 46 46 351 74 74 352 75 75 353 46 46 354 75 75 355 47 47 356 53 53 357 68 68 358 54 54 359 55 55 360 63 63 361 76 76 362 55 55 363 76 76 364 77 77 365 55 55 366 77 77 367 64 64 368 56 56 369 45 45 370 78 78 371 56 56 372 78 78 373 79 79 374 56 56 375 79 79 376 67 67 377 51 51 378 50 50 379 80 80 380 51 51 381 80 80 382 81 81 383 51 51 384 81 81 385 45 45 386 48 48 387 82 82 388 74 74 389 48 48 390 49 49 391 83 83 392 48 48 393 83 83 394 82 82 395 52 52 396 84 84 397 63 63 398 52 52 399 54 54 400 85 85 401 52 52 402 86 86 403 84 84 404 52 52 405 85 85 406 86 86 407 44 44 408 87 87 409 61 61 410 44 44 411 43 43 412 88 88 413 44 44 414 88 88 415 87 87 416 43 43 417 71 71 418 88 88 419 45 45 420 89 89 421 78 78 422 45 45 423 81 81 424 89 89 425 42 42 426 90 90 427 91 91 428 42 42 429 91 91 430 65 65 431 42 42 432 69 69 433 90 90 434 49 49 435 64 64 436 83 83 437 47 47 438 75 75 439 92 92 440 47 47 441 92 92 442 93 93 443 47 47 444 93 93 445 66 66 446 50 50 447 94 94 448 80 80 449 50 50 450 62 62 451 94 94 452 59 59 453 60 60 454 95 95 455 59 59 456 96 96 457 97 97 458 59 59 459 97 97 460 62 62 461 59 59 462 95 95 463 96 96 464 54 54 465 68 68 466 85 85 467 65 65 468 91 91 469 98 98 470 65 65 471 98 98 472 60 60 473 64 64 474 77 77 475 99 99 476 64 64 477 100 100 478 83 83 479 64 64 480 99 99 481 100 100 482 60 60 483 101 101 484 95 95 485 60 60 486 98 98 487 101 101 488 80 80 489 102 102 490 81 81 491 80 80 492 103 103 493 102 102 494 80 80 495 94 94 496 103 103 497 82 82 498 83 83 499 104 104 500 82 82 501 104 104 502 105 105 503 82 82 504 105 105 505 74 74 506 74 74 507 105 105 508 75 75 509 62 62 510 106 106 511 94 94 512 62 62 513 107 107 514 106 106 515 62 62 516 97 97 517 107 107 518 68 68 519 67 67 520 108 108 521 68 68 522 86 86 523 85 85 524 68 68 525 108 108 526 86 86 527 63 63 528 84 84 529 76 76 530 61 61 531 109 109 532 70 70 533 61 61 534 87 87 535 109 109 536 88 88 537 110 110 538 111 111 539 88 88 540 71 71 541 110 110 542 88 88 543 111 111 544 87 87 545 71 71 546 73 73 547 110 110 548 76 76 549 112 112 550 113 113 551 76 76 552 113 113 553 77 77 554 76 76 555 84 84 556 112 112 557 69 69 558 70 70 559 114 114 560 69 69 561 114 114 562 90 90 563 78 78 564 115 115 565 79 79 566 78 78 567 89 89 568 115 115 569 66 66 570 116 116 571 72 72 572 66 66 573 117 117 574 116 116 575 66 66 576 93 93 577 117 117 578 81 81 579 102 102 580 118 118 581 81 81 582 118 118 583 89 89 584 75 75 585 119 119 586 92 92 587 75 75 588 120 120 589 119 119 590 75 75 591 105 105 592 120 120 593 67 67 594 121 121 595 108 108 596 67 67 597 79 79 598 121 121 599 89 89 600 118 118 601 115 115 602 83 83 603 100 100 604 122 122 605 83 83 606 122 122 607 104 104 608 95 95 609 101 101 610 96 96 611 93 93 612 92 92 613 117 117 614 94 94 615 123 123 616 103 103 617 94 94 618 106 106 619 123 123 620 108 108 621 124 124 622 125 125 623 108 108 624 121 121 625 124 124 626 108 108 627 125 125 628 86 86 629 84 84 630 126 126 631 127 127 632 84 84 633 127 127 634 128 128 635 84 84 636 128 128 637 112 112 638 84 84 639 86 86 640 126 126 641 79 79 642 115 115 643 129 129 644 79 79 645 129 129 646 130 130 647 79 79 648 130 130 649 121 121 650 70 70 651 109 109 652 131 131 653 70 70 654 132 132 655 133 133 656 70 70 657 133 133 658 114 114 659 70 70 660 131 131 661 132 132 662 73 73 663 134 134 664 110 110 665 73 73 666 72 72 667 134 134 668 72 72 669 116 116 670 134 134 671 77 77 672 113 113 673 135 135 674 77 77 675 135 135 676 99 99 677 92 92 678 119 119 679 117 117 680 100 100 681 99 99 682 136 136 683 100 100 684 136 136 685 122 122 686 86 86 687 125 125 688 126 126 689 104 104 690 122 122 691 137 137 692 104 104 693 137 137 694 105 105 695 96 96 696 101 101 697 138 138 698 96 96 699 138 138 700 139 139 701 96 96 702 139 139 703 97 97 704 87 87 705 111 111 706 109 109 707 91 91 708 90 90 709 140 140 710 91 91 711 140 140 712 98 98 713 121 121 714 130 130 715 141 141 716 121 121 717 141 141 718 124 124 719 105 105 720 137 137 721 142 142 722 105 105 723 143 143 724 120 120 725 105 105 726 142 142 727 143 143 728 97 97 729 144 144 730 107 107 731 97 97 732 145 145 733 146 146 734 97 97 735 146 146 736 144 144 737 97 97 738 139 139 739 145 145 740 109 109 741 147 147 742 131 131 743 109 109 744 111 111 745 147 147 746 98 98 747 140 140 748 148 148 749 98 98 750 148 148 751 101 101 752 125 125 753 149 149 754 150 150 755 125 125 756 150 150 757 151 151 758 125 125 759 151 151 760 126 126 761 125 125 762 124 124 763 149 149 764 124 124 765 141 141 766 149 149 767 112 112 768 128 128 769 113 113 770 111 111 771 152 152 772 147 147 773 111 111 774 110 110 775 152 152 776 114 114 777 133 133 778 153 153 779 114 114 780 153 153 781 90 90 782 115 115 783 154 154 784 155 155 785 115 115 786 118 118 787 154 154 788 115 115 789 155 155 790 129 129 791 99 99 792 135 135 793 156 156 794 99 99 795 156 156 796 136 136 797 106 106 798 157 157 799 123 123 800 106 106 801 107 107 802 157 157 803 126 126 804 151 151 805 158 158 806 126 126 807 158 158 808 127 127 809 110 110 810 134 134 811 159 159 812 110 110 813 159 159 814 152 152 815 113 113 816 160 160 817 135 135 818 113 113 819 128 128 820 160 160 821 90 90 822 161 161 823 162 162 824 90 90 825 153 153 826 161 161 827 90 90 828 162 162 829 140 140 830 137 137 831 122 122 832 163 163 833 137 137 834 164 164 835 142 142 836 137 137 837 163 163 838 164 164 839 116 116 840 117 117 841 165 165 842 116 116 843 166 166 844 134 134 845 116 116 846 165 165 847 166 166 848 117 117 849 119 119 850 167 167 851 117 117 852 167 167 853 165 165 854 102 102 855 154 154 856 118 118 857 102 102 858 168 168 859 169 169 860 102 102 861 169 169 862 154 154 863 102 102 864 103 103 865 168 168 866 122 122 867 136 136 868 170 170 869 122 122 870 170 170 871 163 163 872 119 119 873 120 120 874 171 171 875 119 119 876 171 171 877 167 167 878 127 127 879 172 172 880 173 173 881 127 127 882 158 158 883 172 172 884 127 127 885 173 173 886 128 128 887 130 130 888 129 129 889 174 174 890 130 130 891 175 175 892 141 141 893 130 130 894 174 174 895 175 175 896 129 129 897 155 155 898 174 174 899 139 139 900 138 138 901 176 176 902 139 139 903 176 176 904 145 145 905 128 128 906 173 173 907 160 160 908 103 103 909 123 123 910 168 168 911 138 138 912 177 177 913 176 176 914 138 138 915 178 178 916 177 177 917 138 138 918 101 101 919 178 178 920 120 120 921 143 143 922 179 179 923 120 120 924 179 179 925 171 171 926 141 141 927 175 175 928 149 149 929 134 134 930 166 166 931 159 159 932 135 135 933 180 180 934 156 156 935 135 135 936 160 160 937 181 181 938 135 135 939 181 181 940 180 180 941 101 101 942 148 148 943 178 178 944 140 140 945 182 182 946 148 148 947 140 140 948 162 162 949 182 182 950 136 136 951 156 156 952 183 183 953 136 136 954 183 183 955 170 170 956 163 163 957 184 184 958 164 164 959 163 163 960 170 170 961 184 184 962 123 123 963 185 185 964 168 168 965 123 123 966 157 157 967 185 185 968 151 151 969 150 150 970 186 186 971 151 151 972 186 186 973 187 187 974 151 151 975 187 187 976 158 158 977 153 153 978 188 188 979 161 161 980 153 153 981 133 133 982 188 188 983 144 144 984 189 189 985 107 107 986 144 144 987 190 190 988 189 189 989 144 144 990 146 146 991 190 190 992 150 150 993 191 191 994 186 186 995 150 150 996 149 149 997 191 191 998 149 149 999 192 192 1000 191 191 1001 149 149 1002 175 175 1003 192 192 1004 158 158 1005 193 193 1006 172 172 1007 158 158 1008 187 187 1009 194 194 1010 158 158 1011 194 194 1012 193 193 1013 131 131 1014 147 147 1015 195 195 1016 131 131 1017 195 195 1018 196 196 1019 131 131 1020 196 196 1021 132 132 1022 133 133 1023 132 132 1024 197 197 1025 133 133 1026 197 197 1027 188 188 1028 160 160 1029 173 173 1030 198 198 1031 160 160 1032 198 198 1033 181 181 1034 156 156 1035 180 180 1036 183 183 1037 171 171 1038 199 199 1039 167 167 1040 171 171 1041 179 179 1042 200 200 1043 171 171 1044 200 200 1045 199 199 1046 145 145 1047 201 201 1048 202 202 1049 145 145 1050 176 176 1051 201 201 1052 145 145 1053 202 202 1054 146 146 1055 174 174 1056 203 203 1057 204 204 1058 174 174 1059 155 155 1060 203 203 1061 174 174 1062 204 204 1063 175 175 1064 155 155 1065 154 154 1066 205 205 1067 155 155 1068 206 206 1069 203 203 1070 155 155 1071 205 205 1072 206 206 1073 180 180 1074 181 181 1075 207 207 1076 180 180 1077 208 208 1078 183 183 1079 180 180 1080 207 207 1081 208 208 1082 148 148 1083 182 182 1084 209 209 1085 148 148 1086 210 210 1087 178 178 1088 148 148 1089 209 209 1090 210 210 1091 143 143 1092 211 211 1093 179 179 1094 143 143 1095 212 212 1096 211 211 1097 143 143 1098 142 142 1099 212 212 1100 164 164 1101 213 213 1102 142 142 1103 164 164 1104 184 184 1105 214 214 1106 164 164 1107 214 214 1108 213 213 1109 142 142 1110 213 213 1111 215 215 1112 142 142 1113 215 215 1114 212 212 1115 107 107 1116 216 216 1117 157 157 1118 107 107 1119 189 189 1120 216 216 1121 147 147 1122 152 152 1123 217 217 1124 147 147 1125 217 217 1126 195 195 1127 181 181 1128 198 198 1129 207 207 1130 154 154 1131 169 169 1132 205 205 1133 165 165 1134 167 167 1135 218 218 1136 165 165 1137 218 218 1138 219 219 1139 165 165 1140 219 219 1141 166 166 1142 167 167 1143 220 220 1144 218 218 1145 167 167 1146 199 199 1147 220 220 1148 170 170 1149 183 183 1150 221 221 1151 170 170 1152 221 221 1153 222 222 1154 170 170 1155 222 222 1156 184 184 1157 178 178 1158 210 210 1159 177 177 1160 176 176 1161 177 177 1162 223 223 1163 176 176 1164 223 223 1165 201 201 1166 175 175 1167 224 224 1168 192 192 1169 175 175 1170 204 204 1171 224 224 1172 132 132 1173 196 196 1174 197 197 1175 177 177 1176 210 210 1177 225 225 1178 177 177 1179 225 225 1180 226 226 1181 177 177 1182 226 226 1183 223 223 1184 179 179 1185 211 211 1186 200 200 1187 146 146 1188 202 202 1189 227 227 1190 146 146 1191 228 228 1192 190 190 1193 146 146 1194 227 227 1195 228 228 1196 152 152 1197 159 159 1198 229 229 1199 152 152 1200 229 229 1201 230 230 1202 152 152 1203 230 230 1204 217 217 1205 186 186 1206 191 191 1207 231 231 1208 186 186 1209 232 232 1210 187 187 1211 186 186 1212 231 231 1213 232 232 1214 191 191 1215 233 233 1216 234 234 1217 191 191 1218 234 234 1219 231 231 1220 191 191 1221 192 192 1222 233 233 1223 172 172 1224 193 193 1225 173 173 1226 195 195 1227 217 217 1228 235 235 1229 195 195 1230 236 236 1231 196 196 1232 195 195 1233 235 235 1234 236 236 1235 173 173 1236 237 237 1237 198 198 1238 173 173 1239 238 238 1240 237 237 1241 173 173 1242 193 193 1243 238 238 1244 162 162 1245 239 239 1246 182 182 1247 162 162 1248 240 240 1249 239 239 1250 162 162 1251 161 161 1252 240 240 1253 168 168 1254 241 241 1255 169 169 1256 168 168 1257 185 185 1258 241 241 1259 192 192 1260 224 224 1261 233 233 1262 196 196 1263 236 236 1264 197 197 1265 188 188 1266 242 242 1267 243 243 1268 188 188 1269 197 197 1270 242 242 1271 188 188 1272 243 243 1273 161 161 1274 161 161 1275 243 243 1276 240 240 1277 193 193 1278 194 194 1279 238 238 1280 205 205 1281 169 169 1282 206 206 1283 184 184 1284 244 244 1285 214 214 1286 184 184 1287 222 222 1288 244 244 1289 202 202 1290 245 245 1291 227 227 1292 202 202 1293 201 201 1294 245 245 1295 187 187 1296 246 246 1297 247 247 1298 187 187 1299 247 247 1300 194 194 1301 187 187 1302 232 232 1303 246 246 1304 204 204 1305 248 248 1306 224 224 1307 204 204 1308 249 249 1309 248 248 1310 204 204 1311 250 250 1312 249 249 1313 204 204 1314 203 203 1315 251 251 1316 204 204 1317 251 251 1318 250 250 1319 166 166 1320 229 229 1321 159 159 1322 166 166 1323 252 252 1324 229 229 1325 166 166 1326 219 219 1327 252 252 1328 182 182 1329 239 239 1330 209 209 1331 183 183 1332 208 208 1333 221 221 1334 157 157 1335 253 253 1336 185 185 1337 157 157 1338 254 254 1339 253 253 1340 157 157 1341 216 216 1342 254 254 1343 201 201 1344 223 223 1345 226 226 1346 201 201 1347 226 226 1348 255 255 1349 201 201 1350 255 255 1351 256 256 1352 201 201 1353 256 256 1354 245 245 1355 231 231 1356 234 234 1357 257 257 1358 231 231 1359 257 257 1360 232 232 1361 194 194 1362 258 258 1363 238 238 1364 194 194 1365 247 247 1366 258 258 1367 217 217 1368 259 259 1369 235 235 1370 217 217 1371 230 230 1372 259 259 1373 213 213 1374 214 214 1375 260 260 1376 213 213 1377 261 261 1378 215 215 1379 213 213 1380 260 260 1381 261 261 1382 169 169 1383 241 241 1384 262 262 1385 169 169 1386 262 262 1387 263 263 1388 169 169 1389 263 263 1390 206 206 1391 199 199 1392 264 264 1393 265 265 1394 199 199 1395 265 265 1396 220 220 1397 199 199 1398 200 200 1399 264 264 1400 210 210 1401 209 209 1402 225 225 1403 200 200 1404 211 211 1405 266 266 1406 200 200 1407 266 266 1408 264 264 1409 211 211 1410 267 267 1411 266 266 1412 211 211 1413 212 212 1414 267 267 1415 212 212 1416 268 268 1417 267 267 1418 212 212 1419 215 215 1420 268 268 1421 189 189 1422 190 190 1423 269 269 1424 189 189 1425 269 269 1426 216 216 1427 234 234 1428 233 233 1429 257 257 1430 236 236 1431 270 270 1432 242 242 1433 236 236 1434 271 271 1435 270 270 1436 236 236 1437 242 242 1438 197 197 1439 236 236 1440 235 235 1441 271 271 1442 229 229 1443 252 252 1444 230 230 1445 203 203 1446 206 206 1447 251 251 1448 207 207 1449 198 198 1450 272 272 1451 207 207 1452 272 272 1453 273 273 1454 207 207 1455 273 273 1456 208 208 1457 222 222 1458 221 221 1459 274 274 1460 222 222 1461 274 274 1462 244 244 1463 216 216 1464 269 269 1465 254 254 1466 232 232 1467 247 247 1468 246 246 1469 232 232 1470 275 275 1471 276 276 1472 232 232 1473 276 276 1474 247 247 1475 232 232 1476 277 277 1477 275 275 1478 232 232 1479 257 257 1480 277 277 1481 233 233 1482 224 224 1483 277 277 1484 233 233 1485 277 277 1486 257 257 1487 235 235 1488 259 259 1489 278 278 1490 235 235 1491 278 278 1492 271 271 1493 224 224 1494 248 248 1495 277 277 1496 198 198 1497 237 237 1498 279 279 1499 198 198 1500 279 279 1501 272 272 1502 218 218 1503 220 220 1504 219 219 1505 185 185 1506 253 253 1507 241 241 1508 227 227 1509 280 280 1510 228 228 1511 227 227 1512 245 245 1513 281 281 1514 227 227 1515 281 281 1516 280 280 1517 247 247 1518 276 276 1519 258 258 1520 238 238 1521 258 258 1522 282 282 1523 238 238 1524 282 282 1525 237 237 1526 206 206 1527 283 283 1528 251 251 1529 206 206 1530 263 263 1531 283 283 1532 208 208 1533 284 284 1534 221 221 1535 208 208 1536 273 273 1537 285 285 1538 208 208 1539 285 285 1540 284 284 1541 221 221 1542 284 284 1543 274 274 1544 241 241 1545 253 253 1546 262 262 1547 259 259 1548 286 286 1549 278 278 1550 259 259 1551 230 230 1552 287 287 1553 259 259 1554 287 287 1555 286 286 1556 271 271 1557 288 288 1558 270 270 1559 271 271 1560 278 278 1561 288 288 1562 277 277 1563 249 249 1564 275 275 1565 277 277 1566 248 248 1567 249 249 1568 230 230 1569 252 252 1570 287 287 1571 219 219 1572 289 289 1573 290 290 1574 219 219 1575 291 291 1576 252 252 1577 219 219 1578 290 290 1579 291 291 1580 219 219 1581 220 220 1582 289 289 1583 209 209 1584 292 292 1585 293 293 1586 209 209 1587 239 239 1588 294 294 1589 209 209 1590 294 294 1591 292 292 1592 209 209 1593 293 293 1594 225 225 1595 220 220 1596 265 265 1597 289 289 1598 253 253 1599 254 254 1600 295 295 1601 253 253 1602 296 296 1603 262 262 1604 253 253 1605 295 295 1606 296 296 1607 214 214 1608 244 244 1609 297 297 1610 214 214 1611 297 297 1612 298 298 1613 214 214 1614 298 298 1615 260 260 1616 267 267 1617 268 268 1618 299 299 1619 267 267 1620 299 299 1621 300 300 1622 267 267 1623 300 300 1624 266 266 1625 245 245 1626 301 301 1627 281 281 1628 245 245 1629 256 256 1630 301 301 1631 242 242 1632 302 302 1633 243 243 1634 242 242 1635 270 270 1636 302 302 1637 258 258 1638 276 276 1639 303 303 1640 258 258 1641 303 303 1642 304 304 1643 258 258 1644 304 304 1645 282 282 1646 270 270 1647 288 288 1648 302 302 1649 272 272 1650 305 305 1651 273 273 1652 272 272 1653 279 279 1654 306 306 1655 272 272 1656 306 306 1657 305 305 1658 252 252 1659 291 291 1660 287 287 1661 226 226 1662 225 225 1663 307 307 1664 226 226 1665 307 307 1666 255 255 1667 266 266 1668 308 308 1669 264 264 1670 266 266 1671 300 300 1672 308 308 1673 260 260 1674 309 309 1675 261 261 1676 260 260 1677 298 298 1678 309 309 1679 215 215 1680 310 310 1681 311 311 1682 215 215 1683 311 311 1684 268 268 1685 215 215 1686 261 261 1687 310 310 1688 269 269 1689 312 312 1690 313 313 1691 269 269 1692 190 190 1693 312 312 1694 269 269 1695 313 313 1696 314 314 1697 269 269 1698 314 314 1699 254 254 1700 190 190 1701 315 315 1702 312 312 1703 190 190 1704 228 228 1705 315 315 1706 282 282 1707 316 316 1708 237 237 1709 282 282 1710 304 304 1711 316 316 1712 237 237 1713 316 316 1714 304 304 1715 237 237 1716 304 304 1717 279 279 1718 279 279 1719 304 304 1720 306 306 1721 251 251 1722 317 317 1723 250 250 1724 251 251 1725 283 283 1726 317 317 1727 225 225 1728 293 293 1729 307 307 1730 244 244 1731 274 274 1732 297 297 1733 278 278 1734 286 286 1735 318 318 1736 278 278 1737 318 318 1738 288 288 1739 243 243 1740 302 302 1741 319 319 1742 243 243 1743 320 320 1744 240 240 1745 243 243 1746 319 319 1747 320 320 1748 239 239 1749 240 240 1750 321 321 1751 239 239 1752 321 321 1753 322 322 1754 239 239 1755 322 322 1756 320 320 1757 239 239 1758 320 320 1759 323 323 1760 239 239 1761 323 323 1762 294 294 1763 254 254 1764 324 324 1765 295 295 1766 254 254 1767 325 325 1768 324 324 1769 254 254 1770 314 314 1771 325 325 1772 268 268 1773 311 311 1774 326 326 1775 268 268 1776 326 326 1777 299 299 1778 281 281 1779 327 327 1780 280 280 1781 281 281 1782 301 301 1783 327 327 1784 240 240 1785 320 320 1786 321 321 1787 288 288 1788 318 318 1789 328 328 1790 288 288 1791 328 328 1792 329 329 1793 288 288 1794 329 329 1795 302 302 1796 302 302 1797 330 330 1798 319 319 1799 302 302 1800 329 329 1801 330 330 1802 273 273 1803 305 305 1804 285 285 1805 274 274 1806 331 331 1807 332 332 1808 274 274 1809 284 284 1810 331 331 1811 274 274 1812 332 332 1813 297 297 1814 261 261 1815 333 333 1816 310 310 1817 261 261 1818 309 309 1819 333 333 1820 228 228 1821 334 334 1822 315 315 1823 228 228 1824 335 335 1825 334 334 1826 228 228 1827 280 280 1828 335 335 1829 318 318 1830 336 336 1831 328 328 1832 318 318 1833 286 286 1834 336 336 1835 286 286 1836 337 337 1837 336 336 1838 286 286 1839 287 287 1840 337 337 1841 249 249 1842 250 250 1843 338 338 1844 249 249 1845 338 338 1846 275 275 1847 283 283 1848 263 263 1849 339 339 1850 283 283 1851 340 340 1852 317 317 1853 283 283 1854 341 341 1855 340 340 1856 283 283 1857 339 339 1858 341 341 1859 284 284 1860 285 285 1861 342 342 1862 284 284 1863 342 342 1864 331 331 1865 264 264 1866 308 308 1867 343 343 1868 264 264 1869 343 343 1870 265 265 1871 255 255 1872 307 307 1873 344 344 1874 255 255 1875 344 344 1876 256 256 1877 256 256 1878 344 344 1879 345 345 1880 256 256 1881 346 346 1882 301 301 1883 256 256 1884 345 345 1885 346 346 1886 280 280 1887 327 327 1888 347 347 1889 280 280 1890 347 347 1891 335 335 1892 287 287 1893 291 291 1894 337 337 1895 320 320 1896 319 319 1897 323 323 1898 320 320 1899 322 322 1900 321 321 1901 291 291 1902 290 290 1903 337 337 1904 262 262 1905 296 296 1906 348 348 1907 262 262 1908 348 348 1909 263 263 1910 304 304 1911 303 303 1912 306 306 1913 329 329 1914 328 328 1915 349 349 1916 329 329 1917 350 350 1918 330 330 1919 329 329 1920 349 349 1921 350 350 1922 263 263 1923 348 348 1924 339 339 1925 295 295 1926 324 324 1927 296 296 1928 297 297 1929 351 351 1930 298 298 1931 297 297 1932 332 332 1933 352 352 1934 297 297 1935 352 352 1936 351 351 1937 301 301 1938 346 346 1939 327 327 1940 312 312 1941 315 315 1942 353 353 1943 312 312 1944 354 354 1945 313 313 1946 312 312 1947 353 353 1948 354 354 1949 328 328 1950 336 336 1951 355 355 1952 328 328 1953 356 356 1954 349 349 1955 328 328 1956 355 355 1957 356 356 1958 319 319 1959 330 330 1960 323 323 1961 250 250 1962 317 317 1963 338 338 1964 294 294 1965 357 357 1966 292 292 1967 294 294 1968 323 323 1969 357 357 1970 265 265 1971 343 343 1972 358 358 1973 265 265 1974 358 358 1975 289 289 1976 307 307 1977 293 293 1978 344 344 1979 300 300 1980 299 299 1981 359 359 1982 300 300 1983 359 359 1984 360 360 1985 300 300 1986 360 360 1987 308 308 1988 298 298 1989 361 361 1990 309 309 1991 298 298 1992 351 351 1993 361 361 1994 299 299 1995 326 326 1996 359 359 1997 336 336 1998 362 362 1999 363 363 2000 336 336 2001 337 337 2002 362 362 2003 336 336 2004 363 363 2005 355 355 2006 330 330 2007 350 350 2008 364 364 2009 330 330 2010 364 364 2011 365 365 2012 330 330 2013 365 365 2014 323 323 2015 306 306 2016 366 366 2017 367 367 2018 306 306 2019 368 368 2020 366 366 2021 306 306 2022 367 367 2023 305 305 2024 306 306 2025 369 369 2026 368 368 2027 306 306 2028 303 303 2029 369 369 2030 285 285 2031 305 305 2032 370 370 2033 285 285 2034 370 370 2035 342 342 2036 289 289 2037 358 358 2038 290 290 2039 331 331 2040 371 371 2041 332 332 2042 331 331 2043 342 342 2044 372 372 2045 331 331 2046 372 372 2047 371 371 2048 309 309 2049 373 373 2050 333 333 2051 309 309 2052 361 361 2053 373 373 2054 313 313 2055 354 354 2056 374 374 2057 313 313 2058 374 374 2059 314 314 2060 337 337 2061 290 290 2062 362 362 2063 317 317 2064 340 340 2065 338 338 2066 290 290 2067 375 375 2068 362 362 2069 290 290 2070 358 358 2071 375 375 2072 293 293 2073 292 292 2074 376 376 2075 293 293 2076 376 376 2077 344 344 2078 308 308 2079 377 377 2080 343 343 2081 308 308 2082 378 378 2083 377 377 2084 308 308 2085 360 360 2086 378 378 2087 314 314 2088 379 379 2089 325 325 2090 314 314 2091 374 374 2092 379 379 2093 315 315 2094 334 334 2095 353 353 2096 305 305 2097 367 367 2098 370 370 2099 339 339 2100 348 348 2101 380 380 2102 339 339 2103 380 380 2104 341 341 2105 292 292 2106 381 381 2107 376 376 2108 292 292 2109 357 357 2110 381 381 2111 348 348 2112 296 296 2113 380 380 2114 332 332 2115 371 371 2116 382 382 2117 332 332 2118 382 382 2119 352 352 2120 324 324 2121 325 325 2122 383 383 2123 324 324 2124 383 383 2125 296 296 2126 351 351 2127 352 352 2128 384 384 2129 351 351 2130 384 384 2131 385 385 2132 351 351 2133 385 385 2134 361 361 2135 311 311 2136 386 386 2137 387 387 2138 311 311 2139 387 387 2140 326 326 2141 311 311 2142 310 310 2143 386 386 2144 327 327 2145 346 346 2146 388 388 2147 327 327 2148 388 388 2149 347 347 2150 323 323 2151 365 365 2152 357 357 2153 296 296 2154 383 383 2155 389 389 2156 296 296 2157 389 389 2158 380 380 2159 326 326 2160 390 390 2161 359 359 2162 326 326 2163 387 387 2164 390 390 2165 347 347 2166 391 391 2167 335 335 2168 347 347 2169 388 388 2170 392 392 2171 347 347 2172 392 392 2173 391 391 2174 353 353 2175 334 334 2176 393 393 2177 353 353 2178 393 393 2179 394 394 2180 353 353 2181 394 394 2182 354 354 2183 335 335 2184 395 395 2185 396 396 2186 335 335 2187 396 396 2188 334 334 2189 335 335 2190 391 391 2191 397 397 2192 335 335 2193 397 397 2194 395 395 2195 355 355 2196 363 363 2197 398 398 2198 355 355 2199 398 398 2200 356 356 2201 350 350 2202 399 399 2203 364 364 2204 350 350 2205 349 349 2206 399 399 2207 343 343 2208 400 400 2209 401 401 2210 343 343 2211 377 377 2212 400 400 2213 343 343 2214 401 401 2215 358 358 2216 344 344 2217 402 402 2218 345 345 2219 344 344 2220 376 376 2221 403 403 2222 344 344 2223 403 403 2224 402 402 2225 325 325 2226 379 379 2227 404 404 2228 325 325 2229 404 404 2230 383 383 2231 359 359 2232 390 390 2233 360 360 2234 334 334 2235 396 396 2236 393 393 2237 340 340 2238 341 341 2239 405 405 2240 340 340 2241 405 405 2242 338 338 2243 374 374 2244 354 354 2245 406 406 2246 374 374 2247 406 406 2248 379 379 2249 361 361 2250 407 407 2251 373 373 2252 361 361 2253 385 385 2254 407 407 2255 338 338 2256 408 408 2257 409 409 2258 338 338 2259 405 405 2260 408 408 2261 338 338 2262 409 409 2263 275 275 2264 310 310 2265 333 333 2266 410 410 2267 310 310 2268 410 410 2269 386 386 2270 358 358 2271 401 401 2272 375 375 2273 357 357 2274 411 411 2275 381 381 2276 357 357 2277 365 365 2278 411 411 2279 342 342 2280 412 412 2281 372 372 2282 342 342 2283 413 413 2284 414 414 2285 342 342 2286 370 370 2287 413 413 2288 342 342 2289 414 414 2290 412 412 2291 352 352 2292 382 382 2293 415 415 2294 352 352 2295 415 415 2296 384 384 2297 346 346 2298 416 416 2299 417 417 2300 346 346 2301 345 345 2302 416 416 2303 346 346 2304 417 417 2305 388 388 2306 373 373 2307 407 407 2308 418 418 2309 373 373 2310 418 418 2311 333 333 2312 333 333 2313 418 418 2314 410 410 2315 349 349 2316 356 356 2317 419 419 2318 349 349 2319 419 419 2320 420 420 2321 349 349 2322 420 420 2323 399 399 2324 370 370 2325 367 367 2326 413 413 2327 341 341 2328 421 421 2329 405 405 2330 341 341 2331 422 422 2332 421 421 2333 341 341 2334 380 380 2335 422 422 2336 379 379 2337 406 406 2338 404 404 2339 354 354 2340 394 394 2341 406 406 2342 396 396 2343 395 395 2344 423 423 2345 396 396 2346 423 423 2347 393 393 2348 362 362 2349 375 375 2350 424 424 2351 362 362 2352 424 424 2353 363 363 2354 367 367 2355 366 366 2356 413 413 2357 364 364 2358 425 425 2359 365 365 2360 364 364 2361 399 399 2362 426 426 2363 364 364 2364 426 426 2365 425 425 2366 371 371 2367 427 427 2368 382 382 2369 371 371 2370 372 372 2371 427 427 2372 377 377 2373 378 378 2374 400 400 2375 345 345 2376 402 402 2377 416 416 2378 390 390 2379 428 428 2380 429 429 2381 390 390 2382 429 429 2383 360 360 2384 390 390 2385 387 387 2386 428 428 2387 388 388 2388 430 430 2389 392 392 2390 388 388 2391 417 417 2392 430 430 2393 386 386 2394 431 431 2395 432 432 2396 386 386 2397 432 432 2398 387 387 2399 386 386 2400 433 433 2401 431 431 2402 386 386 2403 410 410 2404 433 433 2405 356 356 2406 398 398 2407 419 419 2408 405 405 2409 421 421 2410 408 408 2411 372 372 2412 412 412 2413 434 434 2414 372 372 2415 434 434 2416 427 427 2417 380 380 2418 389 389 2419 422 422 2420 360 360 2421 435 435 2422 378 378 2423 360 360 2424 429 429 2425 435 435 2426 387 387 2427 432 432 2428 436 436 2429 387 387 2430 436 436 2431 428 428 2432 394 394 2433 437 437 2434 406 406 2435 394 394 2436 393 393 2437 438 438 2438 394 394 2439 438 438 2440 437 437 2441 410 410 2442 439 439 2443 440 440 2444 410 410 2445 440 440 2446 433 433 2447 410 410 2448 418 418 2449 439 439 2450 393 393 2451 423 423 2452 438 438 2453 381 381 2454 411 411 2455 441 441 2456 381 381 2457 441 441 2458 376 376 2459 402 402 2460 403 403 2461 442 442 2462 402 402 2463 442 442 2464 416 416 2465 383 383 2466 443 443 2467 444 444 2468 383 383 2469 444 444 2470 389 389 2471 383 383 2472 404 404 2473 443 443 2474 404 404 2475 406 406 2476 445 445 2477 404 404 2478 445 445 2479 443 443 2480 407 407 2481 446 446 2482 418 418 2483 407 407 2484 447 447 2485 446 446 2486 407 407 2487 385 385 2488 447 447 2489 395 395 2490 448 448 2491 423 423 2492 395 395 2493 397 397 2494 449 449 2495 395 395 2496 449 449 2497 448 448 2498 391 391 2499 450 450 2500 397 397 2501 391 391 2502 451 451 2503 450 450 2504 391 391 2505 392 392 2506 451 451 2507 366 366 2508 368 368 2509 413 413 2510 375 375 2511 401 401 2512 424 424 2513 382 382 2514 427 427 2515 415 415 2516 384 384 2517 452 452 2518 453 453 2519 384 384 2520 453 453 2521 385 385 2522 384 384 2523 415 415 2524 452 452 2525 385 385 2526 453 453 2527 447 447 2528 431 431 2529 454 454 2530 455 455 2531 431 431 2532 455 455 2533 456 456 2534 431 431 2535 433 433 2536 454 454 2537 431 431 2538 456 456 2539 432 432 2540 397 397 2541 450 450 2542 457 457 2543 397 397 2544 457 457 2545 449 449 2546 399 399 2547 420 420 2548 426 426 2549 365 365 2550 425 425 2551 411 411 2552 401 401 2553 400 400 2554 424 424 2555 376 376 2556 441 441 2557 403 403 2558 427 427 2559 458 458 2560 415 415 2561 427 427 2562 434 434 2563 458 458 2564 406 406 2565 437 437 2566 445 445 2567 392 392 2568 430 430 2569 451 451 2570 418 418 2571 446 446 2572 439 439 2573 423 423 2574 448 448 2575 438 438 2576 432 432 2577 456 456 2578 459 459 2579 432 432 2580 459 459 2581 436 436 2582 433 433 2583 440 440 2584 454 454 2585 450 450 2586 451 451 2587 460 460 2588 450 450 2589 460 460 2590 461 461 2591 450 450 2592 461 461 2593 457 457 2594 363 363 2595 462 462 2596 398 398 2597 363 363 2598 424 424 2599 462 462 2600 428 428 2601 436 436 2602 463 463 2603 428 428 2604 463 463 2605 429 429 2606 411 411 2607 425 425 2608 441 441 2609 378 378 2610 435 435 2611 464 464 2612 378 378 2613 464 464 2614 400 400 2615 455 455 2616 465 465 2617 466 466 2618 455 455 2619 454 454 2620 465 465 2621 455 455 2622 466 466 2623 456 456 2624 451 451 2625 430 430 2626 467 467 2627 451 451 2628 467 467 2629 460 460 2630 439 439 2631 468 468 2632 469 469 2633 439 439 2634 446 446 2635 468 468 2636 439 439 2637 469 469 2638 440 440 2639 454 454 2640 440 440 2641 470 470 2642 454 454 2643 470 470 2644 465 465 2645 413 413 2646 368 368 2647 414 414 2648 471 471 2649 421 421 2650 472 472 2651 421 421 2652 473 473 2653 472 472 2654 421 421 2655 471 471 2656 408 408 2657 421 421 2658 422 422 2659 474 474 2660 421 421 2661 474 474 2662 473 473 2663 400 400 2664 464 464 2665 424 424 2666 422 422 2667 389 389 2668 475 475 2669 422 422 2670 475 475 2671 474 474 2672 429 429 2673 476 476 2674 435 435 2675 429 429 2676 463 463 2677 476 476 2678 448 448 2679 449 449 2680 477 477 2681 448 448 2682 478 478 2683 438 438 2684 448 448 2685 477 477 2686 478 478 2687 449 449 2688 457 457 2689 479 479 2690 449 449 2691 479 479 2692 480 480 2693 449 449 2694 480 480 2695 477 477 2696 447 447 2697 481 481 2698 446 446 2699 447 447 2700 453 453 2701 481 481 2702 446 446 2703 481 481 2704 468 468 2705 456 456 2706 482 482 2707 459 459 2708 456 456 2709 466 466 2710 482 482 2711 457 457 2712 483 483 2713 479 479 2714 457 457 2715 461 461 2716 484 484 2717 457 457 2718 484 484 2719 483 483 2720 403 403 2721 485 485 2722 442 442 2723 403 403 2724 486 486 2725 485 485 2726 403 403 2727 441 441 2728 486 486 2729 389 389 2730 487 487 2731 475 475 2732 389 389 2733 444 444 2734 487 487 2735 453 453 2736 452 452 2737 488 488 2738 453 453 2739 488 488 2740 481 481 2741 430 430 2742 489 489 2743 467 467 2744 430 430 2745 417 417 2746 489 489 2747 438 438 2748 478 478 2749 437 437 2750 440 440 2751 490 490 2752 470 470 2753 440 440 2754 469 469 2755 490 490 2756 483 483 2757 465 465 2758 479 479 2759 483 483 2760 484 484 2761 465 465 2762 477 477 2763 491 491 2764 478 478 2765 477 477 2766 480 480 2767 491 491 2768 424 424 2769 464 464 2770 462 462 2771 414 414 2772 492 492 2773 493 493 2774 414 414 2775 493 493 2776 412 412 2777 414 414 2778 368 368 2779 492 492 2780 412 412 2781 494 494 2782 458 458 2783 412 412 2784 458 458 2785 434 434 2786 412 412 2787 493 493 2788 494 494 2789 415 415 2790 495 495 2791 452 452 2792 415 415 2793 458 458 2794 495 495 2795 435 435 2796 496 496 2797 464 464 2798 435 435 2799 476 476 2800 496 496 2801 416 416 2802 497 497 2803 417 417 2804 416 416 2805 442 442 2806 497 497 2807 437 437 2808 498 498 2809 445 445 2810 437 437 2811 478 478 2812 498 498 2813 460 460 2814 467 467 2815 499 499 2816 460 460 2817 499 499 2818 461 461 2819 466 466 2820 500 500 2821 501 501 2822 466 466 2823 501 501 2824 482 482 2825 466 466 2826 465 465 2827 500 500 2828 465 465 2829 470 470 2830 479 479 2831 465 465 2832 484 484 2833 500 500 2834 479 479 2835 470 470 2836 480 480 2837 368 368 2838 369 369 2839 492 492 2840 398 398 2841 502 502 2842 503 503 2843 398 398 2844 462 462 2845 502 502 2846 398 398 2847 503 503 2848 419 419 2849 419 419 2850 504 504 2851 420 420 2852 419 419 2853 503 503 2854 504 504 2855 441 441 2856 425 425 2857 486 486 2858 443 443 2859 505 505 2860 444 444 2861 443 443 2862 506 506 2863 505 505 2864 443 443 2865 445 445 2866 506 506 2867 452 452 2868 507 507 2869 488 488 2870 452 452 2871 495 495 2872 507 507 2873 470 470 2874 490 490 2875 508 508 2876 470 470 2877 508 508 2878 480 480 2879 445 445 2880 498 498 2881 506 506 2882 467 467 2883 509 509 2884 499 499 2885 467 467 2886 489 489 2887 509 509 2888 481 481 2889 510 510 2890 468 468 2891 481 481 2892 488 488 2893 510 510 2894 459 459 2895 463 463 2896 436 436 2897 459 459 2898 511 511 2899 463 463 2900 459 459 2901 482 482 2902 511 511 2903 425 425 2904 512 512 2905 486 486 2906 425 425 2907 426 426 2908 512 512 2909 417 417 2910 497 497 2911 489 489 2912 463 463 2913 511 511 2914 513 513 2915 463 463 2916 513 513 2917 476 476 2918 461 461 2919 514 514 2920 484 484 2921 461 461 2922 499 499 2923 514 514 2924 484 484 2925 514 514 2926 500 500 2927 490 490 2928 469 469 2929 515 515 2930 490 490 2931 515 515 2932 508 508 2933 480 480 2934 516 516 2935 491 491 2936 480 480 2937 508 508 2938 516 516 2939 458 458 2940 517 517 2941 518 518 2942 458 458 2943 494 494 2944 517 517 2945 458 458 2946 518 518 2947 519 519 2948 458 458 2949 519 519 2950 495 495 2951 444 444 2952 520 520 2953 487 487 2954 444 444 2955 505 505 2956 520 520 2957 495 495 2958 519 519 2959 507 507 2960 489 489 2961 521 521 2962 509 509 2963 489 489 2964 497 497 2965 521 521 2966 468 468 2967 510 510 2968 522 522 2969 468 468 2970 522 522 2971 469 469 2972 482 482 2973 501 501 2974 523 523 2975 482 482 2976 523 523 2977 511 511 2978 478 478 2979 524 524 2980 525 525 2981 478 478 2982 525 525 2983 498 498 2984 478 478 2985 491 491 2986 524 524 2987 469 469 2988 522 522 2989 515 515 2990 500 500 2991 526 526 2992 501 501 2993 500 500 2994 514 514 2995 526 526 2996 508 508 2997 515 515 2998 516 516 2999 462 462 3000 527 527 3001 502 502 3002 462 462 3003 464 464 3004 527 527 3005 474 474 3006 528 528 3007 473 473 3008 474 474 3009 475 475 3010 528 528 3011 442 442 3012 485 485 3013 497 497 3014 499 499 3015 509 509 3016 529 529 3017 499 499 3018 529 529 3019 514 514 3020 501 501 3021 526 526 3022 523 523 3023 491 491 3024 530 530 3025 524 524 3026 491 491 3027 515 515 3028 530 530 3029 491 491 3030 516 516 3031 515 515 3032 472 472 3033 473 473 3034 471 471 3035 473 473 3036 408 408 3037 471 471 3038 473 473 3039 409 409 3040 408 408 3041 473 473 3042 528 528 3043 409 409 3044 485 485 3045 486 486 3046 531 531 3047 485 485 3048 531 531 3049 532 532 3050 485 485 3051 532 532 3052 533 533 3053 485 485 3054 533 533 3055 497 497 3056 476 476 3057 534 534 3058 496 496 3059 476 476 3060 513 513 3061 534 534 3062 487 487 3063 535 535 3064 536 536 3065 487 487 3066 536 536 3067 475 475 3068 487 487 3069 520 520 3070 535 535 3071 497 497 3072 537 537 3073 521 521 3074 497 497 3075 533 533 3076 537 537 3077 511 511 3078 523 523 3079 538 538 3080 511 511 3081 538 538 3082 513 513 3083 492 492 3084 539 539 3085 493 493 3086 492 492 3087 540 540 3088 539 539 3089 492 492 3090 369 369 3091 540 540 3092 475 475 3093 536 536 3094 528 528 3095 507 507 3096 519 519 3097 541 541 3098 507 507 3099 542 542 3100 488 488 3101 507 507 3102 541 541 3103 542 542 3104 505 505 3105 543 543 3106 520 520 3107 505 505 3108 506 506 3109 543 543 3110 498 498 3111 544 544 3112 506 506 3113 498 498 3114 525 525 3115 544 544 3116 510 510 3117 545 545 3118 546 546 3119 510 510 3120 546 546 3121 522 522 3122 510 510 3123 547 547 3124 545 545 3125 510 510 3126 488 488 3127 547 547 3128 523 523 3129 526 526 3130 548 548 3131 523 523 3132 548 548 3133 538 538 3134 514 514 3135 549 549 3136 526 526 3137 514 514 3138 529 529 3139 549 549 3140 515 515 3141 546 546 3142 530 530 3143 515 515 3144 522 522 3145 546 546 3146 420 420 3147 504 504 3148 426 426 3149 464 464 3150 550 550 3151 527 527 3152 464 464 3153 496 496 3154 550 550 3155 493 493 3156 539 539 3157 494 494 3158 488 488 3159 542 542 3160 547 547 3161 506 506 3162 551 551 3163 543 543 3164 506 506 3165 544 544 3166 551 551 3167 526 526 3168 549 549 3169 548 548 3170 486 486 3171 512 512 3172 531 531 3173 519 519 3174 518 518 3175 552 552 3176 519 519 3177 552 552 3178 541 541 3179 520 520 3180 543 543 3181 535 535 3182 513 513 3183 553 553 3184 534 534 3185 513 513 3186 538 538 3187 554 554 3188 513 513 3189 554 554 3190 553 553 3191 524 524 3192 555 555 3193 556 556 3194 524 524 3195 556 556 3196 525 525 3197 524 524 3198 530 530 3199 557 557 3200 524 524 3201 557 557 3202 555 555 3203 369 369 3204 303 303 3205 558 558 3206 369 369 3207 559 559 3208 540 540 3209 369 369 3210 560 560 3211 559 559 3212 369 369 3213 558 558 3214 560 560 3215 494 494 3216 561 561 3217 562 562 3218 494 494 3219 562 562 3220 517 517 3221 494 494 3222 539 539 3223 561 561 3224 496 496 3225 534 534 3226 550 550 3227 509 509 3228 521 521 3229 563 563 3230 509 509 3231 563 563 3232 564 564 3233 509 509 3234 564 564 3235 529 529 3236 525 525 3237 556 556 3238 544 544 3239 545 545 3240 565 565 3241 546 546 3242 545 545 3243 566 566 3244 565 565 3245 545 545 3246 542 542 3247 566 566 3248 545 545 3249 547 547 3250 542 542 3251 546 546 3252 565 565 3253 530 530 3254 530 530 3255 565 565 3256 557 557 3257 426 426 3258 504 504 3259 567 567 3260 426 426 3261 567 567 3262 512 512 3263 528 528 3264 536 536 3265 568 568 3266 528 528 3267 568 568 3268 569 569 3269 570 570 3270 528 528 3271 569 569 3272 528 528 3273 570 570 3274 409 409 3275 517 517 3276 552 552 3277 518 518 3278 517 517 3279 562 562 3280 552 552 3281 529 529 3282 564 564 3283 549 549 3284 548 548 3285 554 554 3286 538 538 3287 548 548 3288 549 549 3289 554 554 3290 549 549 3291 571 571 3292 554 554 3293 549 549 3294 564 564 3295 571 571 3296 539 539 3297 572 572 3298 561 561 3299 539 539 3300 540 540 3301 572 572 3302 536 536 3303 573 573 3304 568 568 3305 536 536 3306 535 535 3307 573 573 3308 535 535 3309 543 543 3310 551 551 3311 535 535 3312 551 551 3313 573 573 3314 534 534 3315 553 553 3316 550 550 3317 521 521 3318 537 537 3319 563 563 3320 544 544 3321 556 556 3322 574 574 3323 544 544 3324 574 574 3325 551 551 3326 565 565 3327 566 566 3328 557 557 3329 512 512 3330 567 567 3331 531 531 3332 533 533 3333 532 532 3334 537 537 3335 552 552 3336 575 575 3337 541 541 3338 552 552 3339 576 576 3340 575 575 3341 552 552 3342 562 562 3343 576 576 3344 541 541 3345 575 575 3346 577 577 3347 541 541 3348 577 577 3349 542 542 3350 542 542 3351 577 577 3352 566 566 3353 557 557 3354 566 566 3355 555 555 3356 527 527 3357 578 578 3358 502 502 3359 527 527 3360 550 550 3361 578 578 3362 502 502 3363 578 578 3364 503 503 3365 503 503 3366 579 579 3367 580 580 3368 503 503 3369 578 578 3370 579 579 3371 503 503 3372 580 580 3373 504 504 3374 556 556 3375 581 581 3376 574 574 3377 556 556 3378 555 555 3379 581 581 3380 555 555 3381 566 566 3382 581 581 3383 540 540 3384 559 559 3385 572 572 3386 550 550 3387 582 582 3388 578 578 3389 550 550 3390 553 553 3391 582 582 3392 531 531 3393 567 567 3394 532 532 3395 554 554 3396 571 571 3397 583 583 3398 554 554 3399 583 583 3400 553 553 3401 551 551 3402 584 584 3403 585 585 3404 551 551 3405 574 574 3406 584 584 3407 551 551 3408 585 585 3409 570 570 3410 551 551 3411 570 570 3412 573 573 3413 564 564 3414 586 586 3415 571 571 3416 564 564 3417 563 563 3418 586 586 3419 566 566 3420 587 587 3421 581 581 3422 566 566 3423 588 588 3424 587 587 3425 566 566 3426 577 577 3427 588 588 3428 504 504 3429 589 589 3430 567 567 3431 504 504 3432 580 580 3433 589 589 3434 562 562 3435 561 561 3436 590 590 3437 562 562 3438 590 590 3439 576 576 3440 575 575 3441 576 576 3442 577 577 3443 563 563 3444 591 591 3445 586 586 3446 563 563 3447 537 537 3448 591 591 3449 571 571 3450 586 586 3451 583 583 3452 561 561 3453 559 559 3454 590 590 3455 561 561 3456 572 572 3457 559 559 3458 568 568 3459 570 570 3460 569 569 3461 568 568 3462 573 573 3463 570 570 3464 532 532 3465 591 591 3466 537 537 3467 532 532 3468 567 567 3469 591 591 3470 577 577 3471 576 576 3472 588 588 3473 567 567 3474 589 589 3475 591 591 3476 553 553 3477 592 592 3478 582 582 3479 553 553 3480 583 583 3481 592 592 3482 576 576 3483 590 590 3484 588 588 3485 574 574 3486 581 581 3487 584 584 3488 581 581 3489 587 587 3490 584 584 3491 578 578 3492 582 582 3493 579 579 3494 582 582 3495 592 592 3496 579 579 3497 586 586 3498 593 593 3499 579 579 3500 586 586 3501 579 579 3502 583 583 3503 586 586 3504 591 591 3505 593 593 3506 588 588 3507 590 590 3508 594 594 3509 588 588 3510 594 594 3511 587 587 3512 591 591 3513 589 589 3514 593 593 3515 583 583 3516 579 579 3517 592 592 3518 584 584 3519 595 595 3520 585 585 3521 584 584 3522 587 587 3523 595 595 3524 587 587 3525 596 596 3526 595 595 3527 587 587 3528 594 594 3529 596 596 3530 590 590 3531 597 597 3532 594 594 3533 590 590 3534 559 559 3535 598 598 3536 590 590 3537 598 598 3538 597 597 3539 559 559 3540 560 560 3541 598 598 3542 589 589 3543 580 580 3544 593 593 3545 570 570 3546 599 599 3547 600 600 3548 570 570 3549 600 600 3550 409 409 3551 570 570 3552 585 585 3553 599 599 3554 579 579 3555 593 593 3556 580 580 3557 594 594 3558 597 597 3559 596 596 3560 585 585 3561 601 601 3562 599 599 3563 585 585 3564 595 595 3565 601 601 3566 596 596 3567 597 597 3568 560 560 3569 596 596 3570 560 560 3571 595 595 3572 595 595 3573 560 560 3574 601 601 3575 599 599 3576 601 601 3577 560 560 3578 599 599 3579 560 560 3580 600 600 3581 560 560 3582 558 558 3583 600 600 3584 560 560 3585 597 597 3586 598 598 3587 275 602 3588 409 602 3589 276 602 3590 276 603 3591 409 603 3592 600 603 3593 276 604 3594 600 604 3595 558 604 3596 276 605 3597 558 605 3598 303 605 3599

-
-
-
-
- - - - - 0.6858805 -0.3173701 0.6548619 7.481132 0.7276338 0.3124686 -0.6106656 -6.50764 -0.01081678 0.8953432 0.4452454 5.343665 0 0 0 1 - - - - -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 - - - - 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 - - - - - - - - - - - - 0.001 0 0 0 0 -1.62921e-10 -0.001 0 0 0.001 -1.62921e-10 0 0 0 0 1 - - - - - - -
diff --git a/cram_boxy/cram_boxy_assembly_demo/resource/fork.dae b/cram_boxy/cram_boxy_assembly_demo/resource/fork.dae deleted file mode 100644 index 807f8b2a3b..0000000000 --- a/cram_boxy/cram_boxy_assembly_demo/resource/fork.dae +++ /dev/null @@ -1,304 +0,0 @@ - - - - - Blender User - Blender 2.77.0 commit date:2016-04-05, commit time:18:12, hash:abf6f08 - - 2016-09-03T13:56:49 - 2016-09-03T13:56:49 - - Z_UP - - - - - - - 49.13434 - 1.777778 - 0.1 - 100 - - - - - - 0 - 0 - 0 - - - - - - - - 49.13434 - 1.777778 - 0.1 - 100 - - - - - - 0 - 0 - 0 - - - - - - - - - 1 1 1 - 1 - 0 - 0.00111109 - - - - - 0.000999987 - 1 - 0.1 - 0.1 - 1 - 1 - 1 - 2 - 0 - 1 - 1 - 1 - 1 - 1 - 0 - 2880 - 2 - 30.002 - 1.000799 - 0.04999995 - 29.99998 - 1 - 2 - 0 - 0 - 1 - 1 - 1 - 1 - 8192 - 1 - 1 - 0 - 1 - 1 - 1 - 3 - 0 - 0 - 0 - 0 - 0 - 1 - 1 - 1 - 3 - 0.15 - 75 - 1 - 1 - 0 - 1 - 1 - 0 - - - - - - - 1 1 1 - 1 - 0 - 0.00111109 - - - - - 9.99987e-4 - 1 - 0.1 - 0.1 - 1 - 1 - 1 - 2 - 0 - 1 - 1 - 1 - 1 - 1 - 0 - 2880 - 2 - 30.002 - 1.000799 - 0.04999995 - 29.99998 - 1 - 2 - 0 - 0 - 1 - 1 - 1 - 1 - 8192 - 1 - 1 - 0 - 1 - 1 - 1 - 3 - 0 - 0 - 0 - 0 - 0 - 1 - 1 - 1 - 3 - 0.15 - 75 - 1 - 1 - 0 - 1 - 1 - 0 - - - - - - - - - - - - 0 0 0 1 - - - 0 0 0 1 - - - 0.04899684 0.0305635 0.6392822 1 - - - 0.0625 0.0625 0.0625 1 - - - 50 - - - 1 - - - - - - - - - - - - - - - - 0.001184046 -0.01644086 -0.003835499 0.00413382 -0.01628756 -0.003832757 0.00413084 -0.01644086 -0.003835499 0.001181066 -0.01628756 -0.003832757 0.001135945 -0.01598632 -0.003827214 0.004178822 -0.01598632 -0.003827214 0.001015245 -0.01570665 -0.003822088 0.004299461 -0.01570665 -0.003822088 0.004366695 -0.01562106 -0.003820538 9.48084e-4 -0.01562106 -0.003820538 -0.009448766 -0.01480257 -0.003771722 -0.006262958 -0.01562106 -0.003820538 -0.009448766 -0.01562106 -0.003820538 -0.006142079 -0.01546704 -0.003811299 -0.005898952 -0.01528358 -0.003800392 -0.005617022 -0.01516842 -0.003793537 -0.005314946 -0.0151292 -0.003791153 0 -0.0151292 -0.003791153 0.005314767 -0.0151292 -0.003791153 0.006262958 -0.01562106 -0.003820538 0.009448766 -0.01480257 -0.003771722 0.009448766 -0.01562106 -0.003820538 0.00614202 -0.01546704 -0.003811299 0.005898952 -0.01528358 -0.003800392 0.005616843 -0.01516842 -0.003793537 8.27142e-4 -0.01546704 -0.003811299 0.004487693 -0.01546704 -0.003811299 0.00473082 -0.01528358 -0.003800392 5.83998e-4 -0.01528358 -0.003800392 3.02028e-4 -0.01516842 -0.003793537 0.00501281 -0.01516842 -0.003793537 -0.004366695 -0.01562106 -0.003820538 -8.27182e-4 -0.01546704 -0.003811299 -9.48128e-4 -0.01562106 -0.003820538 -0.004487693 -0.01546704 -0.003811299 -0.00473088 -0.01528358 -0.003800392 -5.8404e-4 -0.01528358 -0.003800392 -0.00501281 -0.01516842 -0.003793537 -3.02072e-4 -0.01516842 -0.003793537 0.004299461 -0.01570665 -0.002245724 0.004366636 -0.01562118 -0.002244055 0.004487693 -0.01546704 -0.002234578 0.004178822 -0.01598632 -0.002251446 0.00413382 -0.01628756 -0.002257645 0.004078209 -0.01914215 -0.003829598 0.004025757 -0.02184152 -0.003724753 0.003973305 -0.02453523 -0.003521263 0.003921091 -0.02721971 -0.003219425 0.003869235 -0.02989131 -0.002819776 0.00413084 -0.01644086 -0.002260804 0.003817617 -0.03254657 -0.002322494 0.004078447 -0.01913022 -0.002217829 0.003766357 -0.03518193 -0.001728594 0.004026234 -0.0218169 -0.002089262 0.00397408 -0.0244981 -0.001875042 0.003922045 -0.02717107 -0.00157541 0.003715634 -0.03779369 -0.00103867 0.003870368 -0.02983313 -0.001190662 0.003818809 -0.03248161 -7.21216e-4 0.003665328 -0.04037851 -2.5371e-4 0.003767669 -0.03511375 -1.67541e-4 0.003615558 -0.04293292 6.2527e-4 0.003716886 -0.03772693 4.69788e-4 0.00366652 -0.04031842 0.001190125 0.003566563 -0.04545348 0.001597046 0.003616511 -0.04288566 0.001992702 0.003518283 -0.04793673 0.002660334 0.003567159 -0.04542595 0.002876758 0.003444731 -0.05172055 0.004363 0.003518283 -0.04793673 0.0038414 0.003444731 -0.05172055 0.005165696 0.001236557 -0.01914215 -0.003829598 0.001497209 -0.03254657 -0.002322494 0.001236319 -0.01913022 -0.002217829 0.001184046 -0.01644086 -0.002260804 0.001548469 -0.03518193 -0.001728594 0.001288592 -0.0218169 -0.002089262 0.001340687 -0.0244981 -0.001875042 0.001392662 -0.02717107 -0.00157541 0.001599252 -0.03779369 -0.00103867 0.001444458 -0.02983313 -0.001190662 0.001495957 -0.03248161 -7.21216e-4 0.001649498 -0.04037851 -2.5371e-4 0.001547098 -0.03511375 -1.67541e-4 0.001699149 -0.04293292 6.2527e-4 0.00159794 -0.03772693 4.69788e-4 0.001648306 -0.04031842 0.001190125 0.001748144 -0.04545348 0.001597046 0.001698255 -0.04288566 0.001992702 0.001796483 -0.04793673 0.002660334 0.001747608 -0.04542595 0.002876758 0.001870036 -0.05172055 0.004363 0.001796483 -0.04793673 0.0038414 0.001870036 -0.05172055 0.005165696 0.001181066 -0.01628756 -0.002257645 0.001289069 -0.02184152 -0.003724753 0.001341402 -0.02453523 -0.003521263 0.001393616 -0.02721971 -0.003219425 0.001445591 -0.02989131 -0.002819776 0.001135945 -0.01598632 -0.002251446 0.001015245 -0.01570665 -0.002245724 9.4823e-4 -0.01562118 -0.002244055 8.27142e-4 -0.01546704 -0.002234578 0.006498873 -0.01644086 -0.003835499 0.009448766 -0.01628756 -0.003832757 0.009445786 -0.01644086 -0.003835499 0.006495952 -0.01628756 -0.003832757 0.006450831 -0.01598632 -0.003827214 0.006330132 -0.01570665 -0.003822088 0.006330132 -0.01570665 -0.002245724 0.006263077 -0.01562118 -0.002244055 0.00614202 -0.01546704 -0.002234578 0.005898952 -0.01528358 -0.002223372 0.005616843 -0.01516842 -0.002216279 0.005314767 -0.0151292 -0.002213776 0.00501281 -0.01516842 -0.002216279 0.00473082 -0.01528358 -0.002223372 5.83998e-4 -0.01528358 -0.002223372 3.02028e-4 -0.01516842 -0.002216279 0 -0.0151292 -0.002213776 -3.02072e-4 -0.01516842 -0.002216279 -5.84042e-4 -0.01528358 -0.002223372 -8.27182e-4 -0.01546704 -0.002234578 -0.001015305 -0.01570665 -0.002245724 -0.001015305 -0.01570665 -0.003822088 -9.4827e-4 -0.01562118 -0.002244055 -0.00413382 -0.01628756 -0.003832757 -0.001184046 -0.01644086 -0.003835499 -0.00413084 -0.01644086 -0.003835499 -0.001181066 -0.01628756 -0.003832757 -0.001135945 -0.01598632 -0.003827214 -0.004178941 -0.01598632 -0.003827214 -0.00429964 -0.01570665 -0.003822088 -0.00429964 -0.01570665 -0.002245724 -0.004366636 -0.01562118 -0.002244055 -0.004487693 -0.01546704 -0.002234578 -0.00473088 -0.01528358 -0.002223372 -0.00501281 -0.01516842 -0.002216279 -0.005314946 -0.0151292 -0.002213776 -0.005617022 -0.01516842 -0.002216279 -0.005898952 -0.01528358 -0.002223372 -0.006142079 -0.01546704 -0.002234578 -0.006330192 -0.01570665 -0.002245724 -0.006330192 -0.01570665 -0.003822088 -0.006263077 -0.01562118 -0.002244055 -0.009448766 -0.01628756 -0.003832757 -0.006499052 -0.01644086 -0.003835499 -0.009445786 -0.01644086 -0.003835499 -0.006496012 -0.01628756 -0.003832757 -0.006450831 -0.01598632 -0.003827214 -0.009448766 -0.01628756 -0.002257645 -0.009448766 -0.01398682 -0.003689229 -0.009448766 -0.01317524 -0.003573119 -0.009448766 -0.01236903 -0.003423869 -0.009448766 -0.01156961 -0.00324136 -0.009448766 -0.01077854 -0.003026187 -0.009448766 -0.009996891 -0.002778589 -0.009448766 -0.009226024 -0.002499043 -0.009448766 -0.008467555 -0.002187907 -0.009448766 -0.01562118 -0.002244055 -0.009448766 -0.01480305 -0.002193868 -0.009448766 -0.01398754 -0.002110362 -0.009448766 -0.007722318 -0.001845896 -0.009448766 -0.01317608 -0.001993656 -0.009448766 -0.01237022 -0.001843869 -0.009448766 -0.006991982 -0.001473426 -0.009448766 -0.01157104 -0.0016613 -0.009448766 -0.01077997 -0.001446306 -0.009448766 -0.006838619 -0.001396775 -0.009448766 -0.009998261 -0.001199185 -0.009448766 -0.009227514 -9.20404e-4 -0.009448766 -0.008468568 -6.1035e-4 -0.009448766 -0.007723033 -2.6958e-4 -0.009448766 -0.006838619 1.77994e-4 -0.009448766 -0.006991982 1.01342e-4 0.009448766 -0.01398682 -0.003689229 0.009448766 -0.01628756 -0.002257645 0.009448766 -0.01317524 -0.003573119 0.009448766 -0.01236903 -0.003423869 0.009448766 -0.01156961 -0.00324136 0.009448766 -0.01077854 -0.003026187 0.009448766 -0.009996891 -0.002778589 0.009448766 -0.009226024 -0.002499043 0.009448766 -0.008467555 -0.002187907 0.009448766 -0.01562118 -0.002244055 0.009448766 -0.01480305 -0.002193868 0.009448766 -0.01398754 -0.002110362 0.009448766 -0.007722318 -0.001845896 0.009448766 -0.01317608 -0.001993656 0.009448766 -0.01237022 -0.001843869 0.009448766 -0.006991982 -0.001473426 0.009448766 -0.01157104 -0.0016613 0.009448766 -0.01077997 -0.001446306 0.009448766 -0.006838619 -0.001396775 0.009448766 -0.009998261 -0.001199185 0.009448766 -0.009227514 -9.20404e-4 0.009448766 -0.008468568 -6.1035e-4 0.009448766 -0.007723033 -2.6958e-4 0.009448766 -0.006838619 1.77994e-4 0.009448766 -0.006991982 1.01342e-4 0.003414154 -0.05187392 0.00521934 0.001900672 -0.05187392 0.00521934 0.003414154 -0.05187392 0.004431903 0.002657353 -0.05565744 0.006400406 0.001900672 -0.05187392 0.004431903 0.006551504 -0.01914215 -0.003829598 0.009393215 -0.01914215 -0.003829598 0.006812036 -0.03254657 -0.002322494 0.006551206 -0.01913022 -0.002217829 0.006498873 -0.01644086 -0.002260804 0.006863296 -0.03518193 -0.001728594 0.006603419 -0.0218169 -0.002089262 0.006655514 -0.0244981 -0.001875042 0.006707489 -0.02717107 -0.00157541 0.006914079 -0.03779369 -0.00103867 0.006759345 -0.02983313 -0.001190662 0.006810843 -0.03248161 -7.21216e-4 0.006964385 -0.04037851 -2.5371e-4 0.006862044 -0.03511375 -1.67541e-4 0.007014036 -0.04293292 6.2527e-4 0.006912767 -0.03772693 4.69788e-4 0.006963193 -0.04031842 0.001190125 0.00706315 -0.04545348 0.001597046 0.007013142 -0.04288566 0.001992702 0.00711143 -0.04793673 0.002660334 0.007062554 -0.04542595 0.002876758 0.007184982 -0.05172055 0.004363 0.00711143 -0.04793673 0.0038414 0.007184982 -0.05172055 0.005165696 0.006495952 -0.01628756 -0.002257645 0.006603956 -0.02184152 -0.003724753 0.006656408 -0.02453523 -0.003521263 0.006708443 -0.02721971 -0.003219425 0.006760478 -0.02989131 -0.002819776 0.006450831 -0.01598632 -0.002251446 0.009340763 -0.02184152 -0.003724753 0.009288311 -0.02453523 -0.003521263 0.009236216 -0.02721971 -0.003219425 0.009184241 -0.02989131 -0.002819776 0.009445786 -0.01644086 -0.002260804 0.009132564 -0.03254657 -0.002322494 0.009393393 -0.01913022 -0.002217829 0.009081304 -0.03518193 -0.001728594 0.00934118 -0.0218169 -0.002089262 0.009289026 -0.0244981 -0.001875042 0.009237051 -0.02717107 -0.00157541 0.00903058 -0.03779369 -0.00103867 0.009185314 -0.02983313 -0.001190662 0.009133756 -0.03248161 -7.21216e-4 0.008980274 -0.04037851 -2.5371e-4 0.009082674 -0.03511375 -1.67541e-4 0.008930683 -0.04293292 6.2527e-4 0.009031832 -0.03772693 4.69788e-4 0.008981466 -0.04031842 0.001190125 0.008881568 -0.04545348 0.001597046 0.008931457 -0.04288566 0.001992702 0.008833289 -0.04793673 0.002660334 0.008882164 -0.04542595 0.002876758 0.008759737 -0.05172055 0.004363 0.008833289 -0.04793673 0.0038414 0.008759737 -0.05172055 0.005165696 -0.001184046 -0.01644086 -0.002260804 -0.00413382 -0.01628756 -0.002257645 -0.00413084 -0.01644086 -0.002260804 -0.001181066 -0.01628756 -0.002257645 -0.004178941 -0.01598632 -0.002251446 -0.001135945 -0.01598632 -0.002251446 -0.001236617 -0.01914215 -0.003829598 -0.001289069 -0.02184152 -0.003724753 -0.001341462 -0.02453523 -0.003521263 -0.001393675 -0.02721971 -0.003219425 -0.001445591 -0.02989131 -0.002819776 -0.001497268 -0.03254657 -0.002322494 -0.001236379 -0.01913022 -0.002217829 -0.001548469 -0.03518193 -0.001728594 -0.001288592 -0.0218169 -0.002089262 -0.001340746 -0.0244981 -0.001875042 -0.001392722 -0.02717107 -0.00157541 -0.001599252 -0.03779369 -0.00103867 -0.001444458 -0.02983313 -0.001190662 -0.001495957 -0.03248161 -7.21216e-4 -0.001649498 -0.04037851 -2.5371e-4 -0.001547157 -0.03511375 -1.67541e-4 -0.001699209 -0.04293292 6.2527e-4 -0.00159794 -0.03772693 4.69788e-4 -0.001648366 -0.04031842 0.001190125 -0.001748204 -0.04545348 0.001597046 -0.001698255 -0.04288566 0.001992702 -0.001796483 -0.04793673 0.002660334 -0.001747667 -0.04542595 0.002876758 -0.001870095 -0.05172055 0.004363 -0.001796483 -0.04793673 0.0038414 -0.001870095 -0.05172055 0.005165696 -0.004078209 -0.01914215 -0.003829598 -0.003817617 -0.03254657 -0.002322494 -0.004078447 -0.01913022 -0.002217829 -0.003766357 -0.03518193 -0.001728594 -0.004026234 -0.0218169 -0.002089262 -0.003974139 -0.0244981 -0.001875042 -0.003922224 -0.02717107 -0.00157541 -0.003715634 -0.03779369 -0.00103867 -0.003870427 -0.02983313 -0.001190662 -0.003818929 -0.03248161 -7.21216e-4 -0.003665328 -0.04037851 -2.5371e-4 -0.003767669 -0.03511375 -1.67541e-4 -0.003615677 -0.04293292 6.2527e-4 -0.003716886 -0.03772693 4.69788e-4 -0.00366652 -0.04031842 0.001190125 -0.003566682 -0.04545348 0.001597046 -0.003616511 -0.04288566 0.001992702 -0.003518462 -0.04793673 0.002660334 -0.003567159 -0.04542595 0.002876758 -0.003444731 -0.05172055 0.004363 -0.003518462 -0.04793673 0.0038414 -0.003444731 -0.05172055 0.005165696 -0.004025757 -0.02184152 -0.003724753 -0.003973484 -0.02453523 -0.003521263 -0.00392127 -0.02721971 -0.003219425 -0.003869235 -0.02989131 -0.002819776 -0.006496012 -0.01628756 -0.002257645 -0.009445786 -0.01644086 -0.002260804 -0.006499052 -0.01644086 -0.002260804 -0.006450831 -0.01598632 -0.002251446 -0.006551504 -0.01914215 -0.003829598 -0.009393215 -0.01914215 -0.003829598 -0.009132564 -0.03254657 -0.002322494 -0.009393393 -0.01913022 -0.002217829 -0.009081304 -0.03518193 -0.001728594 -0.00934118 -0.0218169 -0.002089262 -0.009289085 -0.0244981 -0.001875042 -0.00923717 -0.02717107 -0.00157541 -0.00903058 -0.03779369 -0.00103867 -0.009185433 -0.02983313 -0.001190662 -0.009133934 -0.03248161 -7.21216e-4 -0.008980274 -0.04037851 -2.5371e-4 -0.009082674 -0.03511375 -1.67541e-4 -0.008930683 -0.04293292 6.2527e-4 -0.009031832 -0.03772693 4.69788e-4 -0.008981466 -0.04031842 0.001190125 -0.008881688 -0.04545348 0.001597046 -0.008931636 -0.04288566 0.001992702 -0.008833408 -0.04793673 0.002660334 -0.008882164 -0.04542595 0.002876758 -0.008759856 -0.05172055 0.004363 -0.008833408 -0.04793673 0.0038414 -0.008759856 -0.05172055 0.005165696 -0.009340763 -0.02184152 -0.003724753 -0.00928843 -0.02453523 -0.003521263 -0.009236216 -0.02721971 -0.003219425 -0.009184241 -0.02989131 -0.002819776 -0.006603956 -0.02184152 -0.003724753 -0.006656408 -0.02453523 -0.003521263 -0.006708562 -0.02721971 -0.003219425 -0.006760537 -0.02989131 -0.002819776 -0.006812155 -0.03254657 -0.002322494 -0.006551206 -0.01913022 -0.002217829 -0.006863296 -0.03518193 -0.001728594 -0.006603419 -0.0218169 -0.002089262 -0.006655633 -0.0244981 -0.001875042 -0.006707668 -0.02717107 -0.00157541 -0.006914079 -0.03779369 -0.00103867 -0.006759345 -0.02983313 -0.001190662 -0.006810843 -0.03248161 -7.21216e-4 -0.006964385 -0.04037851 -2.5371e-4 -0.006862044 -0.03511375 -1.67541e-4 -0.007014095 -0.04293292 6.2527e-4 -0.006912887 -0.03772693 4.69788e-4 -0.006963193 -0.04031842 0.001190125 -0.00706315 -0.04545348 0.001597046 -0.007013142 -0.04288566 0.001992702 -0.00711143 -0.04793673 0.002660334 -0.007062554 -0.04542595 0.002876758 -0.007184982 -0.05172055 0.004363 -0.00711143 -0.04793673 0.0038414 -0.007184982 -0.05172055 0.005165696 0.0094316 -0.006266236 4.64244e-4 -0.0094316 -0.006266236 4.64244e-4 -0.00938034 -0.0056957 7.49468e-4 0.00938034 -0.0056957 7.49468e-4 -0.009295046 -0.005129277 0.00103265 0.009294986 -0.005129277 0.00103265 -0.009175956 -0.004569113 0.001312732 0.009175956 -0.004569113 0.001312732 0.009023725 -0.004016935 0.001588821 -0.009023725 -0.004016935 0.001588821 0.00896418 -0.003842294 0.001676142 -0.00896418 -0.003842294 0.001676142 -0.0094316 -0.006266236 -0.001110553 0.0094316 -0.006266236 -0.001110553 -0.00938034 -0.0056957 -8.25332e-4 0.00938034 -0.0056957 -8.25332e-4 -0.009295046 -0.005129277 -5.42148e-4 0.009294986 -0.005129277 -5.42148e-4 -0.009175956 -0.004569113 -2.62022e-4 0.009175956 -0.004569113 -2.62022e-4 -0.009023725 -0.004016935 1.40524e-5 0.009023725 -0.004016935 1.40524e-5 -0.00896418 -0.003842294 1.01342e-4 0.00896418 -0.003842294 1.01342e-4 0.007215559 -0.05187392 0.004431903 0.0079723 -0.05565744 0.006400406 0.007215559 -0.05187392 0.00521934 0.0087291 -0.05187392 0.00521934 0.0087291 -0.05187392 0.004431903 -0.001900732 -0.05187392 0.00521934 -0.003414154 -0.05187392 0.00521934 -0.001900732 -0.05187392 0.004431903 -0.002657353 -0.05565744 0.006400406 -0.003414154 -0.05187392 0.004431903 -0.007215559 -0.05187392 0.004431903 -0.0087291 -0.05187392 0.004431903 -0.0079723 -0.05565744 0.006400406 -0.0087291 -0.05187392 0.00521934 -0.007215559 -0.05187392 0.00521934 0.008838772 -0.003474891 0.001852035 -0.008838772 -0.003474891 0.001852035 0.008621692 -0.002944767 0.002105653 -0.008621752 -0.002944767 0.002105653 0.008490025 -0.002671301 0.002236545 -0.008490204 -0.002671301 0.002236545 -0.008838772 -0.003474891 2.77248e-4 0.008838772 -0.003474891 2.77248e-4 -0.008621752 -0.002944767 5.30972e-4 0.008621692 -0.002944767 5.30972e-4 -0.008490204 -0.002671301 6.61906e-4 0.008490025 -0.002671301 6.61906e-4 0.00837332 -0.00242877 0.002342641 -0.00837332 -0.00242877 0.002342641 0.008094668 -0.001928448 0.002561271 -0.008094668 -0.001928448 0.002561271 0.00780946 -0.001481771 0.002756536 -0.007809579 -0.001481771 0.002756536 -0.00837332 -0.00242877 7.6794e-4 0.00837332 -0.00242877 7.6794e-4 -0.008094668 -0.001928448 9.86638e-4 0.008094668 -0.001928448 9.86638e-4 0.00780946 -0.001481771 0.00118184 -0.007809579 -0.001481771 0.00118184 0.007786512 -0.001445651 0.002770841 -0.007786512 -0.001445651 0.002770841 0.007450044 -9.8214e-4 0.002954781 -0.007450044 -9.8214e-4 0.002954781 0.007086455 -5.39564e-4 0.003130376 -0.007086455 -5.39564e-4 0.003130376 -0.006874859 -2.75002e-4 0.00323534 0.006874859 -2.75e-4 0.00323534 -0.007786512 -0.001445651 0.001196205 0.007786512 -0.001445651 0.001196205 -0.007450044 -9.8214e-4 0.001380085 0.007450044 -9.8214e-4 0.001380085 -0.007086455 -5.39564e-4 0.001555681 0.007086455 -5.39564e-4 0.001555681 0.006874859 -2.75e-4 0.001660585 -0.006874859 -2.75002e-4 0.001660585 0.005896747 9.47536e-4 0.002097547 0.00490731 0.002184212 0.002492249 0.003936827 0.003397285 0.002833962 0.003936827 0.003397285 0.004408657 0.005896747 9.47536e-4 0.003672301 0.00490731 0.002184212 0.004067003 -0.005896866 9.47536e-4 0.003672301 -0.005896866 9.47536e-4 0.002097547 -0.00490731 0.002184212 0.002492249 -0.003936946 0.003397285 0.002833962 -0.003936946 0.003397285 0.004408657 -0.00490731 0.002184212 0.004067003 0.003909885 0.003433883 0.002844214 0.003524601 0.003956973 0.002972185 0.003524601 0.003956973 0.004547059 0.003909885 0.003433883 0.004418909 -0.003909885 0.003433883 0.004418909 -0.003909885 0.003433883 0.002844214 -0.003524601 0.003956973 0.002972185 -0.003524601 0.003956973 0.004547059 0.003158092 0.004547536 0.003116846 0.003158092 0.004547536 0.00469172 -0.003158152 0.004547536 0.00469172 0.003082156 0.004694998 0.00472784 -0.003082156 0.004694998 0.00472784 -0.003158152 0.004547536 0.003116846 0.003082156 0.004694998 0.003152966 -0.003082156 0.004694998 0.003152966 0.002839684 0.005165398 0.003251135 0.002839684 0.005165398 0.00482589 -0.002839744 0.005165398 0.00482589 0.002571403 0.005806684 0.004959762 -0.002571403 0.005806684 0.004959762 -0.00251919 0.005965948 0.004993021 0.00251919 0.005965948 0.004993021 -0.002839744 0.005165398 0.003251135 -0.002571403 0.005806684 0.003384888 0.002571403 0.005806684 0.003384888 -0.00251919 0.005965948 0.003418147 0.00251919 0.005965948 0.003418147 0.002354919 0.006467163 0.005079746 -0.002354919 0.006467163 0.005079746 0.002191603 0.007142782 0.00519669 -0.002191603 0.007142782 0.00519669 0.002175271 0.007245123 0.005214393 -0.002175271 0.007245123 0.005214393 -0.002354919 0.006467163 0.003504931 0.002354919 0.006467163 0.003504931 0.002191603 0.007142782 0.003621876 -0.002191603 0.007142782 0.003621876 0.002175271 0.007245123 0.003639519 -0.002175271 0.007245123 0.003639519 -0.002082586 0.007829308 0.005294859 0.002082407 0.007829308 0.005294859 -0.002028346 0.008531332 0.005391657 0.002028346 0.008531332 0.005391657 -0.002082586 0.007829308 0.003720164 0.002082407 0.007829308 0.003720164 -0.002028346 0.008531332 0.003816783 0.002028346 0.008531332 0.003816783 0.00202924 0.009217321 0.005462229 -0.002029359 0.009217321 0.005462229 0.002078473 0.009822785 0.005524575 -0.002078473 0.009822785 0.005524575 -0.002029359 0.009217321 0.003887534 0.00202924 0.009217321 0.003887534 0.002078473 0.009822785 0.00394988 -0.002078473 0.009822785 0.00394988 -0.002085626 0.009910106 0.005530536 0.002085566 0.009910106 0.005530536 -0.002196729 0.01059627 0.005577385 0.002196729 0.01059627 0.005577385 -0.002324521 0.01111805 0.005613088 0.002324521 0.01111805 0.005613088 -0.002085626 0.009910106 0.003955781 0.002085566 0.009910106 0.003955781 -0.002196729 0.01059627 0.00400269 0.002196729 0.01059627 0.00400269 -0.002324521 0.01111805 0.004038274 0.002324521 0.01111805 0.004038274 -0.002362132 0.01127135 0.005619585 0.002362132 0.01127135 0.005619585 -0.00240457 0.01177561 0.005641043 0.00240457 0.01177561 0.005641043 -0.002362132 0.01127135 0.004044711 0.002362132 0.01127135 0.004044711 -0.00240457 0.01177561 0.004066348 0.00240457 0.01177561 0.004066348 0.002459943 0.01243352 0.00565803 -0.002459943 0.01243352 0.00565803 -0.002459943 0.01243352 0.004083216 -0.002515375 0.01309156 0.004089057 -0.003012239 0.01899206 0.00521934 -0.002957403 0.0183407 0.0053128 -0.002902448 0.01768779 0.005395233 -0.002847373 0.01703357 0.005466759 -0.002792179 0.01637828 0.005527198 -0.002736926 0.01572203 0.00557667 -0.002681553 0.01506507 0.005615055 -0.00262624 0.01440751 0.005642473 -0.002570807 0.01374959 0.005658686 -0.002515375 0.01309156 0.005663931 -0.008648514 0.08592116 -0.003048121 -0.008661389 0.08607441 -0.001487672 -0.008661389 0.08607441 -0.003062248 -0.003012239 0.01899206 0.003644526 -0.008648514 0.08592116 -0.001473426 -0.002957403 0.0183407 0.003737986 -0.002902448 0.01768779 0.003820538 -0.002847373 0.01703357 0.003892064 -0.002792179 0.01637828 0.003952443 -0.002736926 0.01572203 0.004001915 -0.002681553 0.01506507 0.00404036 -0.00262624 0.01440751 0.004067599 -0.002570807 0.01374959 0.004083931 0.00866127 0.08607441 -0.001487672 0.008648335 0.08592116 -0.003048121 0.00866127 0.08607441 -0.003062248 0.003012239 0.01899206 0.003644526 0.008648335 0.08592116 -0.001473426 0.003012239 0.01899206 0.00521934 0.002957403 0.0183407 0.003737986 0.002902448 0.01768779 0.003820538 0.002847254 0.01703357 0.003892064 0.00279206 0.01637828 0.003952443 0.002736926 0.01572203 0.004001915 0.002681553 0.01506507 0.00404036 0.002626121 0.01440751 0.004067599 0.002570807 0.01374959 0.004083931 0.002515375 0.01309156 0.004089057 0.002459943 0.01243352 0.004083216 0.002957403 0.0183407 0.0053128 0.002902448 0.01768779 0.005395233 0.002847254 0.01703357 0.005466759 0.00279206 0.01637828 0.005527198 0.002736926 0.01572203 0.00557667 0.002681553 0.01506507 0.005615055 0.002626121 0.01440751 0.005642473 0.002570807 0.01374959 0.005658686 0.002515375 0.01309156 0.005663931 -0.008748412 0.08789646 -0.001657128 0.008748292 0.08789646 -0.001657128 -0.008748412 0.08789736 -0.00322926 -0.008764624 0.08823591 -0.00168401 -0.008764624 0.08823591 -0.003254652 0.008748412 0.08789736 -0.00322926 0.008764505 0.08823591 -0.00168401 0.008764505 0.08823591 -0.003254652 -0.008723855 0.08987414 -0.001813471 0.008723855 0.08987414 -0.001813471 -0.008723855 0.08987635 -0.003377377 -0.008710861 0.09039926 -0.001847684 -0.008710861 0.09039926 -0.003407895 0.008723676 0.08987635 -0.003377377 0.008710682 0.09039926 -0.001847684 0.008710682 0.09039926 -0.003407895 -0.008568644 0.09185367 -0.001942455 0.008568644 0.09185367 -0.001942455 -0.008568286 0.09185761 -0.003492832 -0.008500277 0.0925529 -0.001978218 -0.008500277 0.0925529 -0.003521621 0.008568286 0.09185761 -0.003492832 0.008500277 0.0925529 -0.001978218 0.008500277 0.0925529 -0.003521621 -0.008280277 0.09383493 -0.002043783 0.008280158 0.09383493 -0.002043783 -0.008279263 0.09384042 -0.003575146 -0.008134186 0.09468561 -0.002075672 -0.008134186 0.09468561 -0.003596127 0.008279263 0.09384042 -0.003575146 0.008134126 0.09468561 -0.002075672 0.008134126 0.09468561 -0.003596127 -0.007854223 0.09581744 -0.002117931 0.007854104 0.09581744 -0.002117931 -0.007852435 0.09582436 -0.003624618 -0.007614433 0.09678626 -0.00214076 -0.007614433 0.09678626 -0.003632605 0.007852435 0.09582436 -0.003624618 0.007614374 0.09678626 -0.00214076 0.007614374 0.09678626 -0.003632605 -0.007283627 0.09780067 -0.002164423 0.007283627 0.09780067 -0.002164423 -0.006943702 0.09884351 -0.003632485 -0.007281005 0.09780877 -0.003641128 -0.006943702 0.09884351 -0.002174556 0.007280886 0.09780877 -0.003641128 0.006943523 0.09884351 -0.003632485 0.006943523 0.09884351 -0.002174556 -0.006559431 0.09978431 -0.002183616 0.006559312 0.09978431 -0.002183616 -0.006555736 0.09979325 -0.003624618 -0.006125509 0.1008468 -0.003598332 -0.006125509 0.1008468 -0.002179086 0.006555736 0.09979325 -0.003624618 0.00612545 0.1008468 -0.002179086 0.00612545 0.1008468 -0.003598332 -0.005668699 0.1017681 -0.002175152 0.00566864 0.1017681 -0.002175152 -0.005664169 0.1017771 -0.003575146 -0.005164206 0.1027855 -0.003533244 -0.005164206 0.1027855 -0.002156794 0.005664169 0.1017771 -0.003575146 0.005164146 0.1027855 -0.003533244 0.005164146 0.1027855 -0.002156794 -0.004594385 0.1037516 -0.002139389 0.004594385 0.1037516 -0.002139389 -0.004589498 0.1037601 -0.003492832 -0.004064857 0.1046495 -0.003440976 -0.004064857 0.1046495 -0.00211066 0.004589438 0.1037601 -0.003492832 0.004064857 0.1046495 -0.003440976 0.004064857 0.1046495 -0.00211066 0.003313839 0.1057344 -0.002076089 -0.003313839 0.1057344 -0.002076089 -0.00330919 0.1057412 -0.003377377 -0.002833366 0.1064288 -0.003325879 -0.002833366 0.1064288 -0.00204432 0.003309071 0.1057412 -0.003377377 0.002833187 0.1064288 -0.003325879 0.002833187 0.1064288 -0.00204432 0.001796364 0.1077162 -0.001985371 -0.001796424 0.1077162 -0.001985371 -0.001793205 0.1077202 -0.00322926 -0.001475989 0.1081141 -0.00319314 -0.001475989 0.1081141 -0.001961588 0.001793146 0.1077202 -0.00322926 0.00147593 0.1081141 -0.00319314 0.00147593 0.1081141 -0.001961588 0 0.1096965 -0.001867115 0 0.1096965 -0.003048121 - - - - - - - - - - -0.7048984 -0.008056998 -0.7092626 0.6900665 -0.04434418 -0.7223863 0.7051585 -0.008057177 -0.709004 -0.6900326 -0.0444355 -0.7224131 -0.651705 -0.1713342 -0.7388675 0.6517005 -0.1712415 -0.738893 -0.5840824 -0.3328458 -0.7403118 0.5840231 -0.3328773 -0.7403445 0.561585 -0.4068218 -0.7204988 -0.5616686 -0.4067244 -0.7204886 -0.7024869 0.05694848 -0.7094147 0.561735 -0.4067283 -0.7204345 -0.702519 0.02771133 -0.7111254 0.4859869 -0.447136 -0.7509236 0.3450557 -0.5587546 -0.7541418 0.1791802 -0.6287636 -0.7566709 0 -0.6532686 -0.7571263 -0.5616803 -0.4065193 -0.7205951 0.7024869 0.05694848 -0.7094147 0.702519 0.02771133 -0.7111254 -0.4859938 -0.4472644 -0.7508426 -0.3450516 -0.558687 -0.7541938 -0.1791177 -0.6287889 -0.7566647 -0.4859614 -0.4472017 -0.7509009 0.4859827 -0.4472542 -0.750856 -0.3450498 -0.5587757 -0.7541289 -0.1791801 -0.6285802 -0.7568233 0.1791471 -0.6286021 -0.7568129 -0.561668 -0.4065104 -0.7206099 0.4859614 -0.4472017 -0.7509009 0.5616546 -0.4067059 -0.7205098 -0.4859016 -0.4472638 -0.7509027 -0.3450519 -0.5588095 -0.7541029 0.3450498 -0.5587757 -0.7541289 -0.179176 -0.6285657 -0.7568362 0.1791506 -0.6285837 -0.7568274 0.5769135 -0.3587283 0.7338153 0.5507234 -0.466917 0.6918759 0.4604237 -0.5170382 0.7215827 0.6473212 -0.2008496 0.7352787 0.6889389 -0.0732764 0.7211061 0.7027118 -0.02804738 -0.7109215 0.7025241 -0.05404967 -0.7096046 0.7022438 -0.07995992 -0.707432 0.7019377 -0.1057179 -0.7043488 0.7017578 -0.1313545 -0.7002013 0.7111306 -0.01544272 0.7028904 0.7015076 -0.1568366 -0.6951902 0.7105218 0.008453845 0.7036244 0.7012693 -0.1821078 -0.6892448 0.7111809 0.03088504 0.7023304 0.7110441 0.05328708 0.7011253 0.7114298 0.07565671 0.6986729 0.7010322 -0.2071356 -0.6823847 0.7116754 0.09790533 0.6956529 0.7118706 0.1200643 0.6919718 0.7007864 -0.2318863 -0.6746312 0.7121346 0.1421278 0.6875056 0.7005076 -0.2563309 -0.6660208 0.7123556 0.1640117 0.6823854 0.7125308 0.1857395 0.6766097 0.7002907 -0.2804397 -0.6564653 0.7127229 0.2072887 0.6701176 0.7021602 -0.2975643 -0.6468591 0.712985 0.2285873 0.6628727 0.7104264 -0.3379088 -0.6173428 0.7059449 0.2319782 0.6691996 0.7339869 0.1386487 0.6648609 -0.7027267 -0.0280773 -0.7109057 -0.7014921 -0.15684 -0.6952051 -0.7107951 0.008453845 0.7033483 -0.711161 -0.01544272 0.7028597 -0.701239 -0.1821079 -0.6892755 -0.7110292 0.0308851 0.702484 -0.711226 0.05328696 0.7009409 -0.7114467 0.07562798 0.6986589 -0.701002 -0.2071357 -0.6824156 -0.7116754 0.09790533 0.6956529 -0.7118856 0.1200616 0.6919567 -0.7007564 -0.2318865 -0.6746622 -0.7121047 0.1421279 0.6875367 -0.7005373 -0.2563306 -0.6659896 -0.7123109 0.1640084 0.6824328 -0.7125308 0.1857395 0.6766097 -0.7002907 -0.2804397 -0.6564653 -0.7127229 0.2072887 0.6701176 -0.7021602 -0.2975643 -0.6468591 -0.7129555 0.2285876 0.6629043 -0.710419 -0.3379358 -0.6173363 -0.7059899 0.2319729 0.6691538 -0.7339869 0.1386487 0.6648609 -0.6888886 -0.07333856 0.7211477 -0.7024934 -0.05404967 -0.7096349 -0.7022438 -0.07995992 -0.707432 -0.7019989 -0.1057179 -0.7042878 -0.7017578 -0.1313545 -0.7002013 -0.6473238 -0.200942 0.7352512 -0.5770205 -0.3586579 0.7337656 -0.5508032 -0.4667544 0.6919221 -0.4603895 -0.5170341 0.7216075 -0.7052044 -0.008056998 -0.7089583 0.7092584 0.005798578 -0.7049248 0.7051433 -0.008056998 -0.7090192 -0.6900656 -0.04437464 -0.7223853 -0.6516405 -0.1713333 -0.7389246 -0.5842617 -0.3328131 -0.7401849 -0.5771203 -0.358663 0.7336845 -0.5508192 -0.4666154 0.6920033 -0.4604405 -0.5170533 0.7215612 -0.3232339 -0.6156125 0.718708 -0.1662982 -0.6777058 0.7162819 0 -0.6978607 0.7162335 0.1662971 -0.678098 0.7159109 0.3232268 -0.615599 0.7187227 -0.3232279 -0.6156315 0.7186945 -0.1663302 -0.6780781 0.7159221 0 -0.6756099 0.7372593 0.1663302 -0.6780781 0.7159221 0.3232279 -0.6156315 0.7186945 0.4603895 -0.5170341 0.7216075 0.5770002 -0.3586642 0.7337785 0.5840824 -0.3328458 -0.7403118 0.5507819 -0.4667623 0.6919337 -0.6899995 -0.04449635 -0.722441 0.7048984 -0.008056998 -0.7092626 -0.7051585 -0.008057177 -0.709004 0.6900326 -0.0444355 -0.7224131 0.651705 -0.1713342 -0.7388675 -0.6517163 -0.1713677 -0.7388498 -0.5842591 -0.3326895 -0.7402426 -0.577153 -0.3585423 0.7337178 -0.4603582 -0.5170637 0.7216063 -0.323235 -0.615645 0.7186798 -0.16633 -0.6780468 0.7159518 0 -0.6978764 0.7162183 0.1663277 -0.6776711 0.716308 0.3232289 -0.6156639 0.7186663 0.460391 -0.5169442 0.7216709 0.5769339 -0.358722 0.7338024 0.5840432 -0.3328713 -0.7403312 0.5508399 -0.4667901 0.6918688 -0.7092432 0.005798697 -0.70494 0.7041634 -0.00802648 -0.7099925 -0.7051433 -0.008056998 -0.7090192 0.6900004 -0.04446589 -0.7224419 0.6517163 -0.1713677 -0.7388498 -0.7092039 -0.02111923 0.7046871 -0.7024873 0.08621627 -0.7064548 -0.7025228 0.1151797 -0.7022787 -0.7024798 0.1439872 -0.6969864 -0.7025242 0.1726173 -0.690408 -0.7024959 0.2008787 -0.6827499 -0.7024988 0.228805 -0.6739019 -0.7024809 0.2564187 -0.6639052 -0.7025224 0.2835237 -0.6527455 -0.7117432 -0.02865773 0.701855 -0.7117344 -0.05731469 0.7001066 -0.711711 -0.08578985 0.6972143 -0.7024964 0.3101691 -0.640542 -0.7117447 -0.1141734 0.6930974 -0.7117319 -0.1424013 0.6878661 -0.708008 0.3183122 -0.6303985 -0.7117287 -0.1703559 0.6814846 -0.7117359 -0.1980384 0.6739532 -0.7083958 0.321618 -0.6282812 -0.7117318 -0.2253822 0.6653126 -0.7117356 -0.2523623 0.65555 -0.711735 -0.2788832 0.6447151 -0.7117382 -0.3049784 0.6327851 -0.7130492 -0.3024142 0.6325398 -0.7065406 -0.3180058 0.6321969 0.7024873 0.08621627 -0.7064548 0.7092039 -0.02111923 0.7046871 0.7025228 0.1151797 -0.7022787 0.7024798 0.1439872 -0.6969864 0.7025242 0.1726173 -0.690408 0.7024959 0.2008787 -0.6827499 0.7024988 0.228805 -0.6739019 0.7024809 0.2564187 -0.6639052 0.7025224 0.2835237 -0.6527455 0.7117432 -0.02865773 0.701855 0.7117356 -0.05728429 0.7001079 0.711711 -0.08578985 0.6972143 0.7024964 0.3101691 -0.640542 0.7117447 -0.1141734 0.6930974 0.7117319 -0.1424013 0.6878661 0.708008 0.3183122 -0.6303985 0.7117287 -0.1703559 0.6814846 0.7117359 -0.1980384 0.6739532 0.7083958 0.321618 -0.6282812 0.7117318 -0.2253822 0.6653126 0.7117356 -0.2523623 0.65555 0.711735 -0.2788832 0.6447151 0.7117382 -0.3049784 0.6327851 0.7130492 -0.3024142 0.6325398 0.7065406 -0.3180058 0.6321969 0 0 1 0.7140999 0.08859866 0.6944147 -0.7124719 0.08932983 0.6959915 0.6592833 -0.4285555 -0.6178072 3.35714e-4 -0.9248619 0.380303 -0.6592364 -0.4286059 -0.6178224 -0.7027118 -0.02804738 -0.7109215 -0.7015076 -0.1568366 -0.6951902 -0.7105218 0.008453845 0.7036244 -0.7111913 -0.01544272 0.702829 -0.7111809 0.03088504 0.7023304 -0.711332 0.05328577 0.7008335 -0.7114617 0.07562637 0.6986436 -0.7010322 -0.2071356 -0.6823847 -0.7115547 0.09790551 0.6957762 -0.7118706 0.1200643 0.6919718 -0.7007265 -0.2318867 -0.6746934 -0.7121346 0.1421278 0.6875056 -0.7005671 -0.2563303 -0.6659584 -0.7123256 0.1640119 0.6824164 -0.7125011 0.1857398 0.676641 -0.712985 0.2285873 0.6628727 -0.7104337 -0.3378818 -0.6173491 -0.7059449 0.2319782 0.6691996 -0.6889092 -0.073246 0.7211374 -0.7025241 -0.05404967 -0.7096046 -0.7021843 -0.07992959 -0.7074946 -0.7020139 -0.1057202 -0.7042725 -0.6472231 -0.2009696 0.7353323 0.7021843 -0.07992959 -0.7074946 0.7020139 -0.1057202 -0.7042725 0.7111961 0.03088569 0.702315 0.7007265 -0.2318867 -0.6746934 0.7005671 -0.2563303 -0.6659584 0.7123256 0.1640119 0.6824164 0.7125011 0.1857398 0.676641 0.7104337 -0.3378818 -0.6173491 0.7111606 -0.01547324 0.7028594 -0.6888703 -0.07339769 0.7211592 -0.7111457 -0.01544243 0.7028751 0.6888886 -0.07333856 0.7211477 -0.6473336 -0.2009966 0.7352276 0.6473238 -0.200942 0.7352512 0.7027267 -0.0280773 -0.7109057 0.7024934 -0.05404967 -0.7096349 0.7019989 -0.1057179 -0.7042878 0.7014921 -0.15684 -0.6952051 0.7107951 0.008453845 0.7033483 0.701239 -0.1821079 -0.6892755 0.7110142 0.03088575 0.7024992 0.7112411 0.05328583 0.7009257 0.7114617 0.07562637 0.6986436 0.701002 -0.2071357 -0.6824156 0.7118856 0.1200616 0.6919567 0.700772 -0.2318816 -0.6746479 0.7121047 0.1421279 0.6875367 0.7005373 -0.2563306 -0.6659896 0.7123109 0.1640084 0.6824328 0.7021757 -0.2975579 -0.6468451 0.7129555 0.2285876 0.6629043 0.7059899 0.2319729 0.6691538 -0.7009975 -0.2071649 -0.6824113 -0.7117055 0.09790527 0.695622 -0.7119007 0.1200641 0.6919409 -0.7120628 0.1420952 0.6875868 -0.7003202 -0.2804393 -0.6564338 -0.7126933 0.207289 0.670149 -0.702205 -0.2975574 -0.6468135 -0.7129356 0.2286216 0.6629141 -0.7104264 -0.3379088 -0.6173428 -0.7060688 0.2319482 0.6690792 -0.73399 0.1386188 0.6648637 -0.7024627 -0.05404967 -0.7096652 0.6888543 -0.07339924 0.7211744 -0.7111306 -0.01544272 0.7028904 0.7109482 -0.0154733 0.7030742 0.6473376 -0.2009673 0.7352322 0.7027273 -0.02804678 -0.7109063 -0.7111961 0.03088569 0.702315 -0.7127525 0.2072885 0.6700862 -0.7021896 -0.2975638 -0.6468274 -0.7128968 0.2285884 0.6629674 -0.7104372 -0.338036 -0.6172606 -0.7060196 0.2319726 0.6691226 -0.734022 0.1385886 0.6648345 0.7014313 -0.15684 -0.6952664 0.7113258 0.008484125 0.7028112 0.7110289 0.05328595 0.7011408 0.7122511 0.1640087 0.6824951 0.7125605 0.1857393 0.6765785 0.7222981 -0.2689353 0.6371495 -0.7222981 -0.2689353 0.6371495 -0.7279824 -0.2291711 0.6461595 0.7280172 -0.2290504 0.6461633 -0.731269 -0.1885167 0.6555205 0.7312464 -0.1885797 0.6555277 -0.7319439 -0.1474081 0.6652287 0.7319695 -0.1474376 0.6651939 0.7301087 -0.1056571 0.6751133 -0.7301087 -0.1056571 0.6751133 0.7217828 -0.09058141 0.6861667 -0.7217788 -0.09064197 0.6861628 -0.7042562 0.3459327 -0.6199628 0.7042562 0.3459327 -0.6199628 -0.6920846 0.3828637 -0.6119105 0.6920813 0.382923 -0.6118771 -0.6779081 0.4189162 -0.604111 0.6778618 0.4189674 -0.6041274 -0.6617769 0.4538195 -0.5967406 0.6618387 0.4537284 -0.5967413 -0.6440486 0.4873015 -0.5896938 0.6440486 0.4873015 -0.5896938 -0.6279645 0.505155 -0.5920128 0.6279645 0.505155 -0.5920128 -0.6592833 -0.4285555 -0.6178072 7.01939e-4 -0.924851 0.3803291 -0.7141187 0.0885362 0.6944033 0.7125905 0.08935993 0.6958661 -0.7141168 0.08856642 0.6944015 0.6592364 -0.4286059 -0.6178224 0 -0.9248771 0.3802663 -0.65906 -0.4288239 -0.6178592 0 -0.9248361 0.380366 -0.7067532 0.09207504 0.701443 0.7140566 0.08856654 0.6944633 0.7231907 -0.0517916 0.6887037 -0.7231874 -0.05188292 0.6887005 0.7153888 -0.009308159 0.6986646 -0.7154045 -0.009247362 0.6986494 0.7005003 0.006408929 0.7136234 -0.7039533 0.009766101 0.7101792 -0.6258311 0.5110476 -0.5892078 0.6258326 0.5110794 -0.5891788 -0.604929 0.5424248 -0.5829548 0.6048595 0.5424783 -0.5829772 -0.5895363 0.555477 -0.5864233 0.5895452 0.5553938 -0.5864932 0.6985474 0.05664306 0.7133185 -0.6985154 0.05667346 0.7133474 0.6840867 0.09891253 0.7226629 -0.6840867 0.09891253 0.7226629 0.6592149 0.1052913 0.7445465 -0.6801822 0.1290353 0.7215968 -0.5855116 0.5563047 -0.5896622 0.5856115 0.5561906 -0.5896706 -0.5618248 0.5855991 -0.5843173 0.5618039 0.5856397 -0.5842968 0.5450701 0.5969526 -0.5886818 -0.5450047 0.5975582 -0.5881278 0.6592227 0.1640121 0.733843 -0.6592079 0.1640084 0.7338571 0.6381211 0.2043855 0.7423128 -0.6381211 0.2043855 0.7423128 0.6263437 0.2085371 0.7511364 -0.6263477 0.2085078 0.7511412 -0.6254069 0.2110733 0.7512086 0.6255225 0.2111932 0.7510787 -0.5399193 0.5984251 -0.5919245 0.5404878 0.5979241 -0.5919119 -0.5138243 0.6252505 -0.5874065 0.5138243 0.6252505 -0.5874065 -0.4930113 0.6361476 -0.5935119 0.4930113 0.6361476 -0.5935119 0.5017976 0.6297038 -0.5930197 -0.5017885 0.6296924 -0.5930395 0.5058275 0.6142932 -0.6056257 0.5101023 0.5984562 -0.617775 0.5147141 0.5759671 -0.6350837 0.6114228 0.2562397 0.7486678 0.6166781 0.2331083 0.7519102 0.6089182 0.255781 0.7508627 -0.6170459 0.2335057 0.7514849 -0.5058594 0.6143254 -0.6055663 -0.5100699 0.5984233 -0.6178336 -0.5145154 0.5764685 -0.6347898 -0.6114272 0.2563025 0.7486428 -0.6078488 0.2545598 0.7521431 0.532685 0.5625329 -0.6323002 0.5399498 0.5296953 -0.6541231 0.6237139 0.2351173 0.7454536 0.6194196 0.2561179 0.7421072 -0.598243 0.2353357 0.7659781 -0.5319522 0.5630208 -0.6324829 -0.5399478 0.5296628 -0.6541512 -0.6236855 0.2350875 0.7454867 0.5716556 0.4892537 -0.658666 0.6488733 0.1823534 0.7387225 -0.6488945 0.1823204 0.7387119 0.664801 0.1737156 0.7265415 -0.6567947 0.1679143 0.7351364 -0.5716589 0.489409 -0.6585475 0.6016553 0.4613585 -0.6520425 -0.6014771 0.4614539 -0.6521394 0.6048334 0.4258067 -0.6729527 0.6637973 0.1526886 0.7321608 -0.6637911 0.1527482 0.732154 0.6803689 0.09790623 0.7263006 -0.6803354 0.09793627 0.726328 -0.6881679 0.08557462 0.7204874 0.688183 0.08557653 0.7204726 -0.6048652 0.4258075 -0.6729236 -0.6300007 0.379563 -0.6775185 0.6300467 0.3795112 -0.6775046 -0.6564103 0.3455706 -0.6706017 0.6564103 0.3455706 -0.6706017 0.6886533 0.0677514 0.7219187 -0.6886533 0.0677514 0.7219187 0.6969118 0.01211619 0.7170546 -0.6969125 0.01202464 0.7170554 0.6982465 -0.001434385 0.715856 -0.6962033 -0.00213629 0.7178415 -0.6549385 0.3085474 -0.6898218 0.6549385 0.3085474 -0.6898218 0.6723431 0.2574925 -0.6940119 -0.6723431 0.2574925 -0.6940119 0.693647 0.2180923 -0.6865054 -0.6936417 0.2180296 -0.6865307 -0.6989896 -0.01858639 0.7148903 0.6989435 -0.01858597 0.7149354 -0.695281 -0.06228899 0.7160338 0.6953133 -0.06225866 0.7160052 -0.6870777 0.1803987 -0.7038327 0.6870431 0.1804282 -0.703859 -0.6996937 0.1136857 -0.7053399 0.6997424 0.1136532 -0.7052969 0.6957049 -0.1036416 0.7108117 -0.6957156 -0.1037042 0.7107921 0.705791 -0.1163398 0.6988021 -0.6898316 -0.1167675 0.7144913 -0.6989183 0.04648059 -0.7136895 0.6988567 0.04648053 -0.71375 0.7112134 0.002014219 -0.7029733 -0.7108802 0.001556456 -0.7033115 -0.6897953 -0.1335215 0.711586 0.6897615 -0.1335514 0.7116131 -0.6789889 -0.1875703 0.7097827 0.6789998 -0.1876038 0.7097635 -0.6791542 -0.204146 0.7050348 0.6791706 -0.2041418 0.7050202 -0.6959398 -0.03445667 -0.717273 0.6958699 -0.03415101 -0.7173555 -0.6889643 -0.08957296 -0.7192391 0.6889758 -0.08963549 -0.7192205 -0.6939538 -0.1323633 -0.7077487 0.6939538 -0.1323633 -0.7077487 -0.7122638 -0.1442351 0.6869327 0.7122638 -0.1442351 0.6869327 -0.7010189 -0.08285874 0.7083129 0.701402 -0.08286076 0.7079331 -0.7163838 -0.08929997 -0.6919682 0.7163838 -0.08929997 -0.6919682 -0.7074947 -0.03570735 -0.7058161 0.7074947 -0.03570735 -0.7058161 0.7029737 -0.07120072 0.707643 -0.7023625 -0.07117009 0.7082526 -0.7069903 -0.04764133 -0.7056168 -0.7064828 -0.05942034 -0.7052315 -0.7129584 0.02441531 0.7007812 -0.7068289 0.03610438 0.7064627 -0.7064265 0.02420163 0.7073726 -0.7059084 0.01223814 0.7081974 -0.7052121 3.35714e-4 0.7089965 -0.7043231 -0.01153624 0.7097859 -0.7043591 -0.02346944 0.7094559 -0.704508 -0.03543287 0.7088112 -0.7030411 -0.04733532 0.7095721 -0.7026993 -0.0592373 0.7090167 -0.7009428 -0.1261068 -0.7019804 -0.7117118 0.01760965 0.7022508 -0.7075278 -0.1098388 -0.6980974 -0.6963283 -0.1433796 -0.7032562 -0.7129216 0.007629692 0.7012023 -0.7025786 -0.1532055 -0.6949183 -0.7030718 -0.1416093 -0.6968765 -0.7035937 -0.1299515 -0.6986191 -0.7040748 -0.1183224 -0.7001989 -0.7045127 -0.1065741 -0.7016438 -0.7049333 -0.09473168 -0.702919 -0.7055625 -0.08307194 -0.7037618 -0.7060869 -0.07126176 -0.7045304 0.7117123 0.01757913 0.7022513 0.7009277 -0.1261041 -0.7019959 0.7075278 -0.1098388 -0.6980974 0.696359 -0.1433796 -0.7032258 0.7127699 0.007690727 0.7013558 0.7129584 0.02441531 0.7007812 0.7025786 -0.1532055 -0.6949183 0.7031081 -0.1417019 -0.696821 0.7035605 -0.1299815 -0.6986469 0.7039481 -0.1181995 -0.700347 0.7045303 -0.1065417 -0.701631 0.705108 -0.09485262 -0.7027275 0.7053257 -0.08295077 -0.7040134 0.7060869 -0.07126176 -0.7045304 0.7064828 -0.05942034 -0.7052315 0.7069903 -0.04764133 -0.7056168 0.7068289 0.03610438 0.7064627 0.7064265 0.02420163 0.7073726 0.7050209 0.01229918 0.7090799 0.7050896 3.35713e-4 0.7091182 0.7053178 -0.01156657 0.708797 0.7043591 -0.02346944 0.7094559 0.7029473 -0.03534114 0.7103634 0.7055457 -0.04748803 0.7070716 0.7026993 -0.0592373 0.7090167 -0.7093101 0.0265522 0.7043964 0.7092948 0.0265516 0.7044118 -0.7030432 -0.09216833 -0.7051491 -0.7153766 0.04562658 0.697248 -0.7147832 -0.05917614 -0.6968382 0.7031103 -0.09207761 -0.7050941 0.7153612 0.04562562 0.6972636 0.7147432 -0.0590558 -0.6968892 -0.7077711 0.06830197 0.7031322 0.7078884 0.06839305 0.7030054 -0.7056342 -0.02969515 -0.7079537 -0.7124736 0.08786511 0.6961762 -0.7149465 0.003967463 -0.699168 0.7056342 -0.02969515 -0.7079537 0.7124434 0.08786517 0.6962071 0.7149313 0.003936886 -0.6991837 -0.7032837 0.109869 0.7023681 0.7033141 0.109869 0.7023376 -0.7036167 0.03302156 -0.7098121 -0.7064909 0.1297985 0.6957176 -0.7105577 0.06717365 -0.7004252 0.7036481 0.03299111 -0.7097824 0.7064909 0.1297985 0.6957176 0.7105577 0.06717365 -0.7004252 -0.6957826 0.1510407 0.7021918 0.695752 0.1510407 0.7022222 -0.6971198 0.09540301 -0.7105788 -0.6974589 0.1713356 0.6958413 -0.7016158 0.1297695 -0.7006392 0.6971466 0.09546357 -0.7105445 0.6974553 0.1713653 0.6958377 0.7015981 0.1297967 -0.700652 -0.6853181 0.1916937 0.7025617 0.6853181 0.1916937 0.7025617 -0.6860987 0.1570205 -0.7103614 -0.6854267 0.2121987 0.6965357 -0.6882168 0.1913578 -0.6998142 0.686164 0.156991 -0.7103047 0.6854267 0.2121987 0.6965357 0.6881819 0.1913871 -0.6998404 -0.6717901 0.2316412 0.7035912 0.6718524 0.2316417 0.7035315 -0.6704888 0.2515134 -0.6979871 -0.6699668 0.2172692 -0.7098864 -0.6703578 0.2523951 0.6977947 0.6699668 0.2172692 -0.7098864 0.6704796 0.2514795 -0.698008 0.6703267 0.2523949 0.6978246 -0.6554287 0.2707656 0.7050527 0.6554287 0.2707656 0.7050527 -0.6511905 0.2762303 -0.7068578 -0.6486834 0.3097689 -0.695164 -0.6522949 0.291523 0.6996613 0.6512483 0.2762594 -0.7067932 0.6522949 0.291523 0.6996613 0.6486896 0.3097413 -0.6951707 -0.6360256 0.308918 0.707136 0.6360256 0.308918 0.707136 -0.6276862 0.3328717 -0.7037092 -0.6230226 0.3656526 -0.6914775 -0.6312282 0.3296987 0.7020326 0.6277188 0.3329339 -0.7036506 0.6230226 0.3656526 -0.6914775 0.6312529 0.3296651 0.7020262 -0.6137433 0.3459059 0.709696 0.6137756 0.3459069 0.7096675 -0.6005274 0.3871062 -0.6996539 -0.5937805 0.4189974 -0.6869249 -0.6072415 0.3665056 0.7049336 0.6005288 0.3870461 -0.6996861 0.593793 0.4190061 -0.6869089 0.6072415 0.3665056 0.7049336 0.5885311 0.3816113 0.712744 -0.5885121 0.3815577 0.7127884 -0.569943 0.438467 -0.6949185 -0.5613334 0.4692885 -0.6816693 -0.580329 0.4019117 0.7082974 0.5699104 0.4384653 -0.6949464 0.5613126 0.4692966 -0.681681 0.5802891 0.4019358 0.7083165 0.5604263 0.4157037 0.716319 -0.5603982 0.415736 0.7163221 -0.5362883 0.4868162 -0.6894961 -0.5259388 0.5165084 -0.6757275 -0.5504168 0.435725 0.7121694 0.5363101 0.4868083 -0.6894848 0.5259471 0.5164859 -0.6757381 0.5504168 0.435725 0.7121694 0 0.7997472 0.6003369 0 0.8465309 -0.5323397 - - - - - - - - - - 0.007652521 0.03637266 0.004921257 0.03651458 0.004923999 0.03637266 0.004921257 0.03651458 0.007652521 0.03637266 0.007655203 0.03651458 0.004921257 0.03651458 0.007655203 0.03651458 0.007696986 0.03679347 0.004921257 0.03651458 0.007696986 0.03679347 0.004879415 0.03679347 0.004879415 0.03679347 0.007696986 0.03679347 0.007808685 0.03705257 0.004879415 0.03679347 0.007808685 0.03705257 0.004767656 0.03705257 0.004767656 0.03705257 0.007808685 0.03705257 0.004705488 0.03713166 0.004705488 0.03713166 0.007808685 0.03705257 0.007870972 0.03713166 0.01749759 0.03798192 0.014548 0.03722298 0.01749759 0.03722298 0.014548 0.03722298 0.01749759 0.03798192 0.01443582 0.03736579 0.01443582 0.03736579 0.01749759 0.03798192 0.01421082 0.03753596 0.01421082 0.03753596 0.01749759 0.03798192 0.01394981 0.03764259 0.01394981 0.03764259 0.01749759 0.03798192 0.01366996 0.03767919 0.01366996 0.03767919 0.01749759 0.03798192 0.008748888 0.03767919 0.008748888 0.03767919 0.01749759 0.03798192 0.003827631 0.03767919 0.002949655 0.03722298 0 0.03798192 0 0.03722298 0 0.03798192 0.002949655 0.03722298 0.003061652 0.03736579 0 0.03798192 0.003061652 0.03736579 0.003286838 0.03753596 0 0.03798192 0.003286838 0.03753596 0.003547966 0.03764259 0 0.03798192 0.003547966 0.03764259 0.003827631 0.03767919 0 0.03798192 0.003827631 0.03767919 0.01749759 0.03798192 0.007982969 0.03736579 0.004705488 0.03722298 0.007870972 0.03722298 0.004705488 0.03722298 0.007982969 0.03736579 0.004593491 0.03736579 0.004593491 0.03736579 0.007982969 0.03736579 0.004368305 0.03753596 0.004368305 0.03753596 0.007982969 0.03736579 0.008208096 0.03753596 0.004368305 0.03753596 0.008208096 0.03753596 0.008469223 0.03764259 0.004368305 0.03753596 0.008469223 0.03764259 0.004107296 0.03764259 0.004107296 0.03764259 0.008469223 0.03764259 0.008748888 0.03767919 0.004107296 0.03764259 0.008748888 0.03767919 0.003827631 0.03767919 0.01279217 0.03722298 0.009514749 0.03736579 0.009626746 0.03722298 0.009514749 0.03736579 0.01279217 0.03722298 0.01290404 0.03736579 0.009514749 0.03736579 0.01290404 0.03736579 0.01312935 0.03753596 0.009514749 0.03736579 0.01312935 0.03753596 0.009289622 0.03753596 0.009289622 0.03753596 0.01312935 0.03753596 0.01339048 0.03764259 0.009289622 0.03753596 0.01339048 0.03764259 0.009028553 0.03764259 0.009028553 0.03764259 0.01339048 0.03764259 0.01366996 0.03767919 0.009028553 0.03764259 0.01366996 0.03767919 0.008748888 0.03767919 0.02624577 0.003659248 0.02614504 0.005117297 0.02614504 0.003657758 0.02614504 0.005117297 0.02624577 0.003659248 0.02642703 0.003667712 0.02614504 0.005117297 0.02642703 0.003667712 0.02624553 0.005118966 0.02624553 0.005118966 0.02642703 0.003667712 0.02642703 0.005127668 0.03207719 0.003657758 0.03179514 0.005112111 0.03179514 0.003653109 0.03179514 0.005112111 0.03207719 0.003657758 0.03207719 0.005117297 0.035604 0.003653109 0.03532207 0.005106389 0.03532207 0.003647983 0.03532207 0.005106389 0.035604 0.003653109 0.035604 0.005112111 0.0363512 0.003647983 0.03370738 0.003650844 0.03620904 0.00364536 0.03370738 0.003650844 0.0363512 0.003647983 0.0363512 0.005106389 0.03370738 0.003650844 0.0363512 0.005106389 0.03120756 0.00374794 0.03120756 0.00374794 0.0363512 0.005106389 0.02871274 0.00393635 0.02871274 0.00393635 0.0363512 0.005106389 0.02622663 0.004215717 0.02622663 0.004215717 0.0363512 0.005106389 0.02375257 0.004585981 0.02375257 0.004585981 0.0363512 0.005106389 0.03620904 0.005103528 0.02375257 0.004585981 0.03620904 0.005103528 0.02129358 0.005046308 0.02129358 0.005046308 0.03371834 0.005143225 0.01885282 0.00559628 0.03371834 0.005143225 0.02129358 0.005046308 0.03620904 0.005103528 0.01885282 0.00559628 0.03371834 0.005143225 0.03123039 0.005262315 0.01885282 0.00559628 0.03123039 0.005262315 0.02874732 0.005460739 0.01885282 0.00559628 0.02874732 0.005460739 0.02627182 0.005738139 0.01885282 0.00559628 0.02627182 0.005738139 0.01643419 0.006235122 0.01643419 0.006235122 0.02627182 0.005738139 0.02380651 0.006094396 0.01643419 0.006235122 0.02380651 0.006094396 0.02135372 0.006529033 0.01643419 0.006235122 0.02135372 0.006529033 0.01404041 0.006962001 0.01404041 0.006962001 0.02135372 0.006529033 0.01891607 0.007041752 0.01404041 0.006962001 0.01891607 0.007041752 0.01167476 0.007775843 0.01167476 0.007775843 0.01891607 0.007041752 0.01649606 0.007631838 0.01167476 0.007775843 0.01649606 0.007631838 0.01409602 0.008298873 0.01167476 0.007775843 0.01409602 0.008298873 0.009340465 0.008675634 0.009340465 0.008675634 0.01409602 0.008298873 0.01171857 0.009042024 0.009340465 0.008675634 0.01171857 0.009042024 0.007040679 0.009660243 0.007040679 0.009660243 0.01171857 0.009042024 0.009365975 0.009860634 0.007040679 0.009660243 0.009365975 0.009860634 0.003536522 0.0112366 0.003536522 0.0112366 0.009365975 0.009860634 0.007040679 0.01075381 0.003536522 0.0112366 0.007040679 0.01075381 0.003536522 0.01197987 -0.007652521 -0.03630352 -0.004972577 -0.03380227 -0.007603824 -0.03380227 -0.004972577 -0.03380227 -0.007652521 -0.03630352 -0.004923999 -0.03630352 -0.02153789 0.005046308 -0.03396302 0.005143225 -0.03645372 0.005103528 -0.03396302 0.005143225 -0.02153789 0.005046308 -0.01909732 0.00559628 -0.03396302 0.005143225 -0.01909732 0.00559628 -0.0314747 0.005262315 -0.0314747 0.005262315 -0.01909732 0.00559628 -0.02899163 0.005460739 -0.02899163 0.005460739 -0.01909732 0.00559628 -0.02651619 0.005738139 -0.02651619 0.005738139 -0.01909732 0.00559628 -0.01667869 0.006235122 -0.02651619 0.005738139 -0.01667869 0.006235122 -0.02405101 0.006094396 -0.02405101 0.006094396 -0.01667869 0.006235122 -0.02159816 0.006529033 -0.02159816 0.006529033 -0.01667869 0.006235122 -0.01428472 0.006962001 -0.02159816 0.006529033 -0.01428472 0.006962001 -0.01916038 0.007041752 -0.01916038 0.007041752 -0.01428472 0.006962001 -0.01191926 0.007775843 -0.01916038 0.007041752 -0.01191926 0.007775843 -0.01674056 0.007631838 -0.01674056 0.007631838 -0.01191926 0.007775843 -0.01434046 0.008298873 -0.01434046 0.008298873 -0.01191926 0.007775843 -0.009584963 0.008675634 -0.01434046 0.008298873 -0.009584963 0.008675634 -0.01196295 0.009042024 -0.01196295 0.009042024 -0.009584963 0.008675634 -0.007285118 0.009660243 -0.01196295 0.009042024 -0.007285118 0.009660243 -0.009610474 0.009860634 -0.009610474 0.009860634 -0.007285118 0.009660243 -0.00378108 0.0112366 -0.009610474 0.009860634 -0.00378108 0.0112366 -0.007285118 0.01075381 -0.007285118 0.01075381 -0.00378108 0.0112366 -0.00378108 0.01197987 -0.03395175 0.003650844 -0.0365957 0.003647983 -0.03645372 0.00364536 -0.0365957 0.003647983 -0.03395175 0.003650844 -0.0365957 0.005106389 -0.0365957 0.005106389 -0.03395175 0.003650844 -0.031452 0.00374794 -0.0365957 0.005106389 -0.031452 0.00374794 -0.02895724 0.00393635 -0.0365957 0.005106389 -0.02895724 0.00393635 -0.02647113 0.004215717 -0.0365957 0.005106389 -0.02647113 0.004215717 -0.02399688 0.004585981 -0.0365957 0.005106389 -0.02399688 0.004585981 -0.03645372 0.005103528 -0.03645372 0.005103528 -0.02399688 0.004585981 -0.02153789 0.005046308 -0.03718549 0.005106389 -0.03746753 0.003653109 -0.03718549 0.003647983 -0.03746753 0.003653109 -0.03718549 0.005106389 -0.03746753 0.005112111 -0.0367769 0.005112111 -0.03705883 0.003657758 -0.0367769 0.003653109 -0.03705883 0.003657758 -0.0367769 0.005112111 -0.03705883 0.005117297 -0.03391379 0.005117297 -0.03401452 0.003659248 -0.03391379 0.003657758 -0.03401452 0.003659248 -0.03391379 0.005117297 -0.03419584 0.003667712 -0.03419584 0.003667712 -0.03391379 0.005117297 -0.03401434 0.005118966 -0.03419584 0.003667712 -0.03401434 0.005118966 -0.03419584 0.005127668 0.002731204 0.03637266 0 0.03651458 2.76001e-6 0.03637266 0 0.03651458 0.002731204 0.03637266 0.002734005 0.03651458 0 0.03651458 0.002734005 0.03651458 0 0.03713166 0 0.03713166 0.002734005 0.03651458 0.002775788 0.03679347 0 0.03713166 0.002775788 0.03679347 0.002887487 0.03705257 0 0.03713166 0.002887487 0.03705257 0.002949655 0.03713166 -0.03087383 0.005117297 -0.03097438 0.003659248 -0.03087383 0.003657758 -0.03097438 0.003659248 -0.03087383 0.005117297 -0.03115588 0.003667712 -0.03115588 0.003667712 -0.03087383 0.005117297 -0.0309742 0.005118966 -0.03115588 0.003667712 -0.0309742 0.005118966 -0.03115588 0.005127668 -0.02514028 0.005138099 -0.02485823 0.003667712 -0.02485823 0.005127668 -0.02485823 0.003667712 -0.02514028 0.005138099 -0.02514028 0.003677845 -0.01746273 0.005144715 -0.01718068 0.003677845 -0.01718068 0.005138099 -0.01718068 0.003677845 -0.01746273 0.005144715 -0.01746273 0.003684282 -0.008633553 0.00514692 -0.008351504 0.003684282 -0.008351504 0.005144715 -0.008351504 0.003684282 -0.008633553 0.00514692 -0.008633553 0.003686428 7.60149e-4 0.005144715 0.001042068 0.003686428 0.001042068 0.00514692 0.001042068 0.003686428 7.60149e-4 0.005144715 7.60149e-4 0.003684282 0.01037579 0.005144715 0.01009374 0.003677845 0.01037579 0.003684282 0.01009374 0.003677845 0.01037579 0.005144715 0.01009374 0.005138099 0.0190292 0.005138099 0.01874727 0.003667712 0.0190292 0.003677845 0.01874727 0.003667712 0.0190292 0.005138099 0.01874727 0.005127668 -0.02906852 0.005138099 -0.02878654 0.003667712 -0.02878654 0.005127668 -0.02878654 0.003667712 -0.02906852 0.005138099 -0.02906852 0.003677845 -0.02173644 0.005138099 -0.02201843 0.003684282 -0.02173644 0.003677845 -0.02201843 0.003684282 -0.02173644 0.005138099 -0.02201843 0.005144715 -0.01351374 0.00514692 -0.01323175 0.003684282 -0.01323175 0.005144715 -0.01323175 0.003684282 -0.01351374 0.00514692 -0.01351374 0.003686428 -0.004119992 0.005144715 -0.003837943 0.003686428 -0.003837943 0.00514692 -0.003837943 0.003686428 -0.004119992 0.005144715 -0.004119992 0.003684282 0.005538225 0.005138099 0.005820155 0.003684282 0.005820155 0.005144715 0.005820155 0.003684282 0.005538225 0.005138099 0.005538225 0.003677845 0.01510077 0.005138099 0.01481872 0.003667712 0.01510077 0.003677845 0.01481872 0.003667712 0.01510077 0.005138099 0.01481872 0.005127668 0.02320563 0.003659248 0.02310508 0.005117297 0.02310508 0.003657758 0.02310508 0.005117297 0.02320563 0.003659248 0.02338707 0.003667712 0.02310508 0.005117297 0.02338707 0.003667712 0.02320539 0.005118966 0.02320539 0.005118966 0.02338707 0.003667712 0.02338707 0.005127668 0.01257652 0.03651458 0.009845256 0.03637266 0.01257359 0.03637266 0.009845256 0.03637266 0.01257652 0.03651458 0.009842514 0.03651458 0.009842514 0.03651458 0.01257652 0.03651458 0.009800672 0.03679347 0.009800672 0.03679347 0.01257652 0.03651458 0.0126183 0.03679347 0.009800672 0.03679347 0.0126183 0.03679347 0.009688973 0.03705257 0.009688973 0.03705257 0.0126183 0.03679347 0.01273006 0.03705257 0.009688973 0.03705257 0.01273006 0.03705257 0.01279217 0.03713166 0.009688973 0.03705257 0.01279217 0.03713166 0.009626746 0.03713166 -0.03695356 0.005117297 -0.0370543 0.003659248 -0.03695356 0.003657758 -0.0370543 0.003659248 -0.03695356 0.005117297 -0.03723561 0.003667712 -0.03723561 0.003667712 -0.03695356 0.005117297 -0.0370543 0.005118966 -0.03723561 0.003667712 -0.0370543 0.005118966 -0.03723561 0.005127668 -0.03299713 0.005138099 -0.03271514 0.003667712 -0.03271514 0.005127668 -0.03271514 0.003667712 -0.03299713 0.005138099 -0.03299713 0.003677845 -0.02657419 0.005144715 -0.0262922 0.003677845 -0.0262922 0.005138099 -0.0262922 0.003677845 -0.02657419 0.005144715 -0.02657419 0.003684282 -0.01839393 0.00514692 -0.01811194 0.003684282 -0.01811194 0.005144715 -0.01811194 0.003684282 -0.01839393 0.00514692 -0.01839393 0.003686428 -0.009000182 0.005144715 -0.008718192 0.003686428 -0.008718192 0.00514692 -0.008718192 0.003686428 -0.009000182 0.005144715 -0.009000182 0.003684282 9.82474e-4 0.005138099 0.001264393 0.003684282 0.001264393 0.005144715 0.001264393 0.003684282 9.82474e-4 0.005138099 9.82474e-4 0.003677845 0.01089048 0.005127668 0.01117247 0.003677845 0.01117247 0.005138099 0.01117247 0.003677845 0.01089048 0.005127668 0.01089048 0.003667712 0.02016586 0.003659248 0.02006494 0.005117297 0.02006494 0.003657758 0.02006494 0.005117297 0.02016586 0.003659248 0.02034693 0.003667712 0.02006494 0.005117297 0.02034693 0.003667712 0.02016562 0.005118966 0.02016562 0.005118966 0.02034693 0.003667712 0.02034693 0.005127668 0.01749759 0.03651458 0.01476651 0.03637266 0.01749503 0.03637266 0.01476651 0.03637266 0.01749759 0.03651458 0.01476377 0.03651458 0.01476377 0.03651458 0.01749759 0.03651458 0.01472193 0.03679347 0.01472193 0.03679347 0.01749759 0.03651458 0.01749759 0.03713166 0.01472193 0.03679347 0.01749759 0.03713166 0.01461023 0.03705257 0.01461023 0.03705257 0.01749759 0.03713166 0.014548 0.03713166 -0.03645372 0.005106389 -0.03707087 0.003659248 -0.03645372 0.003647983 -0.03707087 0.003659248 -0.03645372 0.005106389 -0.03782868 0.003704488 -0.03782868 0.003704488 -0.03645372 0.005106389 -0.03858399 0.003780782 -0.03858399 0.003780782 -0.03645372 0.005106389 -0.03933537 0.003888309 -0.03933537 0.003888309 -0.03645372 0.005106389 -0.04008179 0.004026532 -0.04008179 0.004026532 -0.03645372 0.005106389 -0.04082196 0.004195511 -0.04082196 0.004195511 -0.03645372 0.005106389 -0.04155457 0.004394769 -0.04155457 0.004394769 -0.03645372 0.005106389 -0.04227823 0.004624009 -0.04227823 0.004624009 -0.03645372 0.005106389 -0.04299205 0.004882872 -0.04299205 0.004882872 -0.03645372 0.005106389 -0.04369431 0.005170941 -0.04369431 0.005170941 -0.03645372 0.005106389 -0.03707069 0.005118966 -0.04369431 0.005170941 -0.03707069 0.005118966 -0.03782808 0.005165398 -0.04369431 0.005170941 -0.03782808 0.005165398 -0.03858321 0.005242824 -0.04369431 0.005170941 -0.03858321 0.005242824 -0.04438436 0.00548768 -0.04438436 0.00548768 -0.03858321 0.005242824 -0.03933465 0.005350828 -0.04438436 0.00548768 -0.03933465 0.005350828 -0.0400809 0.005489528 -0.04438436 0.00548768 -0.0400809 0.005489528 -0.04506069 0.005832493 -0.04506069 0.005832493 -0.0400809 0.005489528 -0.04082071 0.005658507 -0.04506069 0.005832493 -0.04082071 0.005658507 -0.04155319 0.005857706 -0.04506069 0.005832493 -0.04155319 0.005857706 -0.04520267 0.005903542 -0.04520267 0.005903542 -0.04155319 0.005857706 -0.04227691 0.006086468 -0.04520267 0.005903542 -0.04227691 0.006086468 -0.04299086 0.006344676 -0.04520267 0.005903542 -0.04299086 0.006344676 -0.04369348 0.006631672 -0.04520267 0.005903542 -0.04369348 0.006631672 -0.04438382 0.006947219 -0.04520267 0.005903542 -0.04438382 0.006947219 -0.04520267 0.00736171 -0.04520267 0.00736171 -0.04438382 0.006947219 -0.04506069 0.007290661 0.01749759 0.03876847 0 0.03800946 0.01749759 0.03800946 0 0.03800946 0.01749759 0.03876847 0 0.03876847 0.03707087 0.003659248 0.03645372 0.005106389 0.03645372 0.003647983 0.03645372 0.005106389 0.03707087 0.003659248 0.03782868 0.003704488 0.03645372 0.005106389 0.03782868 0.003704488 0.03858399 0.003780782 0.03645372 0.005106389 0.03858399 0.003780782 0.03933537 0.003888309 0.03645372 0.005106389 0.03933537 0.003888309 0.04008179 0.004026532 0.03645372 0.005106389 0.04008179 0.004026532 0.04082196 0.004195511 0.03645372 0.005106389 0.04082196 0.004195511 0.04155457 0.004394769 0.03645372 0.005106389 0.04155457 0.004394769 0.04227823 0.004624009 0.03645372 0.005106389 0.04227823 0.004624009 0.04299205 0.004882872 0.03645372 0.005106389 0.04299205 0.004882872 0.04369431 0.005170941 0.03645372 0.005106389 0.04369431 0.005170941 0.03707069 0.005118966 0.03707069 0.005118966 0.04369431 0.005170941 0.03782808 0.005165398 0.03782808 0.005165398 0.04369431 0.005170941 0.03858321 0.005242824 0.03858321 0.005242824 0.04369431 0.005170941 0.04438436 0.00548768 0.03858321 0.005242824 0.04438436 0.00548768 0.03933465 0.005350828 0.03933465 0.005350828 0.04438436 0.00548768 0.0400809 0.005489528 0.0400809 0.005489528 0.04438436 0.00548768 0.04506069 0.005832493 0.0400809 0.005489528 0.04506069 0.005832493 0.04082071 0.005658507 0.04082071 0.005658507 0.04506069 0.005832493 0.04155319 0.005857706 0.04155319 0.005857706 0.04506069 0.005832493 0.04520267 0.005903542 0.04155319 0.005857706 0.04520267 0.005903542 0.04227691 0.006086468 0.04227691 0.006086468 0.04520267 0.005903542 0.04299086 0.006344676 0.04299086 0.006344676 0.04520267 0.005903542 0.04369348 0.006631672 0.04369348 0.006631672 0.04520267 0.005903542 0.04438382 0.006947219 0.04438382 0.006947219 0.04520267 0.005903542 0.04520267 0.00736171 0.04438382 0.006947219 0.04520267 0.00736171 0.04506069 0.007290661 -0.004593491 0.03745734 -0.007870852 0.03731447 -0.004705548 0.03731447 -0.007870852 0.03731447 -0.004593491 0.03745734 -0.007982969 0.03745734 -0.007982969 0.03745734 -0.004593491 0.03745734 -0.008208096 0.03762751 -0.008208096 0.03762751 -0.004593491 0.03745734 -0.004368305 0.03762751 -0.008208096 0.03762751 -0.004368305 0.03762751 -0.004107296 0.03773438 -0.008208096 0.03762751 -0.004107296 0.03773438 -0.008469223 0.03773438 -0.008469223 0.03773438 -0.004107296 0.03773438 -0.008748888 0.0377708 -0.008748888 0.0377708 -0.004107296 0.03773438 -0.003827631 0.0377708 0 0.03731447 -0.003061652 0.03745734 -0.002949595 0.03731447 -0.003061652 0.03745734 0 0.03731447 0 0.03807348 -0.003061652 0.03745734 0 0.03807348 -0.003286838 0.03762751 -0.003286838 0.03762751 0 0.03807348 -0.003547966 0.03773438 -0.003547966 0.03773438 0 0.03807348 -0.003827631 0.0377708 -0.003827631 0.0377708 0 0.03807348 -0.01366996 0.0377708 -0.01366996 0.0377708 0 0.03807348 -0.01749759 0.03807348 -0.01454818 0.03731447 -0.01749759 0.03807348 -0.01749759 0.03731447 -0.01749759 0.03807348 -0.01454818 0.03731447 -0.01443582 0.03745734 -0.01749759 0.03807348 -0.01443582 0.03745734 -0.01421082 0.03762751 -0.01749759 0.03807348 -0.01421082 0.03762751 -0.01394981 0.03773438 -0.01749759 0.03807348 -0.01394981 0.03773438 -0.01366996 0.0377708 -0.009514749 0.03745734 -0.01279211 0.03731447 -0.009626865 0.03731447 -0.01279211 0.03731447 -0.009514749 0.03745734 -0.01290404 0.03745734 -0.01290404 0.03745734 -0.009514749 0.03745734 -0.009289622 0.03762751 -0.01290404 0.03745734 -0.009289622 0.03762751 -0.01312935 0.03762751 -0.01312935 0.03762751 -0.009289622 0.03762751 -0.009028553 0.03773438 -0.01312935 0.03762751 -0.009028553 0.03773438 -0.01339048 0.03773438 -0.01339048 0.03773438 -0.009028553 0.03773438 -0.008748888 0.0377708 -0.01339048 0.03773438 -0.008748888 0.0377708 -0.01366996 0.0377708 -0.01366996 0.0377708 -0.008748888 0.0377708 -0.003827631 0.0377708 -0.004921257 0.0365504 -0.007652521 0.03640842 -0.004923999 0.03640842 -0.007652521 0.03640842 -0.004921257 0.0365504 -0.007655203 0.0365504 -0.007655203 0.0365504 -0.004921257 0.0365504 -0.004879415 0.03682935 -0.007655203 0.0365504 -0.004879415 0.03682935 -0.007696986 0.03682935 -0.007696986 0.03682935 -0.004879415 0.03682935 -0.004767656 0.03708839 -0.007696986 0.03682935 -0.004767656 0.03708839 -0.007808685 0.03708839 -0.007808685 0.03708839 -0.004767656 0.03708839 -0.004705548 0.03716737 -0.007808685 0.03708839 -0.004705548 0.03716737 -0.007870852 0.03716737 0.004923999 -0.03622561 0.007604062 -0.03373527 0.004972398 -0.03373527 0.007604062 -0.03373527 0.004923999 -0.03622561 0.007652521 -0.03622561 0.004972398 -0.03353691 0.007555723 -0.03104639 0.005020797 -0.03104639 0.007555723 -0.03104639 0.004972398 -0.03353691 0.007604062 -0.03353691 0.005069077 -0.02832466 0.007555723 -0.03081518 0.007507443 -0.02832466 0.007555723 -0.03081518 0.005069077 -0.02832466 0.005020797 -0.03081518 0.005069077 -0.02806317 0.007459342 -0.02557289 0.005117118 -0.02557289 0.007459342 -0.02557289 0.005069077 -0.02806317 0.007507443 -0.02806317 0.005117118 -0.02528429 0.007411301 -0.02279371 0.0051651 -0.02279371 0.007411301 -0.02279371 0.005117118 -0.02528429 0.007459342 -0.02528429 0.005212724 -0.0199902 0.007411301 -0.02248072 0.007363677 -0.0199902 0.007411301 -0.02248072 0.005212724 -0.0199902 0.0051651 -0.02248072 0.005260169 -0.01716506 0.007363677 -0.01965558 0.007316291 -0.01716506 0.007363677 -0.01965558 0.005260169 -0.01716506 0.005212724 -0.01965558 0.005307257 -0.01432102 0.007316291 -0.01681154 0.007269263 -0.01432102 0.007316291 -0.01681154 0.005307257 -0.01432102 0.005260169 -0.01681154 0.005353868 -0.01146131 0.007269263 -0.01395183 0.007222533 -0.01146131 0.007269263 -0.01395183 0.005353868 -0.01146131 0.005307257 -0.01395183 0.005353868 -0.01107937 0.007176399 -0.00858885 0.005400121 -0.00858885 0.007176399 -0.00858885 0.005353868 -0.01107937 0.007222533 -0.01107937 0.005400121 -0.008196711 0.007130563 -0.005706191 0.005445778 -0.005706191 0.007130563 -0.005706191 0.005400121 -0.008196711 0.007176399 -0.008196711 0.005491018 -0.002816379 0.007130563 -0.005306959 0.007085442 -0.002816379 0.007130563 -0.005306959 0.005491018 -0.002816379 0.005445778 -0.005306959 0.005587518 6.67286e-4 0.007017314 5.169e-4 0.006988942 6.67286e-4 0.007017314 5.169e-4 0.005587518 6.67286e-4 0.005559146 5.169e-4 0.007017314 5.169e-4 0.005559146 5.169e-4 0.005491018 -0.003194868 0.007017314 5.169e-4 0.005491018 -0.003194868 0.007085442 -0.003194868 0.002484202 0.01197987 0.002339482 0.01130062 0.002484202 0.0112366 0.002339482 0.01130062 0.002484202 0.01197987 -0.00123322 0.01312333 -0.00123322 0.01312333 0.002484202 0.01197987 0.002339482 0.01202952 -0.007017314 0.001286864 -0.005587518 0.001442492 -0.006988942 0.001442492 -0.005587518 0.001442492 -0.007017314 0.001286864 -0.005559146 0.001286864 -0.005559146 0.001286864 -0.007017314 0.001286864 -0.007085442 -0.002554893 -0.005559146 0.001286864 -0.007085442 -0.002554893 -0.005491018 -0.002554893 -0.007130146 -0.005270481 -0.005491018 -0.002769172 -0.007085442 -0.002769172 -0.005491018 -0.002769172 -0.007130146 -0.005270481 -0.005446255 -0.005270481 -0.007175505 -0.008195936 -0.005446255 -0.005694568 -0.007130146 -0.005694568 -0.005446255 -0.005694568 -0.007175505 -0.008195936 -0.005400955 -0.008195936 -0.00722146 -0.01111203 -0.005400955 -0.008610725 -0.007175505 -0.008610725 -0.005400955 -0.008610725 -0.00722146 -0.01111203 -0.005354881 -0.01111203 -0.007268071 -0.01401484 -0.005354881 -0.01151365 -0.00722146 -0.01151365 -0.005354881 -0.01151365 -0.007268071 -0.01401484 -0.005308449 -0.01401484 -0.007315099 -0.01690065 -0.005308449 -0.01439934 -0.007268071 -0.01439934 -0.005308449 -0.01439934 -0.007315099 -0.01690065 -0.005261421 -0.01690065 -0.007315099 -0.01726442 -0.005213916 -0.01976573 -0.005261421 -0.01726442 -0.005213916 -0.01976573 -0.007315099 -0.01726442 -0.007362544 -0.01976573 -0.007410347 -0.02260589 -0.005213916 -0.0201044 -0.007362544 -0.0201044 -0.005213916 -0.0201044 -0.007410347 -0.02260589 -0.005166113 -0.02260589 -0.007458448 -0.02541726 -0.005166113 -0.02291595 -0.007410347 -0.02291595 -0.005166113 -0.02291595 -0.007458448 -0.02541726 -0.005118072 -0.02541726 -0.007506728 -0.02819669 -0.005118072 -0.02569544 -0.007458448 -0.02569544 -0.005118072 -0.02569544 -0.007506728 -0.02819669 -0.005069732 -0.02819669 -0.007555246 -0.03093975 -0.005069732 -0.02843844 -0.007506728 -0.02843844 -0.005069732 -0.02843844 -0.007555246 -0.03093975 -0.005021214 -0.03093975 -0.007603824 -0.03364342 -0.005021214 -0.03114211 -0.007555246 -0.03114211 -0.005021214 -0.03114211 -0.007603824 -0.03364342 -0.004972577 -0.03364342 -0.004805982 0.01130062 -0.004950702 0.01197987 -0.004950702 0.0112366 -0.004950702 0.01197987 -0.004805982 0.01130062 -0.00123322 0.01312333 -0.004950702 0.01197987 -0.00123322 0.01312333 -0.004805982 0.01202952 -0.002682626 -0.03380227 -2.76001e-6 -0.03630352 -5.13962e-5 -0.03380227 -2.76001e-6 -0.03630352 -0.002682626 -0.03380227 -0.002731204 -0.03630352 -0.02144241 0.005046308 -0.03386718 0.005143225 -0.03635787 0.005103528 -0.03386718 0.005143225 -0.02144241 0.005046308 -0.01900184 0.00559628 -0.03386718 0.005143225 -0.01900184 0.00559628 -0.03137922 0.005262315 -0.03137922 0.005262315 -0.01900184 0.00559628 -0.02889615 0.005460739 -0.02889615 0.005460739 -0.01900184 0.00559628 -0.02642071 0.005738139 -0.02642071 0.005738139 -0.01900184 0.00559628 -0.01658302 0.006235122 -0.02642071 0.005738139 -0.01658302 0.006235122 -0.02395528 0.006094396 -0.02395528 0.006094396 -0.01658302 0.006235122 -0.02150255 0.006529033 -0.02150255 0.006529033 -0.01658302 0.006235122 -0.01418924 0.006962001 -0.02150255 0.006529033 -0.01418924 0.006962001 -0.0190649 0.007041752 -0.0190649 0.007041752 -0.01418924 0.006962001 -0.01182359 0.007775843 -0.0190649 0.007041752 -0.01182359 0.007775843 -0.01664489 0.007631838 -0.01664489 0.007631838 -0.01182359 0.007775843 -0.01424485 0.008298873 -0.01424485 0.008298873 -0.01182359 0.007775843 -0.009489297 0.008675634 -0.01424485 0.008298873 -0.009489297 0.008675634 -0.01186734 0.009042024 -0.01186734 0.009042024 -0.009489297 0.008675634 -0.007189512 0.009660243 -0.01186734 0.009042024 -0.007189512 0.009660243 -0.009514808 0.009860634 -0.009514808 0.009860634 -0.007189512 0.009660243 -0.003685355 0.0112366 -0.009514808 0.009860634 -0.003685355 0.0112366 -0.007189512 0.01075381 -0.007189512 0.01075381 -0.003685355 0.0112366 -0.003685355 0.01197987 -0.03385627 0.003650844 -0.03649985 0.003647983 -0.03635787 0.00364536 -0.03649985 0.003647983 -0.03385627 0.003650844 -0.03649985 0.005106389 -0.03649985 0.005106389 -0.03385627 0.003650844 -0.03135639 0.00374794 -0.03649985 0.005106389 -0.03135639 0.00374794 -0.02886176 0.00393635 -0.03649985 0.005106389 -0.02886176 0.00393635 -0.02637565 0.004215717 -0.03649985 0.005106389 -0.02637565 0.004215717 -0.0239014 0.004585981 -0.03649985 0.005106389 -0.0239014 0.004585981 -0.03635787 0.005103528 -0.03635787 0.005103528 -0.0239014 0.004585981 -0.02144241 0.005046308 -0.03645628 0.005106389 -0.03673851 0.003653109 -0.03645628 0.003647983 -0.03673851 0.003653109 -0.03645628 0.005106389 -0.03673851 0.005112111 -0.03482753 0.005112111 -0.03510946 0.003657758 -0.03482753 0.003653109 -0.03510946 0.003657758 -0.03482753 0.005112111 -0.03510946 0.005117297 0.03644675 0.003647983 0.0338031 0.003650844 0.03630489 0.00364536 0.0338031 0.003650844 0.03644675 0.003647983 0.03644675 0.005106389 0.0338031 0.003650844 0.03644675 0.005106389 0.03130304 0.00374794 0.03130304 0.00374794 0.03644675 0.005106389 0.02880859 0.00393635 0.02880859 0.00393635 0.03644675 0.005106389 0.02632248 0.004215717 0.02632248 0.004215717 0.03644675 0.005106389 0.02384823 0.004585981 0.02384823 0.004585981 0.03644675 0.005106389 0.03630489 0.005103528 0.02384823 0.004585981 0.03630489 0.005103528 0.02138924 0.005046308 0.02138924 0.005046308 0.03381425 0.005143225 0.01894867 0.00559628 0.03381425 0.005143225 0.02138924 0.005046308 0.03630489 0.005103528 0.01894867 0.00559628 0.03381425 0.005143225 0.03132605 0.005262315 0.01894867 0.00559628 0.03132605 0.005262315 0.02884298 0.005460739 0.01894867 0.00559628 0.02884298 0.005460739 0.02636754 0.005738139 0.01894867 0.00559628 0.02636754 0.005738139 0.01652973 0.006235122 0.01652973 0.006235122 0.02636754 0.005738139 0.02390199 0.006094396 0.01652973 0.006235122 0.02390199 0.006094396 0.0214492 0.006529033 0.01652973 0.006235122 0.0214492 0.006529033 0.01413589 0.006962001 0.01413589 0.006962001 0.0214492 0.006529033 0.01901179 0.007041752 0.01413589 0.006962001 0.01901179 0.007041752 0.01177024 0.007775843 0.01177024 0.007775843 0.01901179 0.007041752 0.01659154 0.007631838 0.01177024 0.007775843 0.01659154 0.007631838 0.01419156 0.008298873 0.01177024 0.007775843 0.01419156 0.008298873 0.00943619 0.008675634 0.00943619 0.008675634 0.01419156 0.008298873 0.01181405 0.009042024 0.00943619 0.008675634 0.01181405 0.009042024 0.007136285 0.009660243 0.007136285 0.009660243 0.01181405 0.009042024 0.009461641 0.009860634 0.007136285 0.009660243 0.009461641 0.009860634 0.003632247 0.0112366 0.003632247 0.0112366 0.009461641 0.009860634 0.007136285 0.01075381 0.003632247 0.0112366 0.007136285 0.01075381 0.003632247 0.01197987 0 0.0365504 -0.002731204 0.03640842 -2.76001e-6 0.03640842 -0.002731204 0.03640842 0 0.0365504 -0.002734005 0.0365504 -0.002734005 0.0365504 0 0.0365504 0 0.03716737 -0.002734005 0.0365504 0 0.03716737 -0.002775788 0.03682935 -0.002775788 0.03682935 0 0.03716737 -0.002887487 0.03708839 -0.002887487 0.03708839 0 0.03716737 -0.002949595 0.03716737 -0.009845256 0.03640842 -0.01257652 0.0365504 -0.01257359 0.03640842 -0.01257652 0.0365504 -0.009845256 0.03640842 -0.009842514 0.0365504 -0.01257652 0.0365504 -0.009842514 0.0365504 -0.0126183 0.03682935 -0.0126183 0.03682935 -0.009842514 0.0365504 -0.009800672 0.03682935 -0.0126183 0.03682935 -0.009800672 0.03682935 -0.01273006 0.03708839 -0.01273006 0.03708839 -0.009800672 0.03682935 -0.009688973 0.03708839 -0.01273006 0.03708839 -0.009688973 0.03708839 -0.01279211 0.03716737 -0.01279211 0.03716737 -0.009688973 0.03708839 -0.009626865 0.03716737 0.03012782 0.003657758 0.02984577 0.005112111 0.02984577 0.003653109 0.02984577 0.005112111 0.03012782 0.003657758 0.03012782 0.005117297 0.03487479 0.003653109 0.03459274 0.005106389 0.03459274 0.003647983 0.03459274 0.005106389 0.03487479 0.003653109 0.03487479 0.005112111 0.03625535 0.003647983 0.03361177 0.003650844 0.03611356 0.00364536 0.03361177 0.003650844 0.03625535 0.003647983 0.03625535 0.005106389 0.03361177 0.003650844 0.03625535 0.005106389 0.03111189 0.00374794 0.03111189 0.00374794 0.03625535 0.005106389 0.02861726 0.00393635 0.02861726 0.00393635 0.03625535 0.005106389 0.02613115 0.004215717 0.02613115 0.004215717 0.03625535 0.005106389 0.0236569 0.004585981 0.0236569 0.004585981 0.03625535 0.005106389 0.03611356 0.005103528 0.0236569 0.004585981 0.03611356 0.005103528 0.02119791 0.005046308 0.02119791 0.005046308 0.03362286 0.005143225 0.01875734 0.00559628 0.03362286 0.005143225 0.02119791 0.005046308 0.03611356 0.005103528 0.01875734 0.00559628 0.03362286 0.005143225 0.03113472 0.005262315 0.01875734 0.00559628 0.03113472 0.005262315 0.02865165 0.005460739 0.01875734 0.00559628 0.02865165 0.005460739 0.02617621 0.005738139 0.01875734 0.00559628 0.02617621 0.005738139 0.01633834 0.006235122 0.01633834 0.006235122 0.02617621 0.005738139 0.0237106 0.006094396 0.01633834 0.006235122 0.0237106 0.006094396 0.02125805 0.006529033 0.01633834 0.006235122 0.02125805 0.006529033 0.01394474 0.006962001 0.01394474 0.006962001 0.02125805 0.006529033 0.0188204 0.007041752 0.01394474 0.006962001 0.0188204 0.007041752 0.01157891 0.007775843 0.01157891 0.007775843 0.0188204 0.007041752 0.01640021 0.007631838 0.01157891 0.007775843 0.01640021 0.007631838 0.01400017 0.008298873 0.01157891 0.007775843 0.01400017 0.008298873 0.009244799 0.008675634 0.009244799 0.008675634 0.01400017 0.008298873 0.01162266 0.009042024 0.009244799 0.008675634 0.01162266 0.009042024 0.006944954 0.009660243 0.006944954 0.009660243 0.01162266 0.009042024 0.00927031 0.009860634 0.006944954 0.009660243 0.00927031 0.009860634 0.003440916 0.0112366 0.003440916 0.0112366 0.00927031 0.009860634 0.006944954 0.01075381 0.003440916 0.0112366 0.006944954 0.01075381 0.003440916 0.01197987 -0.01257359 -0.03630352 -0.009893894 -0.03380227 -0.01252514 -0.03380227 -0.009893894 -0.03380227 -0.01257359 -0.03630352 -0.009845256 -0.03630352 -0.02163374 0.005046308 -0.03405869 0.005143225 -0.03654927 0.005103528 -0.03405869 0.005143225 -0.02163374 0.005046308 -0.01919317 0.00559628 -0.03405869 0.005143225 -0.01919317 0.00559628 -0.03157061 0.005262315 -0.03157061 0.005262315 -0.01919317 0.00559628 -0.02908754 0.005460739 -0.02908754 0.005460739 -0.01919317 0.00559628 -0.02661204 0.005738139 -0.02661204 0.005738139 -0.01919317 0.00559628 -0.01677441 0.006235122 -0.02661204 0.005738139 -0.01677441 0.006235122 -0.02414667 0.006094396 -0.02414667 0.006094396 -0.01677441 0.006235122 -0.02169388 0.006529033 -0.02169388 0.006529033 -0.01677441 0.006235122 -0.01438057 0.006962001 -0.02169388 0.006529033 -0.01438057 0.006962001 -0.01925629 0.007041752 -0.01925629 0.007041752 -0.01438057 0.006962001 -0.01201474 0.007775843 -0.01925629 0.007041752 -0.01201474 0.007775843 -0.01683622 0.007631838 -0.01683622 0.007631838 -0.01201474 0.007775843 -0.01443624 0.008298873 -0.01443624 0.008298873 -0.01201474 0.007775843 -0.009680688 0.008675634 -0.01443624 0.008298873 -0.009680688 0.008675634 -0.01205873 0.009042024 -0.01205873 0.009042024 -0.009680688 0.008675634 -0.007380843 0.009660243 -0.01205873 0.009042024 -0.007380843 0.009660243 -0.009706139 0.009860634 -0.009706139 0.009860634 -0.007380843 0.009660243 -0.003876686 0.0112366 -0.009706139 0.009860634 -0.003876686 0.0112366 -0.007380843 0.01075381 -0.007380843 0.01075381 -0.003876686 0.0112366 -0.003876686 0.01197987 -0.0340476 0.003650844 -0.03669118 0.003647983 -0.03654927 0.00364536 -0.03669118 0.003647983 -0.0340476 0.003650844 -0.03669118 0.005106389 -0.03669118 0.005106389 -0.0340476 0.003650844 -0.03154772 0.00374794 -0.03669118 0.005106389 -0.03154772 0.00374794 -0.02905309 0.00393635 -0.03669118 0.005106389 -0.02905309 0.00393635 -0.02656698 0.004215717 -0.03669118 0.005106389 -0.02656698 0.004215717 -0.02409273 0.004585981 -0.03669118 0.005106389 -0.02409273 0.004585981 -0.03654927 0.005103528 -0.03654927 0.005103528 -0.02409273 0.004585981 -0.02163374 0.005046308 -0.03791487 0.005106389 -0.03819692 0.003653109 -0.03791487 0.003647983 -0.03819692 0.003653109 -0.03791487 0.005106389 -0.03819692 0.005112111 -0.03872627 0.005112111 -0.0390082 0.003657758 -0.03872627 0.003653109 -0.0390082 0.003657758 -0.03872627 0.005112111 -0.0390082 0.005117297 -0.01476377 0.0365504 -0.01749503 0.03640842 -0.01476651 0.03640842 -0.01749503 0.03640842 -0.01476377 0.0365504 -0.01749759 0.0365504 -0.01749759 0.0365504 -0.01476377 0.0365504 -0.01472193 0.03682935 -0.01749759 0.0365504 -0.01472193 0.03682935 -0.01749759 0.03716737 -0.01749759 0.03716737 -0.01472193 0.03682935 -0.01461023 0.03708839 -0.01749759 0.03716737 -0.01461023 0.03708839 -0.01454818 0.03716737 0.02817845 0.003657758 0.0278964 0.005112111 0.0278964 0.003653109 0.0278964 0.005112111 0.02817845 0.003657758 0.02817845 0.005117297 -0.01749503 -0.03630352 -0.01481515 -0.03380227 -0.01744621 -0.03380227 -0.01481515 -0.03380227 -0.01749503 -0.03630352 -0.01476651 -0.03630352 -0.02172935 0.005046308 -0.03415441 0.005143225 -0.03664505 0.005103528 -0.03415441 0.005143225 -0.02172935 0.005046308 -0.01928865 0.00559628 -0.03415441 0.005143225 -0.01928865 0.00559628 -0.0316661 0.005262315 -0.0316661 0.005262315 -0.01928865 0.00559628 -0.02918303 0.005460739 -0.02918303 0.005460739 -0.01928865 0.00559628 -0.02670753 0.005738139 -0.02670753 0.005738139 -0.01928865 0.00559628 -0.01687008 0.006235122 -0.02670753 0.005738139 -0.01687008 0.006235122 -0.02424234 0.006094396 -0.02424234 0.006094396 -0.01687008 0.006235122 -0.02178955 0.006529033 -0.02178955 0.006529033 -0.01687008 0.006235122 -0.01447618 0.006962001 -0.02178955 0.006529033 -0.01447618 0.006962001 -0.01935184 0.007041752 -0.01935184 0.007041752 -0.01447618 0.006962001 -0.01211059 0.007775843 -0.01935184 0.007041752 -0.01211059 0.007775843 -0.01693189 0.007631838 -0.01693189 0.007631838 -0.01211059 0.007775843 -0.01453191 0.008298873 -0.01453191 0.008298873 -0.01211059 0.007775843 -0.009776353 0.008675634 -0.01453191 0.008298873 -0.009776353 0.008675634 -0.0121544 0.009042024 -0.0121544 0.009042024 -0.009776353 0.008675634 -0.007476508 0.009660243 -0.0121544 0.009042024 -0.007476508 0.009660243 -0.009801805 0.009860634 -0.009801805 0.009860634 -0.007476508 0.009660243 -0.003972411 0.0112366 -0.009801805 0.009860634 -0.003972411 0.0112366 -0.007476508 0.01075381 -0.007476508 0.01075381 -0.003972411 0.0112366 -0.003972411 0.01197987 -0.03414314 0.003650844 -0.03678703 0.003647983 -0.03664505 0.00364536 -0.03678703 0.003647983 -0.03414314 0.003650844 -0.03678703 0.005106389 -0.03678703 0.005106389 -0.03414314 0.003650844 -0.03164339 0.00374794 -0.03678703 0.005106389 -0.03164339 0.00374794 -0.02914857 0.00393635 -0.03678703 0.005106389 -0.02914857 0.00393635 -0.02666246 0.004215717 -0.03678703 0.005106389 -0.02666246 0.004215717 -0.02418828 0.004585981 -0.03678703 0.005106389 -0.02418828 0.004585981 -0.03664505 0.005103528 -0.03664505 0.005103528 -0.02418828 0.004585981 -0.02172935 0.005046308 0.03414577 0.003653109 0.03386372 0.005106389 0.03386372 0.003647983 0.03386372 0.005106389 0.03414577 0.003653109 0.03414577 0.005112111 0.03615987 0.003647983 0.03351593 0.003650844 0.03601789 0.00364536 0.03351593 0.003650844 0.03615987 0.003647983 0.03615987 0.005106389 0.03351593 0.003650844 0.03615987 0.005106389 0.03101623 0.00374794 0.03101623 0.00374794 0.03615987 0.005106389 0.02852135 0.00393635 0.02852135 0.00393635 0.03615987 0.005106389 0.0260353 0.004215717 0.0260353 0.004215717 0.03615987 0.005106389 0.02356112 0.004585981 0.02356112 0.004585981 0.03615987 0.005106389 0.03601789 0.005103528 0.02356112 0.004585981 0.03601789 0.005103528 0.02110219 0.005046308 0.02110219 0.005046308 0.03352719 0.005143225 0.01866149 0.00559628 0.03352719 0.005143225 0.02110219 0.005046308 0.03601789 0.005103528 0.01866149 0.00559628 0.03352719 0.005143225 0.03103888 0.005262315 0.01866149 0.00559628 0.03103888 0.005262315 0.02855587 0.005460739 0.01866149 0.00559628 0.02855587 0.005460739 0.02608031 0.005738139 0.01866149 0.00559628 0.02608031 0.005738139 0.01624286 0.006235122 0.01624286 0.006235122 0.02608031 0.005738139 0.02361512 0.006094396 0.01624286 0.006235122 0.02361512 0.006094396 0.02116239 0.006529033 0.01624286 0.006235122 0.02116239 0.006529033 0.01384902 0.006962001 0.01384902 0.006962001 0.02116239 0.006529033 0.01872462 0.007041752 0.01384902 0.006962001 0.01872462 0.007041752 0.01148343 0.007775843 0.01148343 0.007775843 0.01872462 0.007041752 0.01630467 0.007631838 0.01148343 0.007775843 0.01630467 0.007631838 0.01390469 0.008298873 0.01148343 0.007775843 0.01390469 0.008298873 0.009149134 0.008675634 0.009149134 0.008675634 0.01390469 0.008298873 0.01152718 0.009042024 0.009149134 0.008675634 0.01152718 0.009042024 0.006849348 0.009660243 0.006849348 0.009660243 0.01152718 0.009042024 0.009174585 0.009860634 0.006849348 0.009660243 0.009174585 0.009860634 0.003345251 0.0112366 0.003345251 0.0112366 0.009174585 0.009860634 0.006849348 0.01075381 0.003345251 0.0112366 0.006849348 0.01075381 0.003345251 0.01197987 0 0.03815776 -0.01749759 0.03891658 -0.01749759 0.03815776 -0.01749759 0.03891658 0 0.03815776 0 0.03891658 0 0.03969568 -0.01749759 0.03893673 0 0.03893673 -0.01749759 0.03893673 0 0.03969568 -0.01749759 0.03969568 0 0.0396502 -0.01749759 0.04040908 -0.01749759 0.0396502 -0.01749759 0.04040908 0 0.0396502 0 0.04040908 0 0.04029697 -0.01749759 0.04105579 -0.01749759 0.04029697 -0.01749759 0.04105579 0 0.04029697 0 0.04105579 0 0.04163479 -0.01749759 0.04087591 0 0.04087591 -0.01749759 0.04087591 0 0.04163479 -0.01749759 0.04163479 0 0.04214513 -0.01749759 0.04138594 0 0.04138594 -0.01749759 0.04138594 0 0.04214513 -0.01749759 0.04214513 0 0.04258573 -0.01749759 0.04182666 0 0.04182666 -0.01749759 0.04182666 0 0.04258573 -0.01749759 0.04258573 0 0.04295593 -0.01749759 0.04219681 0 0.04219681 -0.01749759 0.04219681 0 0.04295593 -0.01749759 0.04295593 0 0.04325515 -0.01749759 0.04249614 0 0.04249614 -0.01749759 0.04249614 0 0.04325515 -0.01749759 0.04325515 0 0.04348284 -0.01749759 0.04272389 0 0.04272389 -0.01749759 0.04272389 0 0.04348284 -0.01749759 0.04348284 0 0.04372256 -0.01749759 0.04356408 0 0.04356408 -0.01749759 0.04356408 0 0.04372256 -0.01749759 0.04372256 -0.01749759 0.04372256 0 0.04372256 -1.58532e-5 0.04431521 -0.01749759 0.04372256 -1.58532e-5 0.04431521 -0.01748192 0.04431521 -0.01748192 0.04431521 -1.58532e-5 0.04431521 -0.01743423 0.04490596 -0.01743423 0.04490596 -1.58532e-5 0.04431521 -6.3356e-5 0.04490596 -0.01743423 0.04490596 -6.3356e-5 0.04490596 -0.01735544 0.04549229 -0.01735544 0.04549229 -6.3356e-5 0.04490596 -1.42339e-4 0.04549229 -0.01735544 0.04549229 -1.42339e-4 0.04549229 -0.01724529 0.04607224 -0.01724529 0.04607224 -1.42339e-4 0.04549229 -2.52519e-4 0.04607224 -0.01724529 0.04607224 -2.52519e-4 0.04607224 -3.93503e-4 0.04664385 -0.01724529 0.04607224 -3.93503e-4 0.04664385 -0.01710408 0.04664385 -0.01710408 0.04664385 -3.93503e-4 0.04664385 -4.4867e-4 0.04682457 -0.01710408 0.04664385 -4.4867e-4 0.04682457 -0.01704913 0.04682457 -0.04465919 0.00736171 -0.04518955 0.006168544 -0.04465919 0.005903542 -0.04518955 0.006168544 -0.04465919 0.00736171 -0.04518955 0.007626712 0.01749759 0.04291176 0 0.04307061 0 0.04291176 0 0.04307061 0.01749759 0.04291176 0.01749759 0.04307061 0 0.04307061 0.01749759 0.04307061 0.01748192 0.04366332 0 0.04307061 0.01748192 0.04366332 1.58532e-5 0.04366332 1.58532e-5 0.04366332 0.01748192 0.04366332 0.01743423 0.04425364 1.58532e-5 0.04366332 0.01743423 0.04425364 6.3356e-5 0.04425364 6.3356e-5 0.04425364 0.01743423 0.04425364 0.01735544 0.04483997 6.3356e-5 0.04425364 0.01735544 0.04483997 1.42339e-4 0.04483997 1.42339e-4 0.04483997 0.01735544 0.04483997 0.01724529 0.04542011 1.42339e-4 0.04483997 0.01724529 0.04542011 2.52519e-4 0.04542011 2.52519e-4 0.04542011 0.01724529 0.04542011 0.01710408 0.04599153 2.52519e-4 0.04542011 0.01710408 0.04599153 3.93503e-4 0.04599153 3.93503e-4 0.04599153 0.01710408 0.04599153 0.01704913 0.04617244 3.93503e-4 0.04599153 0.01704913 0.04617244 4.4867e-4 0.04617244 0.01749759 0.04279202 0 0.04203265 0.01749759 0.04203265 0 0.04203265 0.01749759 0.04279202 0 0.04279202 0.01749759 0.04262638 0 0.04186701 0.01749759 0.04186701 0 0.04186701 0.01749759 0.04262638 0 0.04262638 0.01749759 0.04238879 0 0.04162985 0.01749759 0.04162985 0 0.04162985 0.01749759 0.04238879 0 0.04238879 0.01749759 0.04208034 0 0.04132097 0.01749759 0.04132097 0 0.04132097 0.01749759 0.04208034 0 0.04208034 0.01749759 0.04170078 0 0.04094171 0.01749759 0.04094171 0 0.04094171 0.01749759 0.04170078 0 0.04170078 0.01749759 0.04049193 0 0.0412513 0 0.04049193 0 0.0412513 0.01749759 0.04049193 0.01749759 0.0412513 0.01749759 0.04073232 0 0.03997308 0.01749759 0.03997308 0 0.03997308 0.01749759 0.04073232 0 0.04073232 0.01749759 0.03938555 0 0.04014486 0 0.03938555 0 0.04014486 0.01749759 0.03938555 0.01749759 0.04014486 0.01749759 0.03873074 0 0.03948992 0 0.03873074 0 0.03948992 0.01749759 0.03873074 0.01749759 0.03948992 0.04571259 0.006168544 0.04518228 0.00736171 0.04518228 0.005903542 0.04518228 0.00736171 0.04571259 0.006168544 0.04571259 0.007626712 0.005587518 2.40273e-4 0.006988942 2.40273e-4 0.00628823 0.003910422 -0.005587518 0.00210762 -0.00628823 0.006056845 -0.006988942 0.00210762 -0.002682626 -0.03364342 -9.99958e-5 -0.03114211 -0.002633929 -0.03114211 -9.99958e-5 -0.03114211 -0.002682626 -0.03364342 -5.13962e-5 -0.03364342 -0.003840804 0.01130062 -0.003985643 0.01197987 -0.003985643 0.0112366 -0.003985643 0.01197987 -0.003840804 0.01130062 -2.68094e-4 0.01312333 -0.003985643 0.01197987 -2.68094e-4 0.01312333 -0.003840804 0.01202952 6.37941e-4 5.169e-4 0.002067685 6.67286e-4 6.6633e-4 6.67286e-4 0.002067685 6.67286e-4 6.37941e-4 5.169e-4 0.002095997 5.169e-4 0.002095997 5.169e-4 6.37941e-4 5.169e-4 0.002164185 -0.003194868 0.002164185 -0.003194868 6.37941e-4 5.169e-4 5.69819e-4 -0.003194868 5.69819e-4 -0.002816379 0.002209365 -0.005306959 0.002164185 -0.002816379 0.002209365 -0.005306959 5.69819e-4 -0.002816379 5.24614e-4 -0.005306959 4.78877e-4 -0.008196711 0.002209365 -0.005706191 5.24614e-4 -0.005706191 0.002209365 -0.005706191 4.78877e-4 -0.008196711 0.002255082 -0.008196711 4.78877e-4 -0.00858885 0.002301335 -0.01107937 0.002255082 -0.00858885 0.002301335 -0.01107937 4.78877e-4 -0.00858885 4.32657e-4 -0.01107937 4.32657e-4 -0.01146131 0.002347946 -0.01395183 0.002301335 -0.01146131 0.002347946 -0.01395183 4.32657e-4 -0.01146131 3.85999e-4 -0.01395183 3.38952e-4 -0.01681154 0.002347946 -0.01432102 3.85999e-4 -0.01432102 0.002347946 -0.01432102 3.38952e-4 -0.01681154 0.002394974 -0.01681154 2.91562e-4 -0.01965558 0.002394974 -0.01716506 3.38952e-4 -0.01716506 0.002394974 -0.01716506 2.91562e-4 -0.01965558 0.002442419 -0.01965558 2.91562e-4 -0.0199902 0.002490103 -0.02248072 0.002442419 -0.0199902 0.002490103 -0.02248072 2.91562e-4 -0.0199902 2.43879e-4 -0.02248072 1.9595e-4 -0.02528429 0.002490103 -0.02279371 2.43879e-4 -0.02279371 0.002490103 -0.02279371 1.9595e-4 -0.02528429 0.002538025 -0.02528429 1.47825e-4 -0.02806317 0.002538025 -0.02557289 1.9595e-4 -0.02557289 0.002538025 -0.02557289 1.47825e-4 -0.02806317 0.002586126 -0.02806317 9.95518e-5 -0.03081518 0.002586126 -0.02832466 1.47825e-4 -0.02832466 0.002586126 -0.02832466 9.95518e-5 -0.03081518 0.002634406 -0.03081518 9.95518e-5 -0.03104639 0.002682805 -0.03353691 0.002634406 -0.03104639 0.002682805 -0.03353691 9.95518e-5 -0.03104639 5.11806e-5 -0.03353691 2.76001e-6 -0.03622561 0.002682805 -0.03373527 5.11806e-5 -0.03373527 0.002682805 -0.03373527 2.76001e-6 -0.03622561 0.002731204 -0.03622561 -0.002633929 -0.03093975 -1.48494e-4 -0.02843844 -0.00258553 -0.02843844 -1.48494e-4 -0.02843844 -0.002633929 -0.03093975 -9.99958e-5 -0.03093975 -0.00258553 -0.02819669 -1.96826e-4 -0.02569544 -0.002537131 -0.02569544 -1.96826e-4 -0.02569544 -0.00258553 -0.02819669 -1.48494e-4 -0.02819669 -0.002537131 -0.02541726 -2.44927e-4 -0.02291595 -0.00248903 -0.02291595 -2.44927e-4 -0.02291595 -0.002537131 -0.02541726 -1.96826e-4 -0.02541726 -0.00248903 -0.02260589 -2.92732e-4 -0.0201044 -0.002441287 -0.0201044 -2.92732e-4 -0.0201044 -0.00248903 -0.02260589 -2.44927e-4 -0.02260589 -0.002393782 -0.01726442 -2.92732e-4 -0.01976573 -3.40178e-4 -0.01726442 -2.92732e-4 -0.01976573 -0.002393782 -0.01726442 -0.002441287 -0.01976573 -0.002393782 -0.01690065 -3.87201e-4 -0.01439934 -0.002346754 -0.01439934 -3.87201e-4 -0.01439934 -0.002393782 -0.01690065 -3.40178e-4 -0.01690065 -0.002346754 -0.01401484 -4.33739e-4 -0.01151365 -0.002300262 -0.01151365 -4.33739e-4 -0.01151365 -0.002346754 -0.01401484 -3.87201e-4 -0.01401484 -0.002300262 -0.01111203 -4.79728e-4 -0.008610725 -0.002254188 -0.008610725 -4.79728e-4 -0.008610725 -0.002300262 -0.01111203 -4.33739e-4 -0.01111203 -0.002254188 -0.008195936 -5.25109e-4 -0.005694568 -0.002208888 -0.005694568 -5.25109e-4 -0.005694568 -0.002254188 -0.008195936 -4.79728e-4 -0.008195936 -0.002208888 -0.005270481 -5.69819e-4 -0.002769172 -0.002164185 -0.002769172 -5.69819e-4 -0.002769172 -0.002208888 -0.005270481 -5.25109e-4 -0.005270481 -0.002095997 0.001286864 -6.6633e-4 0.001442492 -0.002067685 0.001442492 -6.6633e-4 0.001442492 -0.002095997 0.001286864 -6.37941e-4 0.001286864 -6.37941e-4 0.001286864 -0.002095997 0.001286864 -5.69819e-4 -0.002554893 -5.69819e-4 -0.002554893 -0.002095997 0.001286864 -0.002164185 -0.002554893 0.00344944 0.01197987 0.00330466 0.01130062 0.00344944 0.0112366 0.00330466 0.01130062 0.00344944 0.01197987 -2.68094e-4 0.01312333 -2.68094e-4 0.01312333 0.00344944 0.01197987 0.00330466 0.01202952 0.009845256 -0.03622561 0.01252532 -0.03373527 0.009893655 -0.03373527 0.01252532 -0.03373527 0.009845256 -0.03622561 0.01257359 -0.03622561 0.009942054 -0.03104639 0.01252532 -0.03353691 0.01247698 -0.03104639 0.01252532 -0.03353691 0.009942054 -0.03104639 0.009893655 -0.03353691 0.009990334 -0.02832466 0.01247698 -0.03081518 0.0124287 -0.02832466 0.01247698 -0.03081518 0.009990334 -0.02832466 0.009942054 -0.03081518 0.01003825 -0.02557289 0.0124287 -0.02806317 0.01238054 -0.02557289 0.0124287 -0.02806317 0.01003825 -0.02557289 0.009990334 -0.02806317 0.01008617 -0.02279371 0.01238054 -0.02528429 0.01233249 -0.02279371 0.01238054 -0.02528429 0.01008617 -0.02279371 0.01003825 -0.02528429 0.01013404 -0.0199902 0.01233249 -0.02248072 0.01228499 -0.0199902 0.01233249 -0.02248072 0.01013404 -0.0199902 0.01008617 -0.02248072 0.01013404 -0.01965558 0.01223737 -0.01716506 0.01018124 -0.01716506 0.01223737 -0.01716506 0.01013404 -0.01965558 0.01228499 -0.01965558 0.01022851 -0.01432102 0.01223737 -0.01681154 0.01219052 -0.01432102 0.01223737 -0.01681154 0.01022851 -0.01432102 0.01018124 -0.01681154 0.01027494 -0.01146131 0.01219052 -0.01395183 0.01214385 -0.01146131 0.01219052 -0.01395183 0.01027494 -0.01146131 0.01022851 -0.01395183 0.01032119 -0.00858885 0.01214385 -0.01107937 0.01209747 -0.00858885 0.01214385 -0.01107937 0.01032119 -0.00858885 0.01027494 -0.01107937 0.01032119 -0.008196711 0.01205188 -0.005706191 0.01036691 -0.005706191 0.01205188 -0.005706191 0.01032119 -0.008196711 0.01209747 -0.008196711 0.01036691 -0.005306959 0.0120067 -0.002816379 0.01041215 -0.002816379 0.0120067 -0.002816379 0.01036691 -0.005306959 0.01205188 -0.005306959 0.01050865 6.67286e-4 0.01193857 5.169e-4 0.0119102 6.67286e-4 0.01193857 5.169e-4 0.01050865 6.67286e-4 0.01048046 5.169e-4 0.01193857 5.169e-4 0.01048046 5.169e-4 0.01041215 -0.003194868 0.01193857 5.169e-4 0.01041215 -0.003194868 0.0120067 -0.003194868 0.001519024 0.01197987 0.001374423 0.01130062 0.001519024 0.0112366 0.001374423 0.01130062 0.001519024 0.01197987 -0.002198338 0.01312333 -0.002198338 0.01312333 0.001519024 0.01197987 0.001374423 0.01202952 -0.01193857 0.001286864 -0.01050865 0.001442492 -0.0119102 0.001442492 -0.01050865 0.001442492 -0.01193857 0.001286864 -0.01048046 0.001286864 -0.01048046 0.001286864 -0.01193857 0.001286864 -0.0120067 -0.002554893 -0.01048046 0.001286864 -0.0120067 -0.002554893 -0.01041215 -0.002554893 -0.0120514 -0.005270481 -0.01041215 -0.002769172 -0.0120067 -0.002769172 -0.01041215 -0.002769172 -0.0120514 -0.005270481 -0.01036763 -0.005270481 -0.01209682 -0.008195936 -0.01036763 -0.005694568 -0.0120514 -0.005694568 -0.01036763 -0.005694568 -0.01209682 -0.008195936 -0.01032221 -0.008195936 -0.01214259 -0.01111203 -0.01032221 -0.008610725 -0.01209682 -0.008610725 -0.01032221 -0.008610725 -0.01214259 -0.01111203 -0.01027607 -0.01111203 -0.01218914 -0.01401484 -0.01027607 -0.01151365 -0.01214259 -0.01151365 -0.01027607 -0.01151365 -0.01218914 -0.01401484 -0.01022952 -0.01401484 -0.01223617 -0.01690065 -0.01022952 -0.01439934 -0.01218914 -0.01439934 -0.01022952 -0.01439934 -0.01223617 -0.01690065 -0.01018249 -0.01690065 -0.0122838 -0.01976573 -0.01018249 -0.01726442 -0.01223617 -0.01726442 -0.01018249 -0.01726442 -0.0122838 -0.01976573 -0.01013523 -0.01976573 -0.0123316 -0.02260589 -0.01013523 -0.0201044 -0.0122838 -0.0201044 -0.01013523 -0.0201044 -0.0123316 -0.02260589 -0.01008743 -0.02260589 -0.01237952 -0.02541726 -0.01008743 -0.02291595 -0.0123316 -0.02291595 -0.01008743 -0.02291595 -0.01237952 -0.02541726 -0.01003921 -0.02541726 -0.01242786 -0.02819669 -0.01003921 -0.02569544 -0.01237952 -0.02569544 -0.01003921 -0.02569544 -0.01242786 -0.02819669 -0.00999099 -0.02819669 -0.0124765 -0.03093975 -0.00999099 -0.02843844 -0.01242786 -0.02843844 -0.00999099 -0.02843844 -0.0124765 -0.03093975 -0.009942471 -0.03093975 -0.01252514 -0.03364342 -0.009942471 -0.03114211 -0.0124765 -0.03114211 -0.009942471 -0.03114211 -0.01252514 -0.03364342 -0.009893894 -0.03364342 -0.00577116 0.01130062 -0.00591588 0.01197987 -0.00591588 0.0112366 -0.00591588 0.01197987 -0.00577116 0.01130062 -0.002198338 0.01312333 -0.00591588 0.01197987 -0.002198338 0.01312333 -0.00577116 0.01202952 0.01476651 -0.03622561 0.01744645 -0.03373527 0.01481491 -0.03373527 0.01744645 -0.03373527 0.01476651 -0.03622561 0.01749503 -0.03622561 -0.01744621 -0.03364342 -0.01486361 -0.03114211 -0.01739782 -0.03114211 -0.01486361 -0.03114211 -0.01744621 -0.03364342 -0.01481515 -0.03364342 -0.01739782 -0.03093975 -0.01491206 -0.02843844 -0.0173493 -0.02843844 -0.01491206 -0.02843844 -0.01739782 -0.03093975 -0.01486361 -0.03093975 -0.0173493 -0.02819669 -0.0149604 -0.02569544 -0.01730096 -0.02569544 -0.0149604 -0.02569544 -0.0173493 -0.02819669 -0.01491206 -0.02819669 -0.01730096 -0.02541726 -0.0150085 -0.02291595 -0.01725286 -0.02291595 -0.0150085 -0.02291595 -0.01730096 -0.02541726 -0.0149604 -0.02541726 -0.01725286 -0.02260589 -0.01505649 -0.0201044 -0.01720494 -0.0201044 -0.01505649 -0.0201044 -0.01725286 -0.02260589 -0.0150085 -0.02260589 -0.01715761 -0.01726442 -0.01505649 -0.01976573 -0.01510375 -0.01726442 -0.01505649 -0.01976573 -0.01715761 -0.01726442 -0.01720494 -0.01976573 -0.01715761 -0.01690065 -0.01515096 -0.01439934 -0.01711058 -0.01439934 -0.01515096 -0.01439934 -0.01715761 -0.01690065 -0.01510375 -0.01690065 -0.01711058 -0.01401484 -0.01519733 -0.01151365 -0.01706403 -0.01151365 -0.01519733 -0.01151365 -0.01711058 -0.01401484 -0.01515096 -0.01401484 -0.01706403 -0.01111203 -0.01524347 -0.008610725 -0.01701802 -0.008610725 -0.01524347 -0.008610725 -0.01706403 -0.01111203 -0.01519733 -0.01111203 -0.01701802 -0.008195936 -0.01528877 -0.005694568 -0.01697266 -0.005694568 -0.01528877 -0.005694568 -0.01701802 -0.008195936 -0.01524347 -0.008195936 -0.01697266 -0.005270481 -0.01533359 -0.002769172 -0.01692777 -0.002769172 -0.01533359 -0.002769172 -0.01697266 -0.005270481 -0.01528877 -0.005270481 -0.01685971 0.001286864 -0.01543009 0.001442492 -0.01683127 0.001442492 -0.01543009 0.001442492 -0.01685971 0.001286864 -0.01540172 0.001286864 -0.01540172 0.001286864 -0.01685971 0.001286864 -0.01692777 -0.002554893 -0.01540172 0.001286864 -0.01692777 -0.002554893 -0.01533359 -0.002554893 -0.006736278 0.01130062 -0.006881058 0.01197987 -0.006881058 0.0112366 -0.006881058 0.01197987 -0.006736278 0.01130062 -0.003163397 0.01312333 -0.006881058 0.01197987 -0.003163397 0.01312333 -0.006736278 0.01202952 0.01543009 6.67286e-4 0.01685971 5.169e-4 0.01683127 6.67286e-4 0.01685971 5.169e-4 0.01543009 6.67286e-4 0.01540172 5.169e-4 0.01685971 5.169e-4 0.01540172 5.169e-4 0.01533359 -0.003194868 0.01685971 5.169e-4 0.01533359 -0.003194868 0.01692777 -0.003194868 0.01528835 -0.005306959 0.01692777 -0.002816379 0.01533359 -0.002816379 0.01692777 -0.002816379 0.01528835 -0.005306959 0.01697301 -0.005306959 0.01524245 -0.008196711 0.01697301 -0.005706191 0.01528835 -0.005706191 0.01697301 -0.005706191 0.01524245 -0.008196711 0.01701891 -0.008196711 0.01519638 -0.01107937 0.01701891 -0.00858885 0.01524245 -0.00858885 0.01701891 -0.00858885 0.01519638 -0.01107937 0.01706492 -0.01107937 0.01514977 -0.01395183 0.01706492 -0.01146131 0.01519638 -0.01146131 0.01706492 -0.01146131 0.01514977 -0.01395183 0.01711159 -0.01395183 0.01514977 -0.01432102 0.01715886 -0.01681154 0.01711159 -0.01432102 0.01715886 -0.01681154 0.01514977 -0.01432102 0.01510268 -0.01681154 0.01510268 -0.01716506 0.01720625 -0.01965558 0.01715886 -0.01716506 0.01720625 -0.01965558 0.01510268 -0.01716506 0.01505511 -0.01965558 0.01505511 -0.0199902 0.01725393 -0.02248072 0.01720625 -0.0199902 0.01725393 -0.02248072 0.01505511 -0.0199902 0.01500761 -0.02248072 0.01500761 -0.02279371 0.01730167 -0.02528429 0.01725393 -0.02279371 0.01730167 -0.02528429 0.01500761 -0.02279371 0.01495969 -0.02528429 0.01495969 -0.02557289 0.01734977 -0.02806317 0.01730167 -0.02557289 0.01734977 -0.02806317 0.01495969 -0.02557289 0.01491159 -0.02806317 0.01491159 -0.02832466 0.01739805 -0.03081518 0.01734977 -0.02832466 0.01739805 -0.03081518 0.01491159 -0.02832466 0.01486331 -0.03081518 0.01481491 -0.03353691 0.01739805 -0.03104639 0.01486331 -0.03104639 0.01739805 -0.03104639 0.01481491 -0.03353691 0.01744645 -0.03353691 5.54061e-4 0.01197987 4.09307e-4 0.01130062 5.54061e-4 0.0112366 4.09307e-4 0.01130062 5.54061e-4 0.01197987 -0.003163397 0.01312333 -0.003163397 0.01312333 5.54061e-4 0.01197987 4.09307e-4 0.01202952 -5.64787e-4 0.04742926 -0.01704913 0.04705184 -4.4867e-4 0.04705184 -0.01704913 0.04705184 -5.64787e-4 0.04742926 -0.01693302 0.04742926 -0.01693302 0.04742926 -5.64787e-4 0.04742926 -7.65758e-4 0.04797333 -0.01693302 0.04742926 -7.65758e-4 0.04797333 -0.01673185 0.04797333 -0.01673185 0.04797333 -7.65758e-4 0.04797333 -8.87622e-4 0.04825413 -0.01673185 0.04797333 -8.87622e-4 0.04825413 -0.01661014 0.04825413 -0.03972852 0.008668065 -0.03989923 0.007290661 -0.03972852 0.007209897 -0.03989923 0.007290661 -0.03972852 0.008668065 -0.04025882 0.00745362 -0.04025882 0.00745362 -0.03972852 0.008668065 -0.04025882 0.008911728 -0.04025882 0.008911728 -0.03972852 0.008668065 -0.03989923 0.008748888 -0.04101741 0.00841242 -0.04154753 0.007209897 -0.04101741 0.006954193 -0.04154753 0.007209897 -0.04101741 0.00841242 -0.04154753 0.008668065 -0.04215878 0.008153021 -0.04268908 0.006954193 -0.04215878 0.006694853 -0.04268908 0.006954193 -0.04215878 0.008153021 -0.04268908 0.00841242 -0.04314827 0.00789082 -0.04367882 0.006694853 -0.04314827 0.006432712 -0.04367882 0.006694853 -0.04314827 0.00789082 -0.04367882 0.008153021 -0.04398304 0.007626712 -0.04451334 0.006432712 -0.04398304 0.006168544 -0.04451334 0.006432712 -0.04398304 0.007626712 -0.04451334 0.00789082 0.04608047 0.006432712 0.04555016 0.007626712 0.04555016 0.006168544 0.04555016 0.007626712 0.04608047 0.006432712 0.04608047 0.00789082 0.04628479 0.006694853 0.04575443 0.00789082 0.04575443 0.006432712 0.04575443 0.00789082 0.04628479 0.006694853 0.04628479 0.008153021 0.04632443 0.006954193 0.04579401 0.008153021 0.04579401 0.006694853 0.04579401 0.008153021 0.04632443 0.006954193 0.04632443 0.00841242 0.04619938 0.007209897 0.0456689 0.00841242 0.0456689 0.006954193 0.0456689 0.00841242 0.04619938 0.007209897 0.04619938 0.008668065 0.0455507 0.007290661 0.04537969 0.008668065 0.04537969 0.007209897 0.04537969 0.008668065 0.0455507 0.007290661 0.04591012 0.00745362 0.04537969 0.008668065 0.04591012 0.00745362 0.04591012 0.008911728 0.04537969 0.008668065 0.04591012 0.008911728 0.0455507 0.008748888 0.01693302 0.0467996 4.4867e-4 0.04642242 0.01704913 0.04642242 4.4867e-4 0.04642242 0.01693302 0.0467996 5.64787e-4 0.0467996 5.64787e-4 0.0467996 0.01693302 0.0467996 0.01673185 0.04734373 5.64787e-4 0.0467996 0.01673185 0.04734373 7.65758e-4 0.04734373 7.65758e-4 0.04734373 0.01673185 0.04734373 0.01661014 0.04762434 7.65758e-4 0.04734373 0.01661014 0.04762434 8.87622e-4 0.04762434 -6.6633e-4 0.00210762 -0.001366913 0.006056845 -0.002067685 0.00210762 0.002067685 2.40273e-4 0.001366913 0.003910422 6.6633e-4 2.40273e-4 0.01050865 2.40273e-4 0.0119102 2.40273e-4 0.0112093 0.003910422 -0.01050865 0.00210762 -0.0112093 0.006056845 -0.0119102 0.00210762 -0.01543009 0.00210762 -0.01613074 0.006056845 -0.01683127 0.00210762 0.01543009 2.40273e-4 0.01683127 2.40273e-4 0.01613074 0.003910422 -9.95699e-4 0.04891163 -0.01661014 0.04866629 -8.87622e-4 0.04866629 -0.01661014 0.04866629 -9.95699e-4 0.04891163 -0.01650208 0.04891163 -0.01650208 0.04891163 -9.95699e-4 0.04891163 -0.001253724 0.04941707 -0.01650208 0.04891163 -0.001253724 0.04941707 -0.01624399 0.04941707 -0.01624399 0.04941707 -0.001253724 0.04941707 -0.001517713 0.04986858 -0.01624399 0.04941707 -0.001517713 0.04986858 -0.01598006 0.04986858 -0.03672695 0.00914669 -0.0370078 0.007809758 -0.03672695 0.007688522 -0.0370078 0.007809758 -0.03672695 0.00914669 -0.03725725 0.007907927 -0.03725725 0.007907927 -0.03672695 0.00914669 -0.03725725 0.009366095 -0.03725725 0.009366095 -0.03672695 0.00914669 -0.0370078 0.009267926 -0.03829658 0.008911728 -0.03882694 0.007688522 -0.03829658 0.00745362 -0.03882694 0.007688522 -0.03829658 0.008911728 -0.03882694 0.00914669 0.04545778 0.007688522 0.04492735 0.008911728 0.04492735 0.00745362 0.04492735 0.008911728 0.04545778 0.007688522 0.04545778 0.00914669 0.0445947 0.007809758 0.04431349 0.00914669 0.04431349 0.007688522 0.04431349 0.00914669 0.0445947 0.007809758 0.04484397 0.007907927 0.04431349 0.00914669 0.04484397 0.007907927 0.04484397 0.009366095 0.04431349 0.00914669 0.04484397 0.009366095 0.0445947 0.009267926 0.01650208 0.04832762 8.87622e-4 0.04808247 0.01661014 0.04808247 8.87622e-4 0.04808247 0.01650208 0.04832762 9.95699e-4 0.04832762 9.95699e-4 0.04832762 0.01650208 0.04832762 0.01624399 0.04883325 9.95699e-4 0.04832762 0.01624399 0.04883325 0.001253724 0.04883325 0.001253724 0.04883325 0.01624399 0.04883325 0.001517713 0.04928445 0.001517713 0.04928445 0.01624399 0.04883325 0.01598006 0.04928445 -0.001538932 0.05025851 -0.01598006 0.05022269 -0.001517713 0.05022269 -0.01598006 0.05022269 -0.001538932 0.05025851 -0.01595848 0.05025851 -0.01595848 0.05025851 -0.001538932 0.05025851 -0.001850605 0.05072045 -0.01595848 0.05025851 -0.001850605 0.05072045 -0.01564717 0.05072045 -0.01564717 0.05072045 -0.001850605 0.05072045 -0.002187192 0.05116117 -0.01564717 0.05072045 -0.002187192 0.05116117 -0.0153104 0.05116117 -0.0153104 0.05116117 -0.002187192 0.05116117 -0.01511442 0.05142486 -0.01511442 0.05142486 -0.002187192 0.05116117 -0.002383172 0.05142486 -0.03319674 0.009568572 -0.03368759 0.008291244 -0.03319674 0.008110463 -0.03368759 0.008291244 -0.03319674 0.009568572 -0.0337271 0.008304476 -0.0337271 0.008304476 -0.03319674 0.009568572 -0.0337271 0.009762644 -0.0337271 0.009762644 -0.03319674 0.009568572 -0.03368759 0.009749352 -0.035025 0.009366095 -0.0355553 0.008110463 -0.035025 0.007907927 -0.0355553 0.008110463 -0.035025 0.009366095 -0.0355553 0.009568572 0.04407078 0.008110463 0.04354023 0.009366095 0.04354023 0.007907927 0.04354023 0.009366095 0.04407078 0.008110463 0.04407078 0.009568572 0.04310125 0.008291244 0.04261064 0.009568572 0.04261064 0.008110463 0.04261064 0.009568572 0.04310125 0.008291244 0.04314076 0.008304476 0.04261064 0.009568572 0.04314076 0.008304476 0.04314076 0.009762644 0.04261064 0.009568572 0.04314076 0.009762644 0.04310125 0.009749352 0.01595848 0.049721 0.001517713 0.049685 0.01598006 0.049685 0.001517713 0.049685 0.01595848 0.049721 0.001538932 0.049721 0.001538932 0.049721 0.01595848 0.049721 0.01564717 0.0501827 0.001538932 0.049721 0.01564717 0.0501827 0.001850605 0.0501827 0.001850605 0.0501827 0.01564717 0.0501827 0.0153104 0.05062341 0.001850605 0.0501827 0.0153104 0.05062341 0.002187192 0.05062341 0.002187192 0.05062341 0.0153104 0.05062341 0.002383172 0.05088692 0.002383172 0.05088692 0.0153104 0.05062341 0.01511442 0.05088692 0.04205787 0.008474767 0.04152745 0.009762644 0.04152745 0.008304476 0.04152745 0.009762644 0.04205787 0.008474767 0.04205787 0.009932935 0.04082524 0.008637368 0.04029512 0.009932935 0.04029512 0.008474767 0.04029512 0.009932935 0.04082524 0.008637368 0.04082524 0.01009529 0.04153186 0.008734524 0.04121816 0.01009529 0.04121816 0.008637368 0.04121816 0.01009529 0.04153186 0.008734524 0.0429815 0.00913912 0.04121816 0.01009529 0.0429815 0.00913912 0.04444795 0.009504616 0.04121816 0.01009529 0.04444795 0.009504616 0.04588639 0.009820938 0.04121816 0.01009529 0.04588639 0.009820938 0.04588639 0.01127892 0.04121816 0.01009529 0.04588639 0.01127892 0.04153186 0.01019269 0.04153186 0.01019269 0.04588639 0.01127892 0.0429815 0.0105971 0.0429815 0.0105971 0.04588639 0.01127892 0.04444795 0.01096278 -0.002383172 0.05171883 -0.01420903 0.05292081 -0.01511442 0.05171883 -0.01420903 0.05292081 -0.002383172 0.05171883 -0.003288686 0.05292081 -0.03028738 0.01009529 -0.03060108 0.008734524 -0.03028738 0.008637368 -0.03060108 0.008734524 -0.03028738 0.01009529 -0.03205054 0.00913912 -0.03205054 0.00913912 -0.03028738 0.01009529 -0.03351736 0.009504616 -0.03351736 0.009504616 -0.03028738 0.01009529 -0.03495568 0.009820938 -0.03495568 0.009820938 -0.03028738 0.01009529 -0.03495568 0.01127892 -0.03495568 0.01127892 -0.03028738 0.01009529 -0.03060108 0.01019269 -0.03495568 0.01127892 -0.03060108 0.01019269 -0.03205054 0.0105971 -0.03495568 0.01127892 -0.03205054 0.0105971 -0.03351736 0.01096278 -0.02918893 0.009932935 -0.02971929 0.008637368 -0.02918893 0.008474767 -0.02971929 0.008637368 -0.02918893 0.009932935 -0.02971929 0.01009529 -0.03124928 0.009762644 -0.0317794 0.008474767 -0.03124928 0.008304476 -0.0317794 0.008474767 -0.03124928 0.009762644 -0.0317794 0.009932935 0.01420903 0.05243015 0.002383172 0.05122786 0.01511442 0.05122786 0.002383172 0.05122786 0.01420903 0.05243015 0.003288686 0.05243015 0.04709213 0.009830474 0.04704999 0.01127892 0.04704999 0.009820938 0.04704999 0.01127892 0.04709213 0.009830474 0.04769361 0.009949028 0.04704999 0.01127892 0.04769361 0.009949028 0.04769361 0.01140701 0.04704999 0.01127892 0.04769361 0.01140701 0.04709213 0.01128864 -0.004204869 0.05452364 -0.01239413 0.05569076 -0.01329267 0.05452364 -0.01239413 0.05569076 -0.004204869 0.05452364 -0.005103528 0.05569076 -0.01239413 0.05569076 -0.005103528 0.05569076 -0.01236927 0.05572599 -0.01236927 0.05572599 -0.005103528 0.05569076 -0.005128443 0.05572599 -0.003288686 0.05315291 -0.01329267 0.05435526 -0.01420903 0.05315291 -0.01329267 0.05435526 -0.003288686 0.05315291 -0.004204869 0.05435526 0.01329267 0.05391192 0.003288686 0.05270963 0.01420903 0.05270963 0.003288686 0.05270963 0.01329267 0.05391192 0.004204869 0.05391192 0.01239413 0.05529528 0.004204869 0.0541284 0.01329267 0.0541284 0.004204869 0.0541284 0.01239413 0.05529528 0.005103528 0.05529528 0.005103528 0.05529528 0.01239413 0.05529528 0.01236927 0.05533069 0.005103528 0.05529528 0.01236927 0.05533069 0.005128443 0.05533069 -0.0366714 0.01127892 -0.03671354 0.009830474 -0.0366714 0.009820938 -0.03671354 0.009830474 -0.0366714 0.01127892 -0.03731501 0.009949028 -0.03731501 0.009949028 -0.0366714 0.01127892 -0.03731501 0.01140701 -0.03731501 0.01140701 -0.0366714 0.01127892 -0.03671354 0.01128864 0.05043751 0.01008296 0.04979383 0.01140701 0.04979383 0.009949028 0.04979383 0.01140701 0.05043751 0.01008296 0.05043751 0.01154094 -0.005128443 0.05582922 -0.01201254 0.05632776 -0.01236927 0.05582922 -0.01201254 0.05632776 -0.005128443 0.05582922 -0.005485236 0.05632776 -0.01201254 0.05632776 -0.005485236 0.05632776 -0.01167315 0.05689096 -0.01167315 0.05689096 -0.005485236 0.05632776 -0.005824625 0.05689096 -0.01167315 0.05689096 -0.005824625 0.05689096 -0.005894899 0.05703151 -0.01167315 0.05689096 -0.005894899 0.05703151 -0.01160264 0.05703151 0.01236927 0.05548238 0.005485236 0.05598104 0.005128443 0.05548238 0.005485236 0.05598104 0.01236927 0.05548238 0.01201254 0.05598104 0.005485236 0.05598104 0.01201254 0.05598104 0.01167315 0.05654418 0.005485236 0.05598104 0.01167315 0.05654418 0.005824625 0.05654418 0.005824625 0.05654418 0.01167315 0.05654418 0.005894899 0.05668473 0.005894899 0.05668473 0.01167315 0.05654418 0.01160264 0.05668473 -0.04056745 0.01140701 -0.04121106 0.01008296 -0.04056745 0.009949028 -0.04121106 0.01008296 -0.04056745 0.01140701 -0.04121106 0.01154094 0.05237436 0.01011621 0.05222082 0.01154094 0.05222082 0.01008296 0.05222082 0.01154094 0.05237436 0.01011621 0.05286437 0.01020711 0.05222082 0.01154094 0.05286437 0.01020711 0.05286437 0.01166546 0.05222082 0.01154094 0.05286437 0.01166546 0.05237436 0.01157438 -0.00611943 0.05751299 -0.01160264 0.05706804 -0.005894899 0.05706804 -0.01160264 0.05706804 -0.00611943 0.05751299 -0.01137816 0.05751299 -0.01137816 0.05751299 -0.00611943 0.05751299 -0.006367862 0.05811965 -0.01137816 0.05751299 -0.006367862 0.05811965 -0.01112973 0.05811965 -0.01112973 0.05811965 -0.006367862 0.05811965 -0.01108139 0.05827033 -0.01108139 0.05827033 -0.006367862 0.05811965 -0.006416201 0.05827033 -0.044205 0.01154094 -0.04435873 0.01011621 -0.044205 0.01008296 -0.04435873 0.01011621 -0.044205 0.01154094 -0.04484874 0.01020711 -0.04484874 0.01020711 -0.044205 0.01154094 -0.04484874 0.01166546 -0.04484874 0.01166546 -0.044205 0.01154094 -0.04435873 0.01157438 0.01160264 0.05677032 0.00611943 0.05721527 0.005894899 0.05677032 0.00611943 0.05721527 0.01160264 0.05677032 0.01137816 0.05721527 0.00611943 0.05721527 0.01137816 0.05721527 0.01112973 0.05782181 0.00611943 0.05721527 0.01112973 0.05782181 0.006367862 0.05782181 0.006367862 0.05782181 0.01112973 0.05782181 0.01108139 0.05797243 0.006367862 0.05782181 0.01108139 0.05797243 0.006416201 0.05797243 0.05495882 0.01033121 0.05431509 0.01166546 0.05431509 0.01020711 0.05431509 0.01166546 0.05495882 0.01033121 0.05495882 0.01178932 -0.006568312 0.0587098 -0.01108139 0.0582388 -0.006416201 0.0582388 -0.01108139 0.0582388 -0.006568312 0.0587098 -0.01092928 0.0587098 -0.01092928 0.0587098 -0.006568312 0.0587098 -0.006719529 0.05934453 -0.01092928 0.0587098 -0.006719529 0.05934453 -0.01077806 0.05934453 -0.01077806 0.05934453 -0.006719529 0.05934453 -0.006734609 0.05944097 -0.01077806 0.05934453 -0.006734609 0.05944097 -0.01076298 0.05944097 -0.05061388 0.01178932 -0.05076915 0.01036185 -0.05061388 0.01033121 -0.05076915 0.01036185 -0.05061388 0.01178932 -0.05125761 0.01044213 -0.05125761 0.01044213 -0.05061388 0.01178932 -0.05125761 0.01190042 -0.05125761 0.01190042 -0.05061388 0.01178932 -0.05076915 0.01181995 -0.04756093 0.01166546 -0.04820466 0.01033121 -0.04756093 0.01020711 -0.04820466 0.01033121 -0.04756093 0.01166546 -0.04820466 0.01178932 0.05621916 0.01036185 0.05606395 0.01178932 0.05606395 0.01033121 0.05606395 0.01178932 0.05621916 0.01036185 0.05670756 0.01044213 0.05606395 0.01178932 0.05670756 0.01044213 0.05670756 0.01190042 0.05606395 0.01178932 0.05670756 0.01190042 0.05621916 0.01181995 0.01108139 0.05799019 0.006568312 0.05846107 0.006416201 0.05799019 0.006568312 0.05846107 0.01108139 0.05799019 0.01092928 0.05846107 0.006568312 0.05846107 0.01092928 0.05846107 0.006719529 0.05909591 0.006719529 0.05909591 0.01092928 0.05846107 0.01077806 0.05909591 0.006719529 0.05909591 0.01077806 0.05909591 0.006734609 0.05919224 0.006734609 0.05919224 0.01077806 0.05909591 0.01076298 0.05919224 -0.006734609 0.05933988 -0.01067703 0.05988574 -0.01076298 0.05933988 -0.01067703 0.05988574 -0.006734609 0.05933988 -0.006820559 0.05988574 -0.01067703 0.05988574 -0.006820559 0.05988574 -0.01062703 0.0605418 -0.01062703 0.0605418 -0.006820559 0.05988574 -0.006870746 0.0605418 -0.055736 0.01200854 -0.05583184 0.01056689 -0.055736 0.01055037 -0.05583184 0.01056689 -0.055736 0.01200854 -0.05637943 0.01064133 -0.05637943 0.01064133 -0.055736 0.01200854 -0.05637943 0.01209962 -0.05637943 0.01209962 -0.055736 0.01200854 -0.05583184 0.01202493 -0.0533446 0.01190042 -0.05398821 0.01055037 -0.0533446 0.01044213 -0.05398821 0.01055037 -0.0533446 0.01190042 -0.05398821 0.01200854 0.05809944 0.01055037 0.05745583 0.01190042 0.05745583 0.01044213 0.05745583 0.01190042 0.05809944 0.01055037 0.05809944 0.01200854 0.05857855 0.01056689 0.0584824 0.01200854 0.0584824 0.01055037 0.0584824 0.01200854 0.05857855 0.01056689 0.05912595 0.01064133 0.0584824 0.01200854 0.05912595 0.01064133 0.05912595 0.01209962 0.0584824 0.01200854 0.05912595 0.01209962 0.05857855 0.01202493 0.01067703 0.05968672 0.006734609 0.0591408 0.01076298 0.0591408 0.006734609 0.0591408 0.01067703 0.05968672 0.006820559 0.05968672 0.006820559 0.05968672 0.01067703 0.05968672 0.01062703 0.06034272 0.006820559 0.05968672 0.01062703 0.06034272 0.006870746 0.06034272 -0.006869733 0.06100857 -0.01062703 0.0603699 -0.006870746 0.0603699 -0.01062703 0.0603699 -0.006869733 0.06100857 -0.01062798 0.06100857 -0.01062798 0.06100857 -0.006869733 0.06100857 -0.006824195 0.06157219 -0.01062798 0.06100857 -0.006824195 0.06157219 -0.01067352 0.06157219 -0.05778825 0.01209962 -0.05844008 0.0107311 -0.05778825 0.01064133 -0.05844008 0.0107311 -0.05778825 0.01209962 -0.05844008 0.01218909 0.05978661 0.0107311 0.05913478 0.01209962 0.05913478 0.01064133 0.05913478 0.01209962 0.05978661 0.0107311 0.05978661 0.01218909 0.01062798 0.06085926 0.006870746 0.06022059 0.01062703 0.06022059 0.006870746 0.06022059 0.01062798 0.06085926 0.006869733 0.06085926 0.006869733 0.06085926 0.01062798 0.06085926 0.006824195 0.06142288 0.006824195 0.06142288 0.01062798 0.06085926 0.01067352 0.06142288 -0.006824195 0.06132817 -0.01067996 0.06140917 -0.01067352 0.06132817 -0.01067996 0.06140917 -0.006824195 0.06132817 -0.006817579 0.06140917 -0.01067996 0.06140917 -0.006817579 0.06140917 -0.01078283 0.06204599 -0.01078283 0.06204599 -0.006817579 0.06140917 -0.006714761 0.06204599 -0.01078283 0.06204599 -0.006714761 0.06204599 -0.01090133 0.06253027 -0.01090133 0.06253027 -0.006714761 0.06204599 -0.006596386 0.06253027 -0.06073278 0.01225447 -0.06129527 0.01085418 -0.06073278 0.0107963 -0.06129527 0.01085418 -0.06073278 0.01225447 -0.06137639 0.01085954 -0.06137639 0.01085954 -0.06073278 0.01225447 -0.06137639 0.01231771 -0.06137639 0.01231771 -0.06073278 0.01225447 -0.06129527 0.01231235 -0.05945003 0.01218909 -0.06008517 0.0107963 -0.05945003 0.0107311 -0.06008517 0.0107963 -0.05945003 0.01218909 -0.06008517 0.01225447 0.06005913 0.0107963 0.05942398 0.01218909 0.05942398 0.0107311 0.05942398 0.01218909 0.06005913 0.0107963 0.06005913 0.01225447 0.05987834 0.01085418 0.05931586 0.01225447 0.05931586 0.0107963 0.05931586 0.01225447 0.05987834 0.01085418 0.05995959 0.01085954 0.05931586 0.01225447 0.05995959 0.01085954 0.05995959 0.01231771 0.05931586 0.01225447 0.05995959 0.01231771 0.05987834 0.01231235 0.01067352 0.06122881 0.006817579 0.06130981 0.006824195 0.06122881 0.006817579 0.06130981 0.01067352 0.06122881 0.01067996 0.06130981 0.006817579 0.06130981 0.01067996 0.06130981 0.01078283 0.06194663 0.006817579 0.06130981 0.01078283 0.06194663 0.006714761 0.06194663 0.006714761 0.06194663 0.01078283 0.06194663 0.01090133 0.06243073 0.006714761 0.06194663 0.01090133 0.06243073 0.006596386 0.06243073 -0.006596386 0.06230098 -0.01093608 0.06244295 -0.01090133 0.06230098 -0.01093608 0.06244295 -0.006596386 0.06230098 -0.006561577 0.06244295 -0.01093608 0.06244295 -0.006561577 0.06244295 -0.01097542 0.06291043 -0.01097542 0.06291043 -0.006561577 0.06244295 -0.006522357 0.06291043 -0.06215023 0.0123611 -0.06264787 0.01093608 -0.06215023 0.01090312 -0.06264787 0.01093608 -0.06215023 0.0123611 -0.06279402 0.01094216 -0.06279402 0.01094216 -0.06215023 0.0123611 -0.06279402 0.01240015 -0.06279402 0.01240015 -0.06215023 0.0123611 -0.06264787 0.01239413 -0.06163758 0.01231771 -0.06228119 0.01090312 -0.06163758 0.01085954 -0.06228119 0.01090312 -0.06163758 0.01231771 -0.06228119 0.0123611 0.05948287 0.01090312 0.05883926 0.01231771 0.05883926 0.01085954 0.05883926 0.01231771 0.05948287 0.01090312 0.05948287 0.0123611 0.0584855 0.01093608 0.05798804 0.0123611 0.05798804 0.01090312 0.05798804 0.0123611 0.0584855 0.01093608 0.05863165 0.01094216 0.05798804 0.0123611 0.05863165 0.01094216 0.05863165 0.01240015 0.05798804 0.0123611 0.05863165 0.01240015 0.0584855 0.01239413 0.01090133 0.06223899 0.006561577 0.06238085 0.006596386 0.06223899 0.006561577 0.06238085 0.01090133 0.06223899 0.01093608 0.06238085 0.006561577 0.06238085 0.01093608 0.06238085 0.01097542 0.06284832 0.006561577 0.06238085 0.01097542 0.06284832 0.006522357 0.06284832 -0.006470978 0.0633468 -0.01097542 0.06273746 -0.006522357 0.06273746 -0.01097542 0.06273746 -0.006470978 0.0633468 -0.01102674 0.0633468 -0.06267052 0.01240015 -0.06313902 0.01096189 -0.06267052 0.01094216 -0.06313902 0.01096189 -0.06267052 0.01240015 -0.06375032 0.01097774 -0.06375032 0.01097774 -0.06267052 0.01240015 -0.06436181 0.01098299 -0.06436181 0.01098299 -0.06267052 0.01240015 -0.0698446 0.01202952 -0.0698446 0.01202952 -0.06267052 0.01240015 -0.06923931 0.01211625 -0.06923931 0.01211625 -0.06267052 0.01240015 -0.06863266 0.01219248 -0.06863266 0.01219248 -0.06267052 0.01240015 -0.06802475 0.01225864 -0.06802475 0.01225864 -0.06267052 0.01240015 -0.06741583 0.01231467 -0.06741583 0.01231467 -0.06267052 0.01240015 -0.06680607 0.01236063 -0.06680607 0.01236063 -0.06267052 0.01240015 -0.0661956 0.01239597 -0.0661956 0.01239597 -0.06267052 0.01240015 -0.06558459 0.0124213 -0.06558459 0.0124213 -0.06267052 0.01240015 -0.06313902 0.01241999 -0.06558459 0.0124213 -0.06313902 0.01241999 -0.06375032 0.01243591 -0.06558459 0.0124213 -0.06375032 0.01243591 -0.06497329 0.01243633 -0.06497329 0.01243633 -0.06375032 0.01243591 -0.06436181 0.01244115 -0.1320354 0.004374444 -0.1321778 0.00581938 -0.1321778 0.004361391 -0.1321778 0.00581938 -0.1320354 0.004374444 -0.06984466 0.01057142 -0.1321778 0.00581938 -0.06984466 0.01057142 -0.1320354 0.005832493 -0.1320354 0.005832493 -0.06984466 0.01057142 -0.0698446 0.01202952 -0.0698446 0.01202952 -0.06984466 0.01057142 -0.06923931 0.0106579 -0.0698446 0.01202952 -0.06923931 0.0106579 -0.06863266 0.01073431 -0.0698446 0.01202952 -0.06863266 0.01073431 -0.06802475 0.0108006 -0.0698446 0.01202952 -0.06802475 0.0108006 -0.06741583 0.0108565 -0.0698446 0.01202952 -0.06741583 0.0108565 -0.06680607 0.01090246 -0.0698446 0.01202952 -0.06680607 0.01090246 -0.0661956 0.0109378 -0.0698446 0.01202952 -0.0661956 0.0109378 -0.06558459 0.01096332 -0.0698446 0.01202952 -0.06558459 0.01096332 -0.06497329 0.0109784 -0.0698446 0.01202952 -0.06497329 0.0109784 -0.06436181 0.01098299 0.1307095 0.00581938 0.1305671 0.004374444 0.1307095 0.004361391 0.1305671 0.004374444 0.1307095 0.00581938 0.06837636 0.01057142 0.06837636 0.01057142 0.1307095 0.00581938 0.1305671 0.005832493 0.06837636 0.01057142 0.1305671 0.005832493 0.06837636 0.01202952 0.06837636 0.01057142 0.06837636 0.01202952 0.06777101 0.0106579 0.06777101 0.0106579 0.06837636 0.01202952 0.06716436 0.01073431 0.06716436 0.01073431 0.06837636 0.01202952 0.06655645 0.0108006 0.06655645 0.0108006 0.06837636 0.01202952 0.06594753 0.0108565 0.06594753 0.0108565 0.06837636 0.01202952 0.06533777 0.01090246 0.06533777 0.01090246 0.06837636 0.01202952 0.0647273 0.0109378 0.0647273 0.0109378 0.06837636 0.01202952 0.06411629 0.01096332 0.06411629 0.01096332 0.06837636 0.01202952 0.06350499 0.0109784 0.06350499 0.0109784 0.06837636 0.01202952 0.0628935 0.01098299 0.06167072 0.01096189 0.06120204 0.01240015 0.06120204 0.01094216 0.06120204 0.01240015 0.06167072 0.01096189 0.06228184 0.01097774 0.06120204 0.01240015 0.06228184 0.01097774 0.0628935 0.01098299 0.06120204 0.01240015 0.0628935 0.01098299 0.06837636 0.01202952 0.06120204 0.01240015 0.06837636 0.01202952 0.06777101 0.01211625 0.06120204 0.01240015 0.06777101 0.01211625 0.06716436 0.01219248 0.06120204 0.01240015 0.06716436 0.01219248 0.06655645 0.01225864 0.06120204 0.01240015 0.06655645 0.01225864 0.06594753 0.01231467 0.06120204 0.01240015 0.06594753 0.01231467 0.06533777 0.01236063 0.06120204 0.01240015 0.06533777 0.01236063 0.0647273 0.01239597 0.06120204 0.01240015 0.0647273 0.01239597 0.06411629 0.0124213 0.06120204 0.01240015 0.06411629 0.0124213 0.06167072 0.01241999 0.06167072 0.01241999 0.06411629 0.0124213 0.06228184 0.01243591 0.06228184 0.01243591 0.06411629 0.0124213 0.06350499 0.01243633 0.06228184 0.01243591 0.06350499 0.01243633 0.0628935 0.01244115 0.01097542 0.06269991 0.006470978 0.06330925 0.006522357 0.06269991 0.006470978 0.06330925 0.01097542 0.06269991 0.01102674 0.06330925 -0.006419718 0.06376534 -0.01102674 0.063156 -0.006470978 0.063156 -0.01102674 0.063156 -0.006419718 0.06376534 -0.011078 0.06376534 0.006419718 -0.06355655 0.01112926 -0.06416589 0.011078 -0.06355655 0.01112926 -0.06416589 0.006419718 -0.06355655 0.006368398 -0.06416589 0.006317138 -0.06454837 0.01112926 -0.06393903 0.006368398 -0.06393903 0.01112926 -0.06393903 0.006317138 -0.06454837 0.01118052 -0.06454837 0.006317138 -0.06430333 0.01123178 -0.06491267 0.01118052 -0.06430333 0.01123178 -0.06491267 0.006317138 -0.06430333 0.006265878 -0.06491267 0.006265878 -0.06464934 0.01128304 -0.06525868 0.01123178 -0.06464934 0.01128304 -0.06525868 0.006265878 -0.06464934 0.006214618 -0.06525868 0.006163418 -0.06558632 0.01128304 -0.06497693 0.006214618 -0.06497693 0.01128304 -0.06497693 0.006163418 -0.06558632 0.0113343 -0.06558632 0.006112337 -0.06589543 0.0113343 -0.06528609 0.006163418 -0.06528609 0.0113343 -0.06528609 0.006112337 -0.06589543 0.01138538 -0.06589543 0.006061375 -0.06618601 0.01138538 -0.06557667 0.006112337 -0.06557667 0.01138538 -0.06557667 0.006061375 -0.06618601 0.0114364 -0.06618601 0.006010413 -0.06645792 0.0114364 -0.06584858 0.006061375 -0.06584858 0.0114364 -0.06584858 0.006010413 -0.06645792 0.01148712 -0.06645792 0.006010413 -0.06610172 0.0115379 -0.06671106 0.01148712 -0.06610172 0.0115379 -0.06671106 0.006010413 -0.06610172 0.00595963 -0.06671106 7.41029e-4 -0.1298606 0.0115379 -0.06758016 0.00595963 -0.06758016 0.0115379 -0.06758016 7.41029e-4 -0.1298606 0.01675677 -0.1298606 7.41029e-4 -0.1299881 0.01676869 -0.1301307 0.01675677 -0.1299881 0.01676869 -0.1301307 7.41029e-4 -0.1299881 7.29076e-4 -0.1301307 0.01676869 -0.1301307 7.29076e-4 -0.1301307 0.01684916 -0.131825 0.01684916 -0.131825 7.29076e-4 -0.1301307 6.48502e-4 -0.131825 -0.133574 0.004206776 -0.1338878 0.005637586 -0.1338878 0.004183292 -0.1338878 0.005637586 -0.133574 0.004206776 -0.131884 0.004361391 -0.1338878 0.005637586 -0.131884 0.004361391 -0.1335731 0.005662441 -0.1335731 0.005662441 -0.131884 0.004361391 -0.131884 0.00581938 -0.01676869 -0.1302883 -7.41029e-4 -0.1301458 -0.01675677 -0.1301458 -7.41029e-4 -0.1301458 -0.01676869 -0.1302883 -7.29076e-4 -0.1302883 -7.29076e-4 -0.1302883 -0.01676869 -0.1302883 -0.01684916 -0.1319833 -7.29076e-4 -0.1302883 -0.01684916 -0.1319833 -6.48459e-4 -0.1319833 -0.01675677 -0.1300058 -0.00595963 -0.06772524 -0.0115379 -0.06772524 -0.00595963 -0.06772524 -0.01675677 -0.1300058 -7.41029e-4 -0.1300058 -0.01148712 -0.06630885 -0.00595963 -0.06691819 -0.006010413 -0.06630885 -0.00595963 -0.06691819 -0.01148712 -0.06630885 -0.0115379 -0.06691819 -0.01148712 -0.06664067 -0.006061375 -0.06603133 -0.0114364 -0.06603133 -0.006061375 -0.06603133 -0.01148712 -0.06664067 -0.006010413 -0.06664067 -0.0114364 -0.06634443 -0.006112337 -0.06573504 -0.01138538 -0.06573504 -0.006112337 -0.06573504 -0.0114364 -0.06634443 -0.006061375 -0.06634443 -0.01138538 -0.06602942 -0.006163418 -0.06542009 -0.0113343 -0.06542009 -0.006163418 -0.06542009 -0.01138538 -0.06602942 -0.006112337 -0.06602942 -0.0113343 -0.06569588 -0.006214618 -0.06508648 -0.01128304 -0.06508648 -0.006214618 -0.06508648 -0.0113343 -0.06569588 -0.006163418 -0.06569588 -0.01128304 -0.06534373 -0.006265878 -0.06473439 -0.01123178 -0.06473439 -0.006265878 -0.06473439 -0.01128304 -0.06534373 -0.006214618 -0.06534373 -0.01123178 -0.06497323 -0.006317138 -0.06436389 -0.01118052 -0.06436389 -0.006317138 -0.06436389 -0.01123178 -0.06497323 -0.006265878 -0.06497323 -0.01112926 -0.06397509 -0.006317138 -0.06458443 -0.006368398 -0.06397509 -0.006317138 -0.06458443 -0.01112926 -0.06397509 -0.01118052 -0.06458443 -0.01112926 -0.06417739 -0.006419718 -0.06356805 -0.011078 -0.06356805 -0.006419718 -0.06356805 -0.01112926 -0.06417739 -0.006368398 -0.06417739 0.011078 0.06375229 0.006470978 0.06314295 0.01102674 0.06314295 0.006470978 0.06314295 0.011078 0.06375229 0.006419718 0.06375229 0.133053 0.005637586 0.1327392 0.004206776 0.133053 0.004183292 0.1327392 0.004206776 0.133053 0.005637586 0.1310493 0.004361391 0.1310493 0.004361391 0.133053 0.005637586 0.1327383 0.005662441 0.1310493 0.004361391 0.1327383 0.005662441 0.1310493 0.00581938 6.33489e-4 -0.1323763 0.01684916 -0.132061 6.48502e-4 -0.132061 0.01684916 -0.132061 6.33489e-4 -0.1323763 0.01686424 -0.1323763 0.01686424 -0.1323763 6.33489e-4 -0.1323763 0.01682657 -0.1338978 0.01682657 -0.1338978 6.33489e-4 -0.1323763 6.71193e-4 -0.1338978 -0.1342942 0.004069507 -0.1347784 0.005486011 -0.1347784 0.004041314 -0.1347784 0.005486011 -0.1342942 0.004069507 -0.1327747 0.004183292 -0.1347784 0.005486011 -0.1327747 0.004183292 -0.134292 0.005517721 -0.134292 0.005517721 -0.1327747 0.004183292 -0.1327747 0.005637586 -0.01686424 -0.1325504 -6.48459e-4 -0.1322361 -0.01684916 -0.1322361 -6.48459e-4 -0.1322361 -0.01686424 -0.1325504 -6.33489e-4 -0.1325504 -6.33489e-4 -0.1325504 -0.01686424 -0.1325504 -0.01682657 -0.1340737 -6.33489e-4 -0.1325504 -0.01682657 -0.1340737 -6.71246e-4 -0.1340737 0.1352131 0.005486011 0.134729 0.004069507 0.1352131 0.004041314 0.134729 0.004069507 0.1352131 0.005486011 0.1332095 0.004183292 0.1332095 0.004183292 0.1352131 0.005486011 0.1347268 0.005517721 0.1332095 0.004183292 0.1347268 0.005517721 0.1332095 0.005637586 6.71193e-4 -0.1341083 0.01681447 -0.1345955 0.01682657 -0.1341083 0.01681447 -0.1345955 6.71193e-4 -0.1341083 6.83279e-4 -0.1345955 0.01681447 -0.1345955 6.83279e-4 -0.1345955 0.01668286 -0.1359451 0.01668286 -0.1359451 6.83279e-4 -0.1345955 8.14909e-4 -0.1359451 -0.1343178 0.003962755 -0.1349647 0.005365133 -0.1349647 0.003935933 -0.1349647 0.005365133 -0.1343178 0.003962755 -0.132961 0.004041314 -0.1349647 0.005365133 -0.132961 0.004041314 -0.1343142 0.005398333 -0.1343142 0.005398333 -0.132961 0.004041314 -0.132961 0.005486011 -0.01681447 -0.1347746 -6.71246e-4 -0.1342898 -0.01682657 -0.1342898 -6.71246e-4 -0.1342898 -0.01681447 -0.1347746 -6.83279e-4 -0.1347746 -6.83279e-4 -0.1347746 -0.01681447 -0.1347746 -0.0166825 -0.1361272 -6.83279e-4 -0.1347746 -0.0166825 -0.1361272 -8.1526e-4 -0.1361272 0.1366667 0.005365133 0.1360199 0.003962755 0.1366667 0.003935933 0.1360199 0.003962755 0.1366667 0.005365133 0.1346631 0.004041314 0.1346631 0.004041314 0.1366667 0.005365133 0.1360163 0.005398333 0.1346631 0.004041314 0.1360163 0.005398333 0.1346631 0.005486011 8.14909e-4 -0.1361296 0.01661962 -0.1367779 0.01668286 -0.1361296 0.01661962 -0.1367779 8.14909e-4 -0.1361296 8.78182e-4 -0.1367779 0.01661962 -0.1367779 8.78182e-4 -0.1367779 0.01641583 -0.1379665 0.01641583 -0.1379665 8.78182e-4 -0.1367779 0.001081943 -0.1379665 -0.1336516 0.003886461 -0.1344456 0.005274832 -0.1344456 0.00386697 -0.1344456 0.005274832 -0.1336516 0.003886461 -0.1324419 0.003935933 -0.1344456 0.005274832 -0.1324419 0.003935933 -0.1336464 0.005304336 -0.1336464 0.005304336 -0.1324419 0.003935933 -0.1324419 0.005365133 -0.0166825 -0.1363061 -8.78182e-4 -0.1369504 -8.1526e-4 -0.1363061 -8.78182e-4 -0.1369504 -0.0166825 -0.1363061 -0.01661962 -0.1369504 -8.78182e-4 -0.1369504 -0.01661962 -0.1369504 -0.001082718 -0.1381435 -0.001082718 -0.1381435 -0.01661962 -0.1369504 -0.01641494 -0.1381435 0.137406 0.005274832 0.1366119 0.003886461 0.137406 0.00386697 0.1366119 0.003886461 0.137406 0.005274832 0.1354023 0.003935933 0.1354023 0.003935933 0.137406 0.005274832 0.1366068 0.005304336 0.1354023 0.003935933 0.1366068 0.005304336 0.1354024 0.005365133 0.001081943 -0.1381247 0.01628059 -0.138913 0.01641583 -0.1381247 0.01628059 -0.138913 0.001081943 -0.1381247 0.001217067 -0.138913 0.01628059 -0.138913 0.001217067 -0.138913 0.01602131 -0.1399616 0.01602131 -0.1399616 0.001217067 -0.138913 0.001476407 -0.1399616 -0.1323065 0.003840625 -0.133224 0.005214691 -0.133224 0.003833234 -0.133224 0.005214691 -0.1323065 0.003840625 -0.1312204 0.00386697 -0.133224 0.005214691 -0.1312204 0.00386697 -0.1322999 0.005235791 -0.1322999 0.005235791 -0.1312204 0.00386697 -0.1312204 0.005274832 -0.01641494 -0.1382845 -0.001217067 -0.1390673 -0.001082718 -0.1382845 -0.001217067 -0.1390673 -0.01641494 -0.1382845 -0.01628059 -0.1390673 -0.001217067 -0.1390673 -0.01628059 -0.1390673 -0.0160197 -0.1401219 -0.001217067 -0.1390673 -0.0160197 -0.1401219 -0.001478016 -0.1401219 0.1374271 0.005214691 0.1365097 0.003840625 0.1374271 0.003833234 0.1365097 0.003840625 0.1374271 0.005214691 0.1354235 0.00386697 0.1354235 0.00386697 0.1374271 0.005214691 0.136503 0.005235791 0.1354235 0.00386697 0.136503 0.005235791 0.1354235 0.005274832 0.001476407 -0.1400932 0.01579934 -0.1409904 0.01602131 -0.1400932 0.01579934 -0.1409904 0.001476407 -0.1400932 0.001698434 -0.1409904 0.01579934 -0.1409904 0.001698434 -0.1409904 0.01549309 -0.1419301 0.01549309 -0.1419301 0.001698434 -0.1409904 0.002004683 -0.1419301 -0.1293026 0.003833234 -0.1313062 0.003833413 -0.1302984 0.003825426 -0.1313062 0.003833413 -0.1293026 0.003833234 -0.1293026 0.005214691 -0.1313062 0.003833413 -0.1293026 0.005214691 -0.1302905 0.005192637 -0.1313062 0.003833413 -0.1302905 0.005192637 -0.1313062 0.005183339 -0.01579934 -0.1411151 -0.001478016 -0.1402245 -0.0160197 -0.1402245 -0.001478016 -0.1402245 -0.01579934 -0.1411151 -0.001698434 -0.1411151 -0.001698434 -0.1411151 -0.01579934 -0.1411151 -0.01549065 -0.1420621 -0.001698434 -0.1411151 -0.01549065 -0.1420621 -0.002007067 -0.1420621 0.13673 0.003833413 0.1347263 0.003833234 0.1357222 0.003825426 0.1347263 0.003833234 0.13673 0.003833413 0.1347263 0.005214691 0.1347263 0.005214691 0.13673 0.003833413 0.1357142 0.005192637 0.1357142 0.005192637 0.13673 0.003833413 0.13673 0.005183339 0.002004683 -0.1420345 0.01517826 -0.1430003 0.01549309 -0.1420345 0.01517826 -0.1430003 0.002004683 -0.1420345 0.002319455 -0.1430003 0.01517826 -0.1430003 0.002319455 -0.1430003 0.01482248 -0.1438714 0.01482248 -0.1438714 0.002319455 -0.1430003 0.002675235 -0.1438714 -0.1266987 0.005183339 -0.1276487 0.003840625 -0.1266987 0.003833413 -0.1276487 0.003840625 -0.1266987 0.005183339 -0.1287024 0.003864884 -0.1287024 0.003864884 -0.1266987 0.005183339 -0.1276397 0.005174875 -0.1287024 0.005179107 -0.1287024 0.003864884 -0.1276397 0.005174875 0.01549065 0.1421256 0.002319455 0.1430838 0.002007067 0.1421256 0.002319455 0.1430838 0.01549065 0.1421256 0.01517826 0.1430838 0.002319455 0.1430838 0.01517826 0.1430838 0.01481896 0.1439632 0.002319455 0.1430838 0.01481896 0.1439632 0.002678573 0.1439632 0.1353182 0.005179107 0.1342555 0.005174875 0.1353182 0.003864884 0.1342644 0.003840625 0.1333145 0.005183339 0.1333145 0.003833413 0.1333145 0.005183339 0.1342644 0.003840625 0.1353182 0.003864884 0.1333145 0.005183339 0.1353182 0.003864884 0.1342555 0.005174875 -0.00307703 0.1449323 -0.01482248 0.1439484 -0.002675235 0.1439484 -0.01482248 0.1439484 -0.00307703 0.1449323 -0.0144205 0.1449323 -0.0144205 0.1449323 -0.00307703 0.1449323 -0.01399773 0.1457853 -0.01399773 0.1457853 -0.00307703 0.1449323 -0.003500044 0.1457853 -0.1234226 0.005179107 -0.1243841 0.003886461 -0.1234226 0.003864884 -0.1243841 0.003886461 -0.1234226 0.005179107 -0.1254262 0.003925204 -0.1254262 0.003925204 -0.1234226 0.005179107 -0.1243748 0.005182683 -0.1254262 0.003925204 -0.1243748 0.005182683 -0.1254262 0.00519973 0.0144205 0.1449631 0.002678573 0.1439872 0.01481896 0.1439872 0.002678573 0.1439872 0.0144205 0.1449631 0.00307703 0.144963 0.00307703 0.144963 0.0144205 0.1449631 0.003504157 0.1458247 0.003504157 0.1458247 0.0144205 0.1449631 0.01399356 0.1458247 0.132157 0.003886461 0.1311956 0.005179107 0.1311956 0.003864884 0.1311956 0.005179107 0.132157 0.003886461 0.1331992 0.003925204 0.1311956 0.005179107 0.1331992 0.003925204 0.1321477 0.005182683 0.1321477 0.005182683 0.1331992 0.003925204 0.1331992 0.00519973 -0.003967106 0.1467769 -0.01399773 0.1458346 -0.003500044 0.1458346 -0.01399773 0.1458346 -0.003967106 0.1467769 -0.01353061 0.1467769 -0.01353061 0.1467769 -0.003967106 0.1467769 -0.01300305 0.1476715 -0.01300305 0.1476715 -0.003967106 0.1467769 -0.004494726 0.1476715 -0.1194913 0.00519973 -0.1205388 0.003962755 -0.1194913 0.003925204 -0.1205388 0.003962755 -0.1194913 0.00519973 -0.121495 0.004010677 -0.121495 0.004010677 -0.1194913 0.00519973 -0.1205298 0.005215883 -0.121495 0.004010677 -0.1205298 0.005215883 -0.121495 0.005242407 0.01399356 0.1458088 0.003967106 0.1467432 0.003504157 0.1458088 0.003967106 0.1467432 0.01399356 0.1458088 0.01353061 0.1467432 0.003967106 0.1467432 0.01353061 0.1467432 0.004499316 0.1476464 0.004499316 0.1476464 0.01353061 0.1467432 0.01299846 0.1476464 0.1294281 0.003962755 0.1283805 0.00519973 0.1283805 0.003925204 0.1283805 0.00519973 0.1294281 0.003962755 0.1303843 0.004010677 0.1283805 0.00519973 0.1303843 0.004010677 0.1294191 0.005215883 0.1294191 0.005215883 0.1303843 0.004010677 0.1303842 0.005242407 -0.004985034 0.1485244 -0.01300305 0.1476926 -0.004494726 0.1476926 -0.01300305 0.1476926 -0.004985034 0.1485244 -0.01251274 0.1485244 -0.01251274 0.1485244 -0.004985034 0.1485244 -0.005680382 0.1495295 -0.01251274 0.1485244 -0.005680382 0.1495295 -0.01181715 0.1495295 -0.1149257 0.005242407 -0.1161551 0.004069507 -0.1149257 0.004010677 -0.1161551 0.004069507 -0.1149257 0.005242407 -0.1169294 0.00411725 -0.1169294 0.00411725 -0.1149257 0.005242407 -0.1161475 0.005274534 -0.1169294 0.00411725 -0.1161475 0.005274534 -0.1169294 0.005303919 0.01251274 0.1484149 0.004499316 0.14759 0.01299846 0.14759 0.004499316 0.14759 0.01251274 0.1484149 0.004985034 0.148415 0.004985034 0.148415 0.01251274 0.1484149 0.005684733 0.1494275 0.005684733 0.1494275 0.01251274 0.1484149 0.01181304 0.1494275 0.1261138 0.004069507 0.1248844 0.005242407 0.1248844 0.004010677 0.1248844 0.005242407 0.1261138 0.004069507 0.126888 0.00411725 0.1248844 0.005242407 0.126888 0.00411725 0.1261062 0.005274534 0.1261062 0.005274534 0.126888 0.00411725 0.126888 0.005303919 -0.005680382 0.1495221 -0.0113722 0.1501657 -0.01181715 0.1495221 -0.0113722 0.1501657 -0.005680382 0.1495221 -0.00612539 0.1501657 -0.0113722 0.1501657 -0.00612539 0.1501657 -0.007085502 0.151359 -0.0113722 0.1501657 -0.007085502 0.151359 -0.01041209 0.151359 -0.1097497 0.005303919 -0.1112851 0.004206776 -0.1097497 0.00411725 -0.1112851 0.004206776 -0.1097497 0.005303919 -0.1117534 0.004240155 -0.1117534 0.004240155 -0.1097497 0.005303919 -0.1112803 0.005358517 -0.1117534 0.004240155 -0.1112803 0.005358517 -0.1117534 0.005380511 0.01181304 0.1493301 0.00612539 0.1499685 0.005684733 0.1493301 0.00612539 0.1499685 0.01181304 0.1493301 0.0113722 0.1499685 0.00612539 0.1499685 0.0113722 0.1499685 0.01040905 0.1511677 0.00612539 0.1499685 0.01040905 0.1511677 0.007088482 0.1511677 0.1222609 0.004206776 0.1207255 0.005303919 0.1207255 0.00411725 0.1207255 0.005303919 0.1222609 0.004206776 0.1227291 0.004240155 0.1207255 0.005303919 0.1227291 0.004240155 0.1222561 0.005358517 0.1222561 0.005358517 0.1227291 0.004240155 0.1227291 0.005380511 -0.007085502 0.1513227 -0.01011556 0.1516917 -0.01041209 0.1513227 -0.01011556 0.1516917 -0.007085502 0.1513227 -0.007382214 0.1516917 -0.01011556 0.1516917 -0.007382214 0.1516917 -0.008748888 0.1531596 -0.1039906 0.005380511 -0.1059942 0.004374444 -0.1039906 0.004240155 -0.1059942 0.004374444 -0.1039906 0.005380511 -0.1059942 0.005467951 0.01011556 0.151395 0.007088482 0.1510288 0.01040905 0.1510288 0.007088482 0.1510288 0.01011556 0.151395 0.007382214 0.151395 0.007382214 0.151395 0.01011556 0.151395 0.008748888 0.1528664 0.1179293 0.004374444 0.1159256 0.005380511 0.1159256 0.004240155 0.1159256 0.005380511 0.1179293 0.004374444 0.1179293 0.005467951 - - - - - - - - - - - - - - - 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 -

0 0 0 1 1 1 2 2 2 1 1 3 0 0 4 3 3 5 1 1 6 3 3 7 4 4 8 1 1 9 4 4 10 5 5 11 5 5 12 4 4 13 6 6 14 5 5 15 6 6 16 7 7 17 7 7 18 6 6 19 8 8 20 8 8 21 6 6 22 9 9 23 10 10 24 11 11 25 12 12 26 11 11 27 10 10 28 13 13 29 13 13 30 10 10 31 14 14 32 14 14 33 10 10 34 15 15 35 15 15 36 10 10 37 16 16 38 16 16 39 10 10 40 17 16 41 17 16 42 10 10 43 18 16 44 19 17 45 20 18 46 21 19 47 20 18 48 19 17 49 22 20 50 20 18 51 22 20 52 23 21 53 20 18 54 23 21 55 24 22 56 20 18 57 24 22 58 18 16 59 20 18 60 18 16 61 10 10 62 25 23 63 8 8 64 9 9 65 8 8 66 25 23 67 26 24 68 26 24 69 25 23 70 27 14 71 27 14 72 25 23 73 28 25 74 27 14 75 28 25 76 29 26 77 27 14 78 29 26 79 30 27 80 30 27 81 29 26 82 17 16 83 30 27 84 17 16 85 18 16 86 31 28 87 32 29 88 33 30 89 32 29 90 31 28 91 34 31 92 32 29 93 34 31 94 35 32 95 32 29 96 35 32 97 36 33 98 36 33 99 35 32 100 37 34 101 36 33 102 37 34 103 38 35 104 38 35 105 37 34 106 16 16 107 38 35 108 16 16 109 17 16 110 8 8 111 39 36 112 7 7 113 39 36 114 8 8 115 26 24 116 39 36 117 26 24 118 40 37 119 40 37 120 26 24 121 41 38 122 7 7 123 42 39 124 5 5 125 42 39 126 7 7 127 39 36 128 5 5 129 43 40 130 1 1 131 43 40 132 5 5 133 42 39 134 1 1 135 44 41 136 2 2 137 44 41 138 1 1 139 43 40 140 44 41 141 43 40 142 45 42 143 45 42 144 43 40 145 46 43 146 46 43 147 43 40 148 47 44 149 47 44 150 43 40 151 48 45 152 48 45 153 43 40 154 49 46 155 48 45 156 49 46 157 50 47 158 50 47 159 51 48 160 52 49 161 51 48 162 50 47 163 49 46 164 52 49 165 51 48 166 53 50 167 52 49 168 53 50 169 54 51 170 52 49 171 54 51 172 55 52 173 52 49 174 55 52 175 56 53 176 56 53 177 55 52 178 57 54 179 56 53 180 57 54 181 58 55 182 56 53 183 58 55 184 59 56 185 59 56 186 58 55 187 60 57 188 59 56 189 60 57 190 61 58 191 61 58 192 60 57 193 62 59 194 61 58 195 62 59 196 63 60 197 61 58 198 63 60 199 64 61 200 64 61 201 63 60 202 65 62 203 64 61 204 65 62 205 66 63 206 66 63 207 65 62 208 67 64 209 66 63 210 67 64 211 68 65 212 68 65 213 67 64 214 69 66 215 68 65 216 69 66 217 70 67 218 0 0 219 44 41 220 71 68 221 44 41 222 0 0 223 2 2 224 72 69 225 73 70 226 74 71 227 73 70 228 72 69 229 75 72 230 73 70 231 75 72 232 76 73 233 76 73 234 75 72 235 77 74 236 77 74 237 75 72 238 78 75 239 78 75 240 75 72 241 79 76 242 78 75 243 79 76 244 80 77 245 80 77 246 79 76 247 81 78 248 81 78 249 79 76 250 82 79 251 81 78 252 82 79 253 83 80 254 83 80 255 82 79 256 84 81 257 83 80 258 84 81 259 85 82 260 85 82 261 84 81 262 86 83 263 86 83 264 84 81 265 87 84 266 86 83 267 87 84 268 88 85 269 88 85 270 87 84 271 89 86 272 88 85 273 89 86 274 90 87 275 90 87 276 89 86 277 91 88 278 90 87 279 91 88 280 92 89 281 92 89 282 91 88 283 93 90 284 71 68 285 3 3 286 0 0 287 3 3 288 71 68 289 94 91 290 94 91 291 71 68 292 95 92 293 94 91 294 95 92 295 96 93 296 94 91 297 96 93 298 97 94 299 94 91 300 97 94 301 98 95 302 94 91 303 98 95 304 74 71 305 74 71 306 98 95 307 72 69 308 94 91 309 4 4 310 3 3 311 4 4 312 94 91 313 99 96 314 99 96 315 6 6 316 4 4 317 6 6 318 99 96 319 100 97 320 100 97 321 9 9 322 6 6 323 9 9 324 100 97 325 25 23 326 25 23 327 100 97 328 101 98 329 25 23 330 101 98 331 102 99 332 103 100 333 104 101 334 105 102 335 104 101 336 103 100 337 106 103 338 104 101 339 106 103 340 21 19 341 21 19 342 106 103 343 107 104 344 21 19 345 107 104 346 108 105 347 21 19 348 108 105 349 19 17 350 109 106 351 19 17 352 108 105 353 19 17 354 109 106 355 22 20 356 22 20 357 109 106 358 110 107 359 22 20 360 110 107 361 111 108 362 112 109 363 22 20 364 111 108 365 22 20 366 112 109 367 23 21 368 113 110 369 23 21 370 112 109 371 23 21 372 113 110 373 24 22 374 114 111 375 24 22 376 113 110 377 24 22 378 114 111 379 18 16 380 115 112 381 18 16 382 114 111 383 18 16 384 115 112 385 30 27 386 115 112 387 27 14 388 30 27 389 27 14 390 115 112 391 116 113 392 116 113 393 26 24 394 27 14 395 26 24 396 116 113 397 41 38 398 117 114 399 25 23 400 102 99 401 25 23 402 117 114 403 28 25 404 117 114 405 29 26 406 28 25 407 29 26 408 117 114 409 118 115 410 119 116 411 29 26 412 118 115 413 29 26 414 119 116 415 17 16 416 120 117 417 17 16 418 119 116 419 17 16 420 120 117 421 38 35 422 121 118 423 38 35 424 120 117 425 38 35 426 121 118 427 36 33 428 121 118 429 32 29 430 36 33 431 32 29 432 121 118 433 122 119 434 33 30 435 123 120 436 124 121 437 123 120 438 33 30 439 32 29 440 123 120 441 32 29 442 125 122 443 125 122 444 32 29 445 122 119 446 126 123 447 127 124 448 128 125 449 127 124 450 126 123 451 129 126 452 129 126 453 126 123 454 130 127 455 130 127 456 126 123 457 131 128 458 130 127 459 131 128 460 124 121 461 124 121 462 131 128 463 132 129 464 124 121 465 132 129 466 31 28 467 124 121 468 31 28 469 33 30 470 133 130 471 31 28 472 132 129 473 31 28 474 133 130 475 34 31 476 34 31 477 133 130 478 134 107 479 34 31 480 134 107 481 135 131 482 136 132 483 34 31 484 135 131 485 34 31 486 136 132 487 35 32 488 137 133 489 35 32 490 136 132 491 35 32 492 137 133 493 37 34 494 138 134 495 37 34 496 137 133 497 37 34 498 138 134 499 16 16 500 139 135 501 16 16 502 138 134 503 16 16 504 139 135 505 15 15 506 140 136 507 15 15 508 139 135 509 15 15 510 140 136 511 14 14 512 141 137 513 14 14 514 140 136 515 14 14 516 141 137 517 13 13 518 11 11 519 142 138 520 143 139 521 142 138 522 11 11 523 13 13 524 142 138 525 13 13 526 144 140 527 144 140 528 13 13 529 141 137 530 145 141 531 146 142 532 147 143 533 146 142 534 145 141 535 148 144 536 148 144 537 145 141 538 149 145 539 149 145 540 145 141 541 12 12 542 149 145 543 12 12 544 143 139 545 143 139 546 12 12 547 11 11 548 150 146 549 12 12 550 145 141 551 12 12 552 150 146 553 10 10 554 10 10 555 150 146 556 151 147 557 151 147 558 150 146 559 152 148 560 152 148 561 150 146 562 153 149 563 153 149 564 150 146 565 154 150 566 154 150 567 150 146 568 155 151 569 155 151 570 150 146 571 156 152 572 156 152 573 150 146 574 157 153 575 157 153 576 150 146 577 158 154 578 158 154 579 150 146 580 159 155 581 158 154 582 159 155 583 160 156 584 158 154 585 160 156 586 161 157 587 158 154 588 161 157 589 162 158 590 162 158 591 161 157 592 163 159 593 162 158 594 163 159 595 164 160 596 162 158 597 164 160 598 165 161 599 165 161 600 164 160 601 166 162 602 165 161 603 166 162 604 167 163 605 165 161 606 167 163 607 168 164 608 168 164 609 167 163 610 169 165 611 168 164 612 169 165 613 170 166 614 168 164 615 170 166 616 171 167 617 168 164 618 171 167 619 172 168 620 168 164 621 172 168 622 173 169 623 173 169 624 172 168 625 174 170 626 151 147 627 20 18 628 10 10 629 20 18 630 151 147 631 175 171 632 21 19 633 176 172 634 104 101 635 176 172 636 21 19 637 20 18 638 176 172 639 20 18 640 175 171 641 176 172 642 175 171 643 177 173 644 176 172 645 177 173 646 178 174 647 176 172 648 178 174 649 179 175 650 176 172 651 179 175 652 180 176 653 176 172 654 180 176 655 181 177 656 176 172 657 181 177 658 182 178 659 176 172 660 182 178 661 183 179 662 176 172 663 183 179 664 184 180 665 184 180 666 183 179 667 185 181 668 185 181 669 183 179 670 186 182 671 186 182 672 183 179 673 187 183 674 186 182 675 187 183 676 188 184 677 188 184 678 187 183 679 189 185 680 189 185 681 187 183 682 190 186 683 189 185 684 190 186 685 191 187 686 191 187 687 190 186 688 192 188 689 192 188 690 190 186 691 193 189 692 192 188 693 193 189 694 194 190 695 194 190 696 193 189 697 195 191 698 195 191 699 193 189 700 196 192 701 196 192 702 193 189 703 197 193 704 197 193 705 193 189 706 198 194 707 197 193 708 198 194 709 199 195 710 41 38 711 101 98 712 40 37 713 101 98 714 41 38 715 102 99 716 102 99 717 41 38 718 117 114 719 117 114 720 41 38 721 116 113 722 117 114 723 116 113 724 115 112 725 117 114 726 115 112 727 118 115 728 118 115 729 115 112 730 119 116 731 119 116 732 115 112 733 114 111 734 184 180 735 111 108 736 110 107 737 111 108 738 184 180 739 185 181 740 111 108 741 185 181 742 112 109 743 112 109 744 185 181 745 113 110 746 113 110 747 185 181 748 114 111 749 114 111 750 185 181 751 138 134 752 138 134 753 185 181 754 160 156 755 144 140 756 160 156 757 159 155 758 160 156 759 144 140 760 141 137 761 160 156 762 141 137 763 140 136 764 160 156 765 140 136 766 139 135 767 160 156 768 139 135 769 138 134 770 122 119 771 134 107 772 125 122 773 134 107 774 122 119 775 135 131 776 135 131 777 122 119 778 121 118 779 135 131 780 121 118 781 136 132 782 136 132 783 121 118 784 120 117 785 136 132 786 120 117 787 137 133 788 137 133 789 120 117 790 119 116 791 137 133 792 119 116 793 138 134 794 138 196 795 119 196 796 114 196 797 43 40 798 74 71 799 49 46 800 74 71 801 43 40 802 94 91 803 94 91 804 43 40 805 42 39 806 94 91 807 42 39 808 99 96 809 99 96 810 42 39 811 39 36 812 99 96 813 39 36 814 100 97 815 100 97 816 39 36 817 40 37 818 100 97 819 40 37 820 101 98 821 49 46 822 73 70 823 51 48 824 73 70 825 49 46 826 74 71 827 51 48 828 76 73 829 53 50 830 76 73 831 51 48 832 73 70 833 54 51 834 76 73 835 77 74 836 76 73 837 54 51 838 53 50 839 54 51 840 78 75 841 55 52 842 78 75 843 54 51 844 77 74 845 55 52 846 80 77 847 57 54 848 80 77 849 55 52 850 78 75 851 58 55 852 80 77 853 81 78 854 80 77 855 58 55 856 57 54 857 60 57 858 81 78 859 83 80 860 81 78 861 60 57 862 58 55 863 62 59 864 83 80 865 85 82 866 83 80 867 62 59 868 60 57 869 63 60 870 85 82 871 86 83 872 85 82 873 63 60 874 62 59 875 63 60 876 88 85 877 65 62 878 88 85 879 63 60 880 86 83 881 65 62 882 90 87 883 67 64 884 90 87 885 65 62 886 88 85 887 69 66 888 90 87 889 92 89 890 90 87 891 69 66 892 67 64 893 200 197 894 93 90 895 201 198 896 93 90 897 200 197 898 70 67 899 93 90 900 70 67 901 69 66 902 93 90 903 69 66 904 92 89 905 70 67 906 202 199 907 68 65 908 202 199 909 70 67 910 203 200 911 203 200 912 70 67 913 200 197 914 91 88 915 202 199 916 204 201 917 202 199 918 91 88 919 68 65 920 68 65 921 91 88 922 89 86 923 68 65 924 89 86 925 66 63 926 87 84 927 66 63 928 89 86 929 66 63 930 87 84 931 64 61 932 84 81 933 64 61 934 87 84 935 64 61 936 84 81 937 61 58 938 82 79 939 61 58 940 84 81 941 61 58 942 82 79 943 59 56 944 79 76 945 59 56 946 82 79 947 59 56 948 79 76 949 56 53 950 75 72 951 56 53 952 79 76 953 56 53 954 75 72 955 52 49 956 75 72 957 50 47 958 52 49 959 50 47 960 75 72 961 72 69 962 98 95 963 50 47 964 72 69 965 50 47 966 98 95 967 48 45 968 97 94 969 48 45 970 98 95 971 48 45 972 97 94 973 47 44 974 96 93 975 47 44 976 97 94 977 47 44 978 96 93 979 46 43 980 95 92 981 46 43 982 96 93 983 46 43 984 95 92 985 45 42 986 71 68 987 45 42 988 95 92 989 45 42 990 71 68 991 44 41 992 204 201 993 93 90 994 91 88 995 93 90 996 204 201 997 203 200 998 93 90 999 203 200 1000 201 198 1001 205 202 1002 105 102 1003 206 41 1004 105 102 1005 205 202 1006 103 100 1007 207 203 1008 208 204 1009 209 205 1010 208 204 1011 207 203 1012 210 72 1013 208 204 1014 210 72 1015 211 206 1016 211 206 1017 210 72 1018 212 207 1019 212 207 1020 210 72 1021 213 208 1022 213 208 1023 210 72 1024 214 209 1025 213 208 1026 214 209 1027 215 210 1028 215 210 1029 214 209 1030 216 211 1031 216 211 1032 214 209 1033 217 212 1034 216 211 1035 217 212 1036 218 213 1037 218 213 1038 217 212 1039 219 214 1040 218 213 1041 219 214 1042 220 215 1043 220 215 1044 219 214 1045 221 216 1046 221 216 1047 219 214 1048 222 84 1049 221 216 1050 222 84 1051 223 85 1052 223 85 1053 222 84 1054 224 86 1055 223 85 1056 224 86 1057 225 217 1058 225 217 1059 224 86 1060 226 218 1061 225 217 1062 226 218 1063 227 219 1064 227 219 1065 226 218 1066 228 90 1067 205 202 1068 106 103 1069 103 100 1070 106 103 1071 205 202 1072 229 220 1073 229 220 1074 205 202 1075 230 221 1076 229 220 1077 230 221 1078 231 222 1079 229 220 1080 231 222 1081 232 223 1082 229 220 1083 232 223 1084 233 95 1085 229 220 1086 233 95 1087 209 205 1088 209 205 1089 233 95 1090 207 203 1091 229 220 1092 107 104 1093 106 103 1094 107 104 1095 229 220 1096 234 224 1097 234 224 1098 108 105 1099 107 104 1100 108 105 1101 234 224 1102 109 106 1103 104 101 1104 206 41 1105 105 102 1106 206 41 1107 104 101 1108 176 172 1109 206 41 1110 176 172 1111 235 42 1112 235 42 1113 176 172 1114 236 225 1115 236 225 1116 176 172 1117 237 226 1118 237 226 1119 176 172 1120 238 45 1121 238 45 1122 176 172 1123 239 46 1124 238 45 1125 239 46 1126 240 47 1127 240 47 1128 241 48 1129 242 49 1130 241 48 1131 240 47 1132 239 46 1133 242 49 1134 241 48 1135 243 227 1136 242 49 1137 243 227 1138 244 51 1139 242 49 1140 244 51 1141 245 52 1142 242 49 1143 245 52 1144 246 53 1145 246 53 1146 245 52 1147 247 54 1148 246 53 1149 247 54 1150 248 55 1151 246 53 1152 248 55 1153 249 228 1154 249 228 1155 248 55 1156 250 57 1157 249 228 1158 250 57 1159 251 229 1160 251 229 1161 250 57 1162 252 230 1163 251 229 1164 252 230 1165 253 231 1166 251 229 1167 253 231 1168 254 61 1169 254 61 1170 253 231 1171 255 62 1172 254 61 1173 255 62 1174 256 63 1175 256 63 1176 255 62 1177 257 64 1178 256 63 1179 257 64 1180 258 232 1181 258 232 1182 257 64 1183 259 66 1184 258 232 1185 259 66 1186 260 67 1187 176 172 1188 209 205 1189 239 46 1190 209 205 1191 176 172 1192 229 220 1193 229 220 1194 176 172 1195 184 180 1196 229 220 1197 184 180 1198 234 224 1199 234 224 1200 184 180 1201 109 106 1202 109 106 1203 184 180 1204 110 107 1205 261 233 1206 262 234 1207 263 235 1208 262 234 1209 261 233 1210 264 236 1211 262 234 1212 264 236 1213 265 237 1214 265 237 1215 264 236 1216 266 238 1217 265 237 1218 266 238 1219 133 130 1220 133 130 1221 266 238 1222 123 120 1223 133 130 1224 123 120 1225 134 107 1226 134 107 1227 123 120 1228 125 122 1229 124 121 1230 266 238 1231 130 127 1232 266 238 1233 124 121 1234 123 120 1235 130 127 1236 264 236 1237 129 126 1238 264 236 1239 130 127 1240 266 238 1241 129 126 1242 267 239 1243 127 124 1244 267 239 1245 129 126 1246 264 236 1247 267 239 1248 264 236 1249 268 240 1250 268 240 1251 264 236 1252 269 43 1253 269 43 1254 264 236 1255 270 241 1256 270 241 1257 264 236 1258 271 45 1259 271 45 1260 264 236 1261 261 233 1262 271 45 1263 261 233 1264 272 242 1265 272 242 1266 273 243 1267 274 244 1268 273 243 1269 272 242 1270 261 233 1271 274 244 1272 273 243 1273 275 245 1274 274 244 1275 275 245 1276 276 246 1277 274 244 1278 276 246 1279 277 247 1280 274 244 1281 277 247 1282 278 248 1283 278 248 1284 277 247 1285 279 54 1286 278 248 1287 279 54 1288 280 249 1289 278 248 1290 280 249 1291 281 250 1292 281 250 1293 280 249 1294 282 251 1295 281 250 1296 282 251 1297 283 252 1298 283 252 1299 282 251 1300 284 253 1301 283 252 1302 284 253 1303 285 60 1304 283 252 1305 285 60 1306 286 61 1307 286 61 1308 285 60 1309 287 62 1310 286 61 1311 287 62 1312 288 254 1313 288 254 1314 287 62 1315 289 255 1316 288 254 1317 289 255 1318 290 65 1319 290 65 1320 289 255 1321 291 256 1322 290 65 1323 291 256 1324 292 67 1325 128 125 1326 267 239 1327 293 202 1328 267 239 1329 128 125 1330 127 124 1331 294 203 1332 295 204 1333 263 235 1334 295 204 1335 294 203 1336 296 72 1337 295 204 1338 296 72 1339 297 206 1340 297 206 1341 296 72 1342 298 207 1343 298 207 1344 296 72 1345 299 208 1346 299 208 1347 296 72 1348 300 257 1349 299 208 1350 300 257 1351 301 258 1352 301 258 1353 300 257 1354 302 259 1355 302 259 1356 300 257 1357 303 212 1358 302 259 1359 303 212 1360 304 260 1361 304 260 1362 303 212 1363 305 81 1364 304 260 1365 305 81 1366 306 215 1367 306 215 1368 305 81 1369 307 216 1370 307 216 1371 305 81 1372 308 261 1373 307 216 1374 308 261 1375 309 262 1376 309 262 1377 308 261 1378 310 263 1379 309 262 1380 310 263 1381 311 264 1382 311 264 1383 310 263 1384 312 265 1385 311 264 1386 312 265 1387 313 266 1388 313 266 1389 312 265 1390 314 267 1391 293 202 1392 126 123 1393 128 125 1394 126 123 1395 293 202 1396 262 234 1397 262 234 1398 293 202 1399 315 268 1400 262 234 1401 315 268 1402 316 93 1403 262 234 1404 316 93 1405 317 223 1406 262 234 1407 317 223 1408 318 95 1409 262 234 1410 318 95 1411 263 235 1412 263 235 1413 318 95 1414 294 203 1415 262 234 1416 131 128 1417 126 123 1418 131 128 1419 262 234 1420 265 237 1421 265 237 1422 132 129 1423 131 128 1424 132 129 1425 265 237 1426 133 130 1427 319 269 1428 320 270 1429 321 271 1430 320 270 1431 319 269 1432 150 146 1433 150 146 1434 319 269 1435 322 272 1436 150 146 1437 322 272 1438 159 155 1439 159 155 1440 322 272 1441 142 138 1442 159 155 1443 142 138 1444 144 140 1445 143 139 1446 322 272 1447 149 145 1448 322 272 1449 143 139 1450 142 138 1451 147 143 1452 323 273 1453 324 202 1454 323 273 1455 147 143 1456 146 142 1457 325 203 1458 326 204 1459 320 270 1460 326 204 1461 325 203 1462 327 72 1463 326 204 1464 327 72 1465 328 274 1466 328 274 1467 327 72 1468 329 207 1469 329 207 1470 327 72 1471 330 208 1472 330 208 1473 327 72 1474 331 257 1475 330 208 1476 331 257 1477 332 258 1478 332 258 1479 331 257 1480 333 259 1481 333 259 1482 331 257 1483 334 212 1484 333 259 1485 334 212 1486 335 260 1487 335 260 1488 334 212 1489 336 81 1490 335 260 1491 336 81 1492 337 215 1493 337 215 1494 336 81 1495 338 216 1496 338 216 1497 336 81 1498 339 84 1499 338 216 1500 339 84 1501 340 275 1502 340 275 1503 339 84 1504 341 276 1505 340 275 1506 341 276 1507 342 277 1508 342 277 1509 341 276 1510 343 278 1511 342 277 1512 343 278 1513 344 279 1514 344 279 1515 343 278 1516 345 280 1517 324 202 1518 145 141 1519 147 143 1520 145 141 1521 324 202 1522 150 146 1523 150 146 1524 324 202 1525 346 268 1526 150 146 1527 346 268 1528 347 93 1529 150 146 1530 347 93 1531 348 223 1532 150 146 1533 348 223 1534 349 95 1535 150 146 1536 349 95 1537 320 270 1538 320 270 1539 349 95 1540 325 203 1541 149 145 1542 319 269 1543 148 144 1544 319 269 1545 149 145 1546 322 272 1547 148 144 1548 323 273 1549 146 142 1550 323 273 1551 148 144 1552 319 269 1553 323 273 1554 319 269 1555 350 42 1556 350 42 1557 319 269 1558 351 43 1559 351 43 1560 319 269 1561 352 226 1562 352 226 1563 319 269 1564 353 45 1565 353 45 1566 319 269 1567 321 271 1568 353 45 1569 321 271 1570 354 281 1571 354 281 1572 355 282 1573 356 49 1574 355 282 1575 354 281 1576 321 271 1577 356 49 1578 355 282 1579 357 50 1580 356 49 1581 357 50 1582 358 283 1583 356 49 1584 358 283 1585 359 52 1586 356 49 1587 359 52 1588 360 53 1589 360 53 1590 359 52 1591 361 54 1592 360 53 1593 361 54 1594 362 55 1595 360 53 1596 362 55 1597 363 56 1598 363 56 1599 362 55 1600 364 57 1601 363 56 1602 364 57 1603 365 58 1604 365 58 1605 364 57 1606 366 284 1607 365 58 1608 366 284 1609 367 285 1610 365 58 1611 367 285 1612 368 61 1613 368 61 1614 367 285 1615 369 62 1616 368 61 1617 369 62 1618 370 63 1619 370 63 1620 369 62 1621 371 64 1622 370 63 1623 371 64 1624 372 232 1625 372 232 1626 371 64 1627 373 66 1628 372 232 1629 373 66 1630 374 67 1631 185 181 1632 161 157 1633 160 156 1634 161 157 1635 185 181 1636 186 182 1637 188 184 1638 161 157 1639 186 182 1640 161 157 1641 188 184 1642 163 159 1643 188 184 1644 164 160 1645 163 159 1646 164 160 1647 188 184 1648 189 185 1649 189 185 1650 166 162 1651 164 160 1652 166 162 1653 189 185 1654 191 187 1655 192 188 1656 166 162 1657 191 187 1658 166 162 1659 192 188 1660 167 163 1661 194 190 1662 167 163 1663 192 188 1664 167 163 1665 194 190 1666 169 165 1667 195 191 1668 169 165 1669 194 190 1670 169 165 1671 195 191 1672 170 166 1673 196 192 1674 170 166 1675 195 191 1676 170 166 1677 196 192 1678 171 167 1679 197 193 1680 171 167 1681 196 192 1682 171 167 1683 197 193 1684 172 168 1685 199 195 1686 172 168 1687 197 193 1688 172 168 1689 199 195 1690 174 170 1691 198 194 1692 174 170 1693 199 195 1694 174 170 1695 198 194 1696 173 169 1697 173 169 1698 198 194 1699 375 286 1700 173 169 1701 375 286 1702 376 287 1703 376 287 1704 375 286 1705 377 288 1706 377 288 1707 375 286 1708 378 289 1709 377 288 1710 378 289 1711 379 290 1712 379 290 1713 378 289 1714 380 291 1715 379 290 1716 380 291 1717 381 292 1718 381 292 1719 380 291 1720 382 293 1721 381 292 1722 382 293 1723 383 294 1724 381 292 1725 383 294 1726 384 295 1727 384 295 1728 383 294 1729 385 296 1730 384 295 1731 385 296 1732 386 297 1733 173 169 1734 387 298 1735 168 164 1736 387 298 1737 173 169 1738 376 287 1739 165 161 1740 193 189 1741 190 186 1742 193 189 1743 165 161 1744 168 164 1745 193 189 1746 168 164 1747 387 298 1748 193 189 1749 387 298 1750 388 299 1751 388 299 1752 387 298 1753 389 300 1754 388 299 1755 389 300 1756 390 301 1757 390 301 1758 389 300 1759 391 302 1760 390 301 1761 391 302 1762 392 303 1763 392 303 1764 391 302 1765 393 304 1766 392 303 1767 393 304 1768 394 305 1769 394 305 1770 393 304 1771 395 306 1772 394 305 1773 395 306 1774 396 307 1775 396 307 1776 395 306 1777 397 308 1778 396 307 1779 397 308 1780 398 309 1781 165 161 1782 187 183 1783 162 158 1784 187 183 1785 165 161 1786 190 186 1787 162 158 1788 183 179 1789 158 154 1790 183 179 1791 162 158 1792 187 183 1793 158 154 1794 182 178 1795 157 153 1796 182 178 1797 158 154 1798 183 179 1799 157 153 1800 181 177 1801 156 152 1802 181 177 1803 157 153 1804 182 178 1805 156 152 1806 180 176 1807 155 151 1808 180 176 1809 156 152 1810 181 177 1811 154 150 1812 180 176 1813 179 175 1814 180 176 1815 154 150 1816 155 151 1817 154 150 1818 178 174 1819 153 149 1820 178 174 1821 154 150 1822 179 175 1823 152 148 1824 178 174 1825 177 173 1826 178 174 1827 152 148 1828 153 149 1829 151 147 1830 177 173 1831 175 171 1832 177 173 1833 151 147 1834 152 148 1835 388 299 1836 198 194 1837 193 189 1838 198 194 1839 388 299 1840 375 286 1841 200 197 1842 201 198 1843 203 200 1844 202 199 1845 203 200 1846 204 201 1847 205 202 1848 235 42 1849 230 221 1850 235 42 1851 205 202 1852 206 41 1853 399 310 1854 228 90 1855 226 218 1856 228 90 1857 399 310 1858 400 311 1859 228 90 1860 400 311 1861 401 312 1862 260 67 1863 401 312 1864 402 197 1865 401 312 1866 260 67 1867 228 90 1868 228 90 1869 260 67 1870 227 219 1871 227 219 1872 260 67 1873 259 66 1874 259 66 1875 225 217 1876 227 219 1877 225 217 1878 259 66 1879 257 64 1880 255 62 1881 225 217 1882 257 64 1883 225 217 1884 255 62 1885 223 85 1886 255 62 1887 221 216 1888 223 85 1889 221 216 1890 255 62 1891 253 231 1892 253 231 1893 220 215 1894 221 216 1895 220 215 1896 253 231 1897 252 230 1898 250 57 1899 220 215 1900 252 230 1901 220 215 1902 250 57 1903 218 213 1904 248 55 1905 218 213 1906 250 57 1907 218 213 1908 248 55 1909 216 211 1910 248 55 1911 215 210 1912 216 211 1913 215 210 1914 248 55 1915 247 54 1916 245 52 1917 215 210 1918 247 54 1919 215 210 1920 245 52 1921 213 208 1922 244 51 1923 213 208 1924 245 52 1925 213 208 1926 244 51 1927 212 207 1928 243 227 1929 212 207 1930 244 51 1931 212 207 1932 243 227 1933 211 206 1934 243 227 1935 208 204 1936 211 206 1937 208 204 1938 243 227 1939 241 48 1940 239 46 1941 208 204 1942 241 48 1943 208 204 1944 239 46 1945 209 205 1946 230 221 1947 236 225 1948 231 222 1949 236 225 1950 230 221 1951 235 42 1952 231 222 1953 237 226 1954 232 223 1955 237 226 1956 231 222 1957 236 225 1958 232 223 1959 238 45 1960 233 95 1961 238 45 1962 232 223 1963 237 226 1964 233 95 1965 240 47 1966 207 203 1967 240 47 1968 233 95 1969 238 45 1970 210 72 1971 240 47 1972 242 49 1973 240 47 1974 210 72 1975 207 203 1976 210 72 1977 246 53 1978 214 209 1979 246 53 1980 210 72 1981 242 49 1982 214 209 1983 249 228 1984 217 212 1985 249 228 1986 214 209 1987 246 53 1988 217 212 1989 251 229 1990 219 214 1991 251 229 1992 217 212 1993 249 228 1994 219 214 1995 254 61 1996 222 84 1997 254 61 1998 219 214 1999 251 229 2000 222 84 2001 256 63 2002 224 86 2003 256 63 2004 222 84 2005 254 61 2006 226 218 2007 403 199 2008 399 310 2009 403 199 2010 226 218 2011 258 232 2012 258 232 2013 226 218 2014 256 63 2015 256 63 2016 226 218 2017 224 86 2018 260 67 2019 403 199 2020 258 232 2021 403 199 2022 260 67 2023 400 311 2024 400 311 2025 260 67 2026 402 197 2027 261 233 2028 295 204 2029 273 243 2030 295 204 2031 261 233 2032 263 235 2033 275 245 2034 295 204 2035 297 206 2036 295 204 2037 275 245 2038 273 243 2039 276 246 2040 297 206 2041 298 207 2042 297 206 2043 276 246 2044 275 245 2045 277 247 2046 298 207 2047 299 208 2048 298 207 2049 277 247 2050 276 246 2051 279 54 2052 299 208 2053 301 258 2054 299 208 2055 279 54 2056 277 247 2057 280 249 2058 301 258 2059 302 259 2060 301 258 2061 280 249 2062 279 54 2063 280 249 2064 304 260 2065 282 251 2066 304 260 2067 280 249 2068 302 259 2069 284 253 2070 304 260 2071 306 215 2072 304 260 2073 284 253 2074 282 251 2075 285 60 2076 306 215 2077 307 216 2078 306 215 2079 285 60 2080 284 253 2081 287 62 2082 307 216 2083 309 262 2084 307 216 2085 287 62 2086 285 60 2087 287 62 2088 311 264 2089 289 255 2090 311 264 2091 287 62 2092 309 262 2093 289 255 2094 313 266 2095 291 256 2096 313 266 2097 289 255 2098 311 264 2099 404 313 2100 314 267 2101 405 314 2102 314 267 2103 404 313 2104 292 67 2105 314 267 2106 292 67 2107 291 256 2108 314 267 2109 291 256 2110 313 266 2111 292 67 2112 406 315 2113 290 65 2114 406 315 2115 292 67 2116 407 316 2117 407 316 2118 292 67 2119 404 313 2120 312 265 2121 406 315 2122 408 310 2123 406 315 2124 312 265 2125 290 65 2126 290 65 2127 312 265 2128 310 263 2129 290 65 2130 310 263 2131 288 254 2132 308 261 2133 288 254 2134 310 263 2135 288 254 2136 308 261 2137 286 61 2138 305 81 2139 286 61 2140 308 261 2141 286 61 2142 305 81 2143 283 252 2144 303 212 2145 283 252 2146 305 81 2147 283 252 2148 303 212 2149 281 250 2150 300 257 2151 281 250 2152 303 212 2153 281 250 2154 300 257 2155 278 248 2156 296 72 2157 278 248 2158 300 257 2159 278 248 2160 296 72 2161 274 244 2162 294 203 2163 274 244 2164 296 72 2165 274 244 2166 294 203 2167 272 242 2168 318 95 2169 272 242 2170 294 203 2171 272 242 2172 318 95 2173 271 45 2174 317 223 2175 271 45 2176 318 95 2177 271 45 2178 317 223 2179 270 241 2180 316 93 2181 270 241 2182 317 223 2183 270 241 2184 316 93 2185 269 43 2186 315 268 2187 269 43 2188 316 93 2189 269 43 2190 315 268 2191 268 240 2192 293 202 2193 268 240 2194 315 268 2195 268 240 2196 293 202 2197 267 239 2198 408 310 2199 314 267 2200 312 265 2201 314 267 2202 408 310 2203 407 316 2204 314 267 2205 407 316 2206 405 314 2207 321 271 2208 326 204 2209 355 282 2210 326 204 2211 321 271 2212 320 270 2213 324 202 2214 350 42 2215 346 268 2216 350 42 2217 324 202 2218 323 273 2219 346 268 2220 351 43 2221 347 93 2222 351 43 2223 346 268 2224 350 42 2225 347 93 2226 352 226 2227 348 223 2228 352 226 2229 347 93 2230 351 43 2231 348 223 2232 353 45 2233 349 95 2234 353 45 2235 348 223 2236 352 226 2237 349 95 2238 354 281 2239 325 203 2240 354 281 2241 349 95 2242 353 45 2243 327 72 2244 354 281 2245 356 49 2246 354 281 2247 327 72 2248 325 203 2249 327 72 2250 360 53 2251 331 257 2252 360 53 2253 327 72 2254 356 49 2255 331 257 2256 363 56 2257 334 212 2258 363 56 2259 331 257 2260 360 53 2261 334 212 2262 365 58 2263 336 81 2264 365 58 2265 334 212 2266 363 56 2267 336 81 2268 368 61 2269 339 84 2270 368 61 2271 336 81 2272 365 58 2273 339 84 2274 370 63 2275 341 276 2276 370 63 2277 339 84 2278 368 61 2279 343 278 2280 409 199 2281 410 317 2282 409 199 2283 343 278 2284 372 232 2285 372 232 2286 343 278 2287 341 276 2288 372 232 2289 341 276 2290 370 63 2291 410 317 2292 345 280 2293 343 278 2294 345 280 2295 410 317 2296 411 318 2297 345 280 2298 411 318 2299 412 319 2300 413 320 2301 345 280 2302 412 319 2303 345 280 2304 413 320 2305 374 67 2306 345 280 2307 374 67 2308 373 66 2309 345 280 2310 373 66 2311 344 279 2312 371 64 2313 344 279 2314 373 66 2315 344 279 2316 371 64 2317 342 277 2318 369 62 2319 342 277 2320 371 64 2321 342 277 2322 369 62 2323 340 275 2324 367 285 2325 340 275 2326 369 62 2327 340 275 2328 367 285 2329 338 216 2330 366 284 2331 338 216 2332 367 285 2333 338 216 2334 366 284 2335 337 215 2336 366 284 2337 335 260 2338 337 215 2339 335 260 2340 366 284 2341 364 57 2342 364 57 2343 333 259 2344 335 260 2345 333 259 2346 364 57 2347 362 55 2348 362 55 2349 332 258 2350 333 259 2351 332 258 2352 362 55 2353 361 54 2354 361 54 2355 330 208 2356 332 258 2357 330 208 2358 361 54 2359 359 52 2360 359 52 2361 329 207 2362 330 208 2363 329 207 2364 359 52 2365 358 283 2366 358 283 2367 328 274 2368 329 207 2369 328 274 2370 358 283 2371 357 50 2372 355 282 2373 328 274 2374 357 50 2375 328 274 2376 355 282 2377 326 204 2378 374 67 2379 409 199 2380 372 232 2381 409 199 2382 374 67 2383 411 318 2384 411 318 2385 374 67 2386 413 320 2387 414 321 2388 386 297 2389 385 296 2390 386 297 2391 414 321 2392 415 322 2393 415 322 2394 414 321 2395 416 323 2396 415 322 2397 416 323 2398 417 324 2399 417 324 2400 416 323 2401 418 325 2402 417 324 2403 418 325 2404 419 326 2405 384 295 2406 397 308 2407 395 306 2408 397 308 2409 384 295 2410 420 327 2411 420 327 2412 384 295 2413 415 322 2414 415 322 2415 384 295 2416 386 297 2417 381 292 2418 395 306 2419 393 304 2420 395 306 2421 381 292 2422 384 295 2423 379 290 2424 393 304 2425 391 302 2426 393 304 2427 379 290 2428 381 292 2429 377 288 2430 391 302 2431 389 300 2432 391 302 2433 377 288 2434 379 290 2435 376 287 2436 389 300 2437 387 298 2438 389 300 2439 376 287 2440 377 288 2441 390 301 2442 375 286 2443 388 299 2444 375 286 2445 390 301 2446 378 289 2447 392 303 2448 378 289 2449 390 301 2450 378 289 2451 392 303 2452 380 291 2453 394 305 2454 380 291 2455 392 303 2456 380 291 2457 394 305 2458 382 293 2459 396 307 2460 382 293 2461 394 305 2462 382 293 2463 396 307 2464 383 294 2465 398 309 2466 383 294 2467 396 307 2468 383 294 2469 398 309 2470 421 328 2471 383 294 2472 421 328 2473 414 321 2474 383 294 2475 414 321 2476 385 296 2477 420 327 2478 398 309 2479 397 308 2480 398 309 2481 420 327 2482 421 328 2483 421 328 2484 420 327 2485 422 329 2486 421 328 2487 422 329 2488 423 330 2489 423 330 2490 422 329 2491 424 331 2492 423 330 2493 424 331 2494 425 332 2495 403 199 2496 400 311 2497 399 310 2498 401 312 2499 400 311 2500 402 197 2501 404 313 2502 405 314 2503 407 316 2504 406 315 2505 407 316 2506 408 310 2507 409 199 2508 411 318 2509 410 317 2510 413 320 2511 412 319 2512 411 318 2513 426 333 2514 419 326 2515 418 325 2516 419 326 2517 426 333 2518 427 334 2519 427 334 2520 426 333 2521 428 335 2522 427 334 2523 428 335 2524 429 336 2525 429 336 2526 428 335 2527 430 337 2528 429 336 2529 430 337 2530 431 338 2531 417 324 2532 424 331 2533 422 329 2534 424 331 2535 417 324 2536 432 339 2537 432 339 2538 417 324 2539 427 334 2540 427 334 2541 417 324 2542 419 326 2543 415 322 2544 422 329 2545 420 327 2546 422 329 2547 415 322 2548 417 324 2549 423 330 2550 414 321 2551 421 328 2552 414 321 2553 423 330 2554 416 323 2555 425 332 2556 416 323 2557 423 330 2558 416 323 2559 425 332 2560 433 340 2561 416 323 2562 433 340 2563 426 333 2564 416 323 2565 426 333 2566 418 325 2567 432 339 2568 425 332 2569 424 331 2570 425 332 2571 432 339 2572 433 340 2573 433 340 2574 432 339 2575 434 341 2576 433 340 2577 434 341 2578 435 342 2579 435 342 2580 434 341 2581 436 343 2582 436 343 2583 434 341 2584 437 344 2585 438 345 2586 431 338 2587 430 337 2588 431 338 2589 438 345 2590 439 346 2591 439 346 2592 438 345 2593 440 347 2594 439 346 2595 440 347 2596 441 348 2597 441 348 2598 440 347 2599 442 349 2600 441 348 2601 442 349 2602 443 350 2603 443 350 2604 442 349 2605 444 351 2606 444 351 2607 442 349 2608 445 352 2609 429 336 2610 437 344 2611 434 341 2612 437 344 2613 429 336 2614 446 353 2615 446 353 2616 429 336 2617 439 346 2618 439 346 2619 429 336 2620 431 338 2621 427 334 2622 434 341 2623 432 339 2624 434 341 2625 427 334 2626 429 336 2627 435 342 2628 426 333 2629 433 340 2630 426 333 2631 435 342 2632 428 335 2633 436 343 2634 428 335 2635 435 342 2636 428 335 2637 436 343 2638 447 354 2639 428 335 2640 447 354 2641 438 345 2642 428 335 2643 438 345 2644 430 337 2645 446 353 2646 436 343 2647 437 344 2648 436 343 2649 446 353 2650 447 354 2651 447 354 2652 446 353 2653 448 355 2654 447 354 2655 448 355 2656 449 356 2657 449 356 2658 448 355 2659 450 357 2660 449 356 2661 450 357 2662 451 358 2663 451 358 2664 450 357 2665 452 359 2666 452 359 2667 450 357 2668 453 360 2669 449 356 2670 438 345 2671 447 354 2672 438 345 2673 449 356 2674 440 347 2675 451 358 2676 440 347 2677 449 356 2678 440 347 2679 451 358 2680 442 349 2681 452 359 2682 442 349 2683 451 358 2684 442 349 2685 452 359 2686 454 361 2687 442 349 2688 454 361 2689 455 362 2690 442 349 2691 455 362 2692 456 363 2693 442 349 2694 456 363 2695 457 364 2696 442 349 2697 457 364 2698 445 352 2699 445 352 2700 457 364 2701 458 365 2702 458 365 2703 457 364 2704 459 366 2705 445 352 2706 460 367 2707 444 351 2708 460 367 2709 445 352 2710 458 365 2711 443 350 2712 453 360 2713 450 357 2714 453 360 2715 443 350 2716 461 368 2717 461 368 2718 443 350 2719 462 369 2720 462 369 2721 443 350 2722 463 370 2723 463 370 2724 443 350 2725 464 371 2726 464 371 2727 443 350 2728 444 351 2729 464 371 2730 444 351 2731 460 367 2732 464 371 2733 460 367 2734 465 372 2735 441 348 2736 450 357 2737 448 355 2738 450 357 2739 441 348 2740 443 350 2741 439 346 2742 448 355 2743 446 353 2744 448 355 2745 439 346 2746 441 348 2747 461 368 2748 452 359 2749 453 360 2750 452 359 2751 461 368 2752 454 361 2753 466 373 2754 457 364 2755 456 363 2756 457 364 2757 466 373 2758 467 374 2759 457 364 2760 467 374 2761 468 375 2762 457 364 2763 468 375 2764 469 376 2765 459 366 2766 464 371 2767 465 372 2768 464 371 2769 459 366 2770 457 364 2771 464 371 2772 457 364 2773 470 377 2774 470 377 2775 457 364 2776 469 376 2777 458 365 2778 465 372 2779 460 367 2780 465 372 2781 458 365 2782 459 366 2783 462 369 2784 454 361 2785 461 368 2786 454 361 2787 462 369 2788 455 362 2789 463 370 2790 455 362 2791 462 369 2792 455 362 2793 463 370 2794 456 363 2795 456 363 2796 463 370 2797 471 378 2798 456 363 2799 471 378 2800 466 373 2801 464 371 2802 471 378 2803 463 370 2804 471 378 2805 464 371 2806 472 379 2807 472 379 2808 464 371 2809 473 380 2810 473 380 2811 464 371 2812 470 377 2813 474 381 2814 468 375 2815 467 374 2816 468 375 2817 474 381 2818 475 382 2819 469 376 2820 473 380 2821 470 377 2822 473 380 2823 469 376 2824 468 375 2825 473 380 2826 468 375 2827 476 383 2828 476 383 2829 468 375 2830 475 382 2831 476 383 2832 475 382 2833 477 384 2834 476 383 2835 477 384 2836 478 385 2837 471 378 2838 467 374 2839 466 373 2840 467 374 2841 471 378 2842 472 379 2843 467 374 2844 472 379 2845 479 386 2846 467 374 2847 479 386 2848 474 381 2849 474 381 2850 479 386 2851 480 387 2852 480 387 2853 479 386 2854 481 388 2855 473 380 2856 479 386 2857 472 379 2858 479 386 2859 473 380 2860 476 383 2861 480 387 2862 475 382 2863 474 381 2864 475 382 2865 480 387 2866 482 389 2867 475 382 2868 482 389 2869 483 390 2870 475 382 2871 483 390 2872 477 384 2873 483 390 2874 478 385 2875 477 384 2876 478 385 2877 483 390 2878 484 391 2879 484 391 2880 483 390 2881 485 392 2882 484 391 2883 485 392 2884 486 393 2885 486 393 2886 485 392 2887 487 394 2888 487 394 2889 485 392 2890 488 395 2891 476 383 2892 481 388 2893 479 386 2894 481 388 2895 476 383 2896 489 396 2897 489 396 2898 476 383 2899 484 391 2900 484 391 2901 476 383 2902 478 385 2903 481 388 2904 482 389 2905 480 387 2906 482 389 2907 481 388 2908 489 396 2909 482 389 2910 489 396 2911 490 397 2912 482 389 2913 490 397 2914 491 398 2915 491 398 2916 490 397 2917 492 399 2918 491 398 2919 492 399 2920 493 400 2921 491 398 2922 483 390 2923 482 389 2924 483 390 2925 491 398 2926 485 392 2927 494 401 2928 487 394 2929 488 395 2930 487 394 2931 494 401 2932 495 402 2933 495 402 2934 494 401 2935 496 403 2936 495 402 2937 496 403 2938 497 404 2939 497 404 2940 496 403 2941 498 405 2942 497 404 2943 498 405 2944 499 406 2945 486 393 2946 492 399 2947 490 397 2948 492 399 2949 486 393 2950 500 407 2951 500 407 2952 486 393 2953 495 402 2954 495 402 2955 486 393 2956 487 394 2957 484 391 2958 490 397 2959 489 396 2960 490 397 2961 484 391 2962 486 393 2963 493 400 2964 485 392 2965 491 398 2966 485 392 2967 493 400 2968 501 408 2969 485 392 2970 501 408 2971 494 401 2972 485 392 2973 494 401 2974 488 395 2975 492 399 2976 501 408 2977 493 400 2978 501 408 2979 492 399 2980 500 407 2981 501 408 2982 500 407 2983 502 409 2984 502 409 2985 500 407 2986 503 410 2987 502 409 2988 503 410 2989 504 411 2990 504 411 2991 503 410 2992 505 412 2993 498 405 2994 506 413 2995 499 406 2996 506 413 2997 498 405 2998 507 414 2999 506 413 3000 507 414 3001 508 415 3002 508 415 3003 507 414 3004 509 416 3005 497 404 3006 505 412 3007 503 410 3008 505 412 3009 497 404 3010 510 417 3011 510 417 3012 497 404 3013 506 413 3014 506 413 3015 497 404 3016 499 406 3017 495 402 3018 503 410 3019 500 407 3020 503 410 3021 495 402 3022 497 404 3023 502 409 3024 494 401 3025 501 408 3026 494 401 3027 502 409 3028 496 403 3029 504 411 3030 496 403 3031 502 409 3032 496 403 3033 504 411 3034 511 418 3035 496 403 3036 511 418 3037 507 414 3038 496 403 3039 507 414 3040 498 405 3041 510 417 3042 504 411 3043 505 412 3044 504 411 3045 510 417 3046 511 418 3047 511 418 3048 510 417 3049 512 419 3050 511 418 3051 512 419 3052 513 420 3053 514 421 3054 508 415 3055 509 416 3056 508 415 3057 514 421 3058 515 422 3059 515 422 3060 514 421 3061 516 423 3062 515 422 3063 516 423 3064 517 424 3065 506 413 3066 512 419 3067 510 417 3068 512 419 3069 506 413 3070 508 415 3071 513 420 3072 507 414 3073 511 418 3074 507 414 3075 513 420 3076 509 416 3077 518 425 3078 513 420 3079 512 419 3080 513 420 3081 518 425 3082 519 426 3083 519 426 3084 518 425 3085 520 427 3086 520 427 3087 518 425 3088 521 428 3089 516 423 3090 522 429 3091 517 424 3092 522 429 3093 516 423 3094 523 430 3095 522 429 3096 523 430 3097 524 431 3098 524 431 3099 523 430 3100 525 432 3101 524 431 3102 525 432 3103 526 433 3104 526 433 3105 525 432 3106 527 434 3107 515 422 3108 521 428 3109 518 425 3110 521 428 3111 515 422 3112 528 435 3113 528 435 3114 515 422 3115 522 429 3116 522 429 3117 515 422 3118 517 424 3119 508 415 3120 518 425 3121 512 419 3122 518 425 3123 508 415 3124 515 422 3125 519 426 3126 509 416 3127 513 420 3128 509 416 3129 519 426 3130 514 421 3131 520 427 3132 514 421 3133 519 426 3134 514 421 3135 520 427 3136 529 436 3137 514 421 3138 529 436 3139 523 430 3140 514 421 3141 523 430 3142 516 423 3143 521 428 3144 529 436 3145 520 427 3146 529 436 3147 521 428 3148 528 435 3149 529 436 3150 528 435 3151 530 437 3152 529 436 3153 530 437 3154 531 438 3155 531 438 3156 530 437 3157 532 439 3158 531 438 3159 532 439 3160 533 440 3161 527 434 3162 534 441 3163 526 433 3164 534 441 3165 527 434 3166 535 442 3167 534 441 3168 535 442 3169 536 443 3170 536 443 3171 535 442 3172 537 444 3173 524 431 3174 532 439 3175 530 437 3176 532 439 3177 524 431 3178 538 445 3179 538 445 3180 524 431 3181 534 441 3182 534 441 3183 524 431 3184 526 433 3185 522 429 3186 530 437 3187 528 435 3188 530 437 3189 522 429 3190 524 431 3191 531 438 3192 523 430 3193 529 436 3194 523 430 3195 531 438 3196 525 432 3197 533 440 3198 525 432 3199 531 438 3200 525 432 3201 533 440 3202 539 446 3203 525 432 3204 539 446 3205 535 442 3206 525 432 3207 535 442 3208 527 434 3209 532 439 3210 539 446 3211 533 440 3212 539 446 3213 532 439 3214 538 445 3215 539 446 3216 538 445 3217 540 447 3218 539 446 3219 540 447 3220 541 448 3221 542 449 3222 536 443 3223 537 444 3224 536 443 3225 542 449 3226 543 450 3227 534 441 3228 540 447 3229 538 445 3230 540 447 3231 534 441 3232 544 451 3233 544 451 3234 534 441 3235 545 452 3236 545 452 3237 534 441 3238 546 453 3239 546 453 3240 534 441 3241 547 454 3242 547 454 3243 534 441 3244 548 455 3245 548 455 3246 534 441 3247 549 456 3248 549 456 3249 534 441 3250 550 457 3251 550 457 3252 534 441 3253 551 458 3254 551 458 3255 534 441 3256 552 459 3257 552 459 3258 534 441 3259 553 460 3260 553 460 3261 534 441 3262 536 443 3263 553 460 3264 536 443 3265 543 450 3266 553 460 3267 543 450 3268 554 461 3269 554 461 3270 543 450 3271 555 462 3272 556 463 3273 557 464 3274 558 465 3275 557 464 3276 556 463 3277 559 466 3278 557 464 3279 559 466 3280 560 467 3281 560 467 3282 559 466 3283 546 453 3284 546 453 3285 559 466 3286 561 468 3287 546 453 3288 561 468 3289 562 469 3290 546 453 3291 562 469 3292 563 470 3293 546 453 3294 563 470 3295 564 471 3296 546 453 3297 564 471 3298 565 472 3299 546 453 3300 565 472 3301 566 473 3302 546 453 3303 566 473 3304 567 474 3305 546 453 3306 567 474 3307 568 475 3308 546 453 3309 568 475 3310 545 452 3311 569 476 3312 570 477 3313 571 478 3314 570 477 3315 569 476 3316 572 479 3317 572 479 3318 569 476 3319 573 480 3320 572 479 3321 573 480 3322 574 481 3323 572 479 3324 574 481 3325 575 482 3326 575 482 3327 574 481 3328 576 483 3329 576 483 3330 574 481 3331 577 484 3332 577 484 3333 574 481 3334 578 485 3335 578 485 3336 574 481 3337 579 486 3338 579 486 3339 574 481 3340 580 487 3341 580 487 3342 574 481 3343 581 488 3344 581 488 3345 574 481 3346 582 489 3347 582 489 3348 574 481 3349 583 490 3350 541 448 3351 535 442 3352 539 446 3353 535 442 3354 541 448 3355 584 491 3356 535 442 3357 584 491 3358 583 490 3359 535 442 3360 583 490 3361 574 481 3362 535 442 3363 574 481 3364 585 492 3365 535 442 3366 585 492 3367 586 493 3368 535 442 3369 586 493 3370 587 494 3371 535 442 3372 587 494 3373 588 495 3374 535 442 3375 588 495 3376 589 496 3377 535 442 3378 589 496 3379 590 497 3380 535 442 3381 590 497 3382 591 498 3383 535 442 3384 591 498 3385 537 444 3386 537 444 3387 591 498 3388 542 449 3389 542 449 3390 591 498 3391 592 499 3392 542 449 3393 592 499 3394 593 500 3395 540 447 3396 584 491 3397 541 448 3398 584 491 3399 540 447 3400 544 451 3401 593 500 3402 543 450 3403 542 449 3404 543 450 3405 593 500 3406 555 462 3407 593 500 3408 554 461 3409 555 462 3410 554 461 3411 593 500 3412 592 499 3413 591 498 3414 554 461 3415 592 499 3416 554 461 3417 591 498 3418 553 460 3419 591 498 3420 552 459 3421 553 460 3422 552 459 3423 591 498 3424 590 497 3425 590 497 3426 551 458 3427 552 459 3428 551 458 3429 590 497 3430 589 496 3431 588 495 3432 551 458 3433 589 496 3434 551 458 3435 588 495 3436 550 457 3437 587 494 3438 550 457 3439 588 495 3440 550 457 3441 587 494 3442 549 456 3443 586 493 3444 549 456 3445 587 494 3446 549 456 3447 586 493 3448 548 455 3449 585 492 3450 548 455 3451 586 493 3452 548 455 3453 585 492 3454 547 454 3455 585 492 3456 546 453 3457 547 454 3458 546 453 3459 585 492 3460 574 481 3461 573 480 3462 546 453 3463 574 481 3464 546 453 3465 573 480 3466 560 467 3467 573 480 3468 557 464 3469 560 467 3470 557 464 3471 573 480 3472 569 476 3473 557 464 3474 569 476 3475 594 501 3476 594 501 3477 569 476 3478 595 502 3479 596 503 3480 597 504 3481 598 505 3482 597 504 3483 596 503 3484 558 465 3485 597 504 3486 558 465 3487 594 501 3488 594 501 3489 558 465 3490 557 464 3491 558 465 3492 570 477 3493 556 463 3494 570 477 3495 558 465 3496 571 478 3497 571 478 3498 558 465 3499 596 503 3500 571 478 3501 596 503 3502 599 506 3503 556 463 3504 572 479 3505 559 466 3506 572 479 3507 556 463 3508 570 477 3509 561 468 3510 572 479 3511 575 482 3512 572 479 3513 561 468 3514 559 466 3515 561 468 3516 576 483 3517 562 469 3518 576 483 3519 561 468 3520 575 482 3521 562 469 3522 577 484 3523 563 470 3524 577 484 3525 562 469 3526 576 483 3527 563 470 3528 578 485 3529 564 471 3530 578 485 3531 563 470 3532 577 484 3533 564 471 3534 579 486 3535 565 472 3536 579 486 3537 564 471 3538 578 485 3539 565 472 3540 580 487 3541 566 473 3542 580 487 3543 565 472 3544 579 486 3545 566 473 3546 581 488 3547 567 474 3548 581 488 3549 566 473 3550 580 487 3551 568 475 3552 581 488 3553 582 489 3554 581 488 3555 568 475 3556 567 474 3557 568 475 3558 583 490 3559 545 452 3560 583 490 3561 568 475 3562 582 489 3563 545 452 3564 584 491 3565 544 451 3566 584 491 3567 545 452 3568 583 490 3569 600 507 3570 599 506 3571 601 508 3572 599 506 3573 600 507 3574 571 478 3575 571 478 3576 600 507 3577 595 502 3578 571 478 3579 595 502 3580 569 476 3581 600 507 3582 594 501 3583 595 502 3584 594 501 3585 600 507 3586 597 504 3587 597 504 3588 600 507 3589 602 509 3590 602 509 3591 600 507 3592 603 510 3593 604 511 3594 605 512 3595 606 513 3596 605 512 3597 604 511 3598 598 505 3599 605 512 3600 598 505 3601 602 509 3602 602 509 3603 598 505 3604 597 504 3605 598 505 3606 599 506 3607 596 503 3608 599 506 3609 598 505 3610 601 508 3611 601 508 3612 598 505 3613 604 511 3614 601 508 3615 604 511 3616 607 514 3617 608 515 3618 607 514 3619 609 516 3620 607 514 3621 608 515 3622 601 508 3623 601 508 3624 608 515 3625 603 510 3626 601 508 3627 603 510 3628 600 507 3629 603 510 3630 605 512 3631 602 509 3632 605 512 3633 603 510 3634 608 515 3635 605 512 3636 608 515 3637 610 517 3638 610 517 3639 608 515 3640 611 518 3641 612 519 3642 613 520 3643 614 521 3644 613 520 3645 612 519 3646 606 513 3647 613 520 3648 606 513 3649 610 517 3650 610 517 3651 606 513 3652 605 512 3653 606 513 3654 607 514 3655 604 511 3656 607 514 3657 606 513 3658 609 516 3659 609 516 3660 606 513 3661 612 519 3662 609 516 3663 612 519 3664 615 522 3665 616 523 3666 615 522 3667 617 524 3668 615 522 3669 616 523 3670 609 516 3671 609 516 3672 616 523 3673 611 518 3674 609 516 3675 611 518 3676 608 515 3677 611 518 3678 613 520 3679 610 517 3680 613 520 3681 611 518 3682 616 523 3683 613 520 3684 616 523 3685 618 525 3686 618 525 3687 616 523 3688 619 526 3689 620 527 3690 621 528 3691 622 529 3692 621 528 3693 620 527 3694 614 521 3695 621 528 3696 614 521 3697 618 525 3698 618 525 3699 614 521 3700 613 520 3701 612 519 3702 617 524 3703 615 522 3704 617 524 3705 612 519 3706 614 521 3707 617 524 3708 614 521 3709 623 530 3710 623 530 3711 614 521 3712 620 527 3713 624 531 3714 623 530 3715 625 532 3716 623 530 3717 624 531 3718 617 524 3719 617 524 3720 624 531 3721 619 526 3722 617 524 3723 619 526 3724 616 523 3725 619 526 3726 621 528 3727 618 525 3728 621 528 3729 619 526 3730 624 531 3731 621 528 3732 624 531 3733 626 533 3734 626 533 3735 624 531 3736 627 534 3737 628 535 3738 629 536 3739 630 537 3740 629 536 3741 628 535 3742 622 529 3743 629 536 3744 622 529 3745 626 533 3746 626 533 3747 622 529 3748 621 528 3749 620 527 3750 625 532 3751 623 530 3752 625 532 3753 620 527 3754 622 529 3755 625 532 3756 622 529 3757 628 535 3758 625 532 3759 628 535 3760 631 538 3761 632 539 3762 631 538 3763 633 540 3764 631 538 3765 632 539 3766 625 532 3767 625 532 3768 632 539 3769 627 534 3770 625 532 3771 627 534 3772 624 531 3773 627 534 3774 629 536 3775 626 533 3776 629 536 3777 627 534 3778 632 539 3779 629 536 3780 632 539 3781 634 541 3782 634 541 3783 632 539 3784 635 542 3785 630 537 3786 636 543 3787 637 544 3788 636 543 3789 630 537 3790 629 536 3791 636 543 3792 629 536 3793 634 541 3794 636 543 3795 634 541 3796 638 545 3797 630 537 3798 631 538 3799 628 535 3800 631 538 3801 630 537 3802 633 540 3803 633 540 3804 630 537 3805 637 544 3806 633 540 3807 637 544 3808 639 546 3809 640 547 3810 633 540 3811 639 546 3812 633 540 3813 640 547 3814 632 539 3815 632 539 3816 640 547 3817 635 542 3818 635 542 3819 640 547 3820 641 548 3821 635 542 3822 638 545 3823 634 541 3824 638 545 3825 635 542 3826 641 548 3827 638 545 3828 641 548 3829 642 549 3830 642 549 3831 641 548 3832 643 550 3833 638 545 3834 644 551 3835 636 543 3836 644 551 3837 638 545 3838 645 552 3839 645 552 3840 638 545 3841 642 549 3842 646 553 3843 645 552 3844 642 549 3845 637 544 3846 640 547 3847 639 546 3848 640 547 3849 637 544 3850 636 543 3851 640 547 3852 636 543 3853 644 551 3854 640 547 3855 644 551 3856 647 554 3857 648 555 3858 643 550 3859 649 556 3860 647 554 3861 641 548 3862 640 547 3863 641 548 3864 647 554 3865 649 556 3866 641 548 3867 649 556 3868 643 550 3869 648 555 3870 642 549 3871 643 550 3872 642 549 3873 648 555 3874 646 553 3875 646 553 3876 648 555 3877 650 557 3878 650 557 3879 648 555 3880 651 558 3881 646 553 3882 652 559 3883 645 552 3884 652 559 3885 646 553 3886 653 560 3887 653 560 3888 646 553 3889 650 557 3890 653 560 3891 650 557 3892 654 561 3893 645 552 3894 647 554 3895 644 551 3896 647 554 3897 645 552 3898 649 556 3899 649 556 3900 645 552 3901 655 562 3902 655 562 3903 645 552 3904 652 559 3905 655 562 3906 648 555 3907 649 556 3908 648 555 3909 655 562 3910 656 563 3911 648 555 3912 656 563 3913 651 558 3914 651 558 3915 656 563 3916 657 564 3917 657 564 3918 650 557 3919 651 558 3920 650 557 3921 657 564 3922 654 561 3923 654 561 3924 657 564 3925 658 565 3926 658 565 3927 657 564 3928 659 566 3929 654 561 3930 660 567 3931 653 560 3932 660 567 3933 654 561 3934 661 568 3935 661 568 3936 654 561 3937 658 565 3938 661 568 3939 658 565 3940 662 569 3941 652 559 3942 656 563 3943 655 562 3944 656 563 3945 652 559 3946 653 560 3947 656 563 3948 653 560 3949 663 570 3950 663 570 3951 653 560 3952 660 567 3953 663 570 3954 657 564 3955 656 563 3956 657 564 3957 663 570 3958 664 571 3959 657 564 3960 664 571 3961 659 566 3962 659 566 3963 664 571 3964 665 572 3965 665 572 3966 658 565 3967 659 566 3968 658 565 3969 665 572 3970 662 569 3971 662 569 3972 665 572 3973 666 573 3974 662 569 3975 666 573 3976 667 574 3977 662 569 3978 668 575 3979 661 568 3980 668 575 3981 662 569 3982 669 576 3983 669 576 3984 662 569 3985 667 574 3986 669 576 3987 667 574 3988 670 577 3989 661 568 3990 663 570 3991 660 567 3992 663 570 3993 661 568 3994 664 571 3995 664 571 3996 661 568 3997 671 578 3998 671 578 3999 661 568 4000 668 575 4001 671 578 4002 665 572 4003 664 571 4004 665 572 4005 671 578 4006 672 579 4007 665 572 4008 672 579 4009 666 573 4010 666 573 4011 672 579 4012 673 580 4013 666 573 4014 670 577 4015 667 574 4016 670 577 4017 666 573 4018 673 580 4019 670 577 4020 673 580 4021 674 581 4022 670 577 4023 674 581 4024 675 582 4025 670 577 4026 676 583 4027 669 576 4028 676 583 4029 670 577 4030 677 584 4031 677 584 4032 670 577 4033 675 582 4034 677 584 4035 675 582 4036 678 585 4037 668 575 4038 672 579 4039 671 578 4040 672 579 4041 668 575 4042 669 576 4043 672 579 4044 669 576 4045 676 583 4046 672 579 4047 676 583 4048 679 586 4049 679 586 4050 673 580 4051 672 579 4052 673 580 4053 679 586 4054 680 587 4055 673 580 4056 680 587 4057 674 581 4058 674 581 4059 680 587 4060 681 588 4061 674 581 4062 678 585 4063 675 582 4064 678 585 4065 674 581 4066 681 588 4067 678 585 4068 681 588 4069 682 589 4070 678 585 4071 683 590 4072 677 584 4073 683 590 4074 678 585 4075 682 589 4076 677 584 4077 679 586 4078 676 583 4079 679 586 4080 677 584 4081 680 587 4082 680 587 4083 677 584 4084 683 590 4085 683 590 4086 681 588 4087 680 587 4088 681 588 4089 683 590 4090 682 589 4091

-
-
-
-
- - - - - 0.6858805 -0.3173701 0.6548619 7.481132 0.7276338 0.3124686 -0.6106656 -6.50764 -0.01081678 0.8953432 0.4452454 5.343665 0 0 0 1 - - - - -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 - - - - 0.6858805 -0.3173701 0.6548619 7.481132 0.7276337 0.3124686 -0.6106656 -6.50764 -0.01081678 0.8953431 0.4452454 5.343665 0 0 0 1 - - - - -0.2908646 -0.7711008 0.5663933 4.076245 0.9551712 -0.1998833 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 - - - - 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 - - - - - - - - - - - - - -
\ No newline at end of file diff --git a/cram_boxy/cram_boxy_assembly_demo/src/demo.lisp b/cram_boxy/cram_boxy_assembly_demo/src/demo.lisp deleted file mode 100644 index 6e7fce78bc..0000000000 --- a/cram_boxy/cram_boxy_assembly_demo/src/demo.lisp +++ /dev/null @@ -1,119 +0,0 @@ -;;; -;;; Copyright (c) 2018, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software -;;; without specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :demo) - -#+everything-below-is-pr2-s-stuff-so-need-new-things-for-boxy -( -(defparameter *object-cad-models* - '(;; (:cup . "cup_eco_orange") - ;; (:bowl . "edeka_red_bowl") - )) - -(cpl:def-cram-function initialize-or-finalize () - (cpl:with-failure-handling - ((cpl:plan-failure (e) - (declare (ignore e)) - (return))) - (cpl:par - (exe:perform - (desig:an action - (type positioning-arm) - (left-configuration park) - (right-configuration park))) - (let ((?pose (cl-transforms-stamped:make-pose-stamped - cram-tf:*fixed-frame* - 0.0 - (cl-transforms:make-identity-vector) - (cl-transforms:make-identity-rotation)))) - (exe:perform - (desig:an action - (type going) - (target (desig:a location - (pose ?pose)))))) - (exe:perform (desig:an action (type opening-gripper) (gripper (left right)))) - (exe:perform (desig:an action (type looking) (direction forward)))))) - - -(cpl:def-cram-function demo-random (&optional - (random t) - (list-of-objects '(:milk :cup :breakfast-cereal :bowl :spoon))) - (btr:detach-all-objects (btr:get-robot-object)) - (btr-utils:kill-all-objects) - - ;; (setf proj-reasoning::*projection-reasoning-enabled* nil) - (when (eql cram-projection:*projection-environment* - 'urdf-proj:urdf-bullet-projection-environment) - (spawn-objects-on-sink-counter :random random)) - - (setf cram-robot-pose-guassian-costmap::*orientation-samples* 1) - - (initialize-or-finalize) - - (dolist (?object-type list-of-objects) - (let* ((?cad-model - (cdr (assoc ?object-type *object-cad-models*))) - (?object-to-fetch - (desig:an object - (type ?object-type) - (desig:when ?cad-model - (cad-model ?cad-model)))) - (?fetching-location - (desig:a location - (on "CounterTop") - (name "iai_kitchen_sink_area_counter_top") - (side left))) - (?placing-target-pose - (cl-transforms-stamped:pose->pose-stamped - "map" 0.0 - (cram-bullet-reasoning:ensure-pose - (cdr (assoc ?object-type *object-placing-poses*))))) - (?arm-to-use - (cdr (assoc ?object-type *object-grasping-arms*))) - (?delivering-location - (desig:a location - (pose ?placing-target-pose)))) - - (cpl:with-failure-handling - ((common-fail:high-level-failure (e) - (roslisp:ros-warn (pp-plans demo) "Failure happened: ~a~%Skipping..." e) - (return))) - (exe:perform - (desig:an action - (type transporting) - (object ?object-to-fetch) - ;; (arm ?arm-to-use) - (location ?fetching-location) - (target ?delivering-location)))))) - - (initialize-or-finalize) - - cpl:*current-path*) - -) diff --git a/cram_boxy/cram_boxy_assembly_demo/src/projection-demo.lisp b/cram_boxy/cram_boxy_assembly_demo/src/projection-demo.lisp deleted file mode 100644 index f3bd3469b0..0000000000 --- a/cram_boxy/cram_boxy_assembly_demo/src/projection-demo.lisp +++ /dev/null @@ -1,438 +0,0 @@ -;;; -;;; Copyright (c) 2018, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software -;;; without specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :demo) - -(defparameter *plate-x* -1.1115) -(defparameter *plate-y* 1.6) -(defparameter *plate-z* 0.8626) - -(defparameter *plate-rad-x* 0.36) -(defparameter *plate-rad-y* 0.60) -(defparameter *plate-rad-z* 0.008) -(defparameter *holder-bolt-rad-x* 0.05) -(defparameter *holder-bolt-rad-y* 0.025) -(defparameter *holder-bolt-rad-z* 0.0125) -(defparameter *bolt-rad-x* 0.01) -(defparameter *bolt-rad-y* 0.01) -(defparameter *bolt-rad-z* 0.0225) -(defparameter *holder-upperbody-rad-x* 0.085) -(defparameter *holder-upperbody-rad-y* 0.025) -(defparameter *holder-upperbody-rad-z* 0.021) -(defparameter *holder-bottom-wing-rad-x* 0.035) -(defparameter *holder-bottom-wing-rad-y* 0.045) -(defparameter *holder-bottom-wing-rad-z* 0.045) -(defparameter *holder-underbody-rad-x* 0.0925) -(defparameter *holder-underbody-rad-y* 0.025) -(defparameter *holder-underbody-rad-z* 0.024) -(defparameter *holder-plane-horizontal-rad-x* 0.1015) -(defparameter *holder-plane-horizontal-rad-y* 0.05) -(defparameter *holder-plane-horizontal-rad-z* 0.0335) -(defparameter *holder-window-rad-x* 0.026) -(defparameter *holder-window-rad-y* 0.025) -(defparameter *holder-window-rad-z* 0.017) -(defparameter *front-wheel-rad-z* 0.015) -(defparameter *nut-rad-z* 0.0075) -(defparameter *chassis-rad-z* 0.0515) -(defparameter *holder-plane-vertical-rad-x* 0.065) -(defparameter *holder-plane-vertical-rad-y* 0.06) -(defparameter *holder-plane-vertical-rad-z* 0.0175) -(defparameter *holder-top-wing-rad-x* 0.035) -(defparameter *holder-top-wing-rad-y* 0.0415) -(defparameter *holder-top-wing-rad-z* 0.045) - -(defparameter *yellow-plastic* '(0.949 0.807 0.082)) -(defparameter *gray-plastic* '(0.568 0.592 0.584)) -(defparameter *red-plane* '(0.878 0.376 0.243)) -(defparameter *cyan-plane* '(0.078 0.513 0.541)) -(defparameter *yellow-plane* '(0.964 0.847 0.584)) -(defparameter *transparent-plane* '(1 1 1)) -(defparameter *black-plane* '(0.184 0.152 0.121)) -(defparameter *gray-plane* '(0.482 0.537 0.549)) - -(defparameter *object-spawning-data* - `((big-wooden-plate :big-wooden-plate (0.823 0.698 0.513) - ((,*plate-rad-x* ,*plate-rad-y* ,(- *plate-rad-z*)) (0 0 0 1))) - (holder-bolt :holder-bolt ,*yellow-plastic* - ((,*holder-bolt-rad-x* ,*holder-bolt-rad-y* ,*holder-bolt-rad-z*) (0 0 0 1))) - (holder-upper-body :holder-upper-body ,*yellow-plastic* - ((,(+ 0.05 *holder-upperbody-rad-x*) 0.10 ,*holder-upperbody-rad-z*) - (0 0 0 1))) - (holder-bottom-wing :holder-bottom-wing ,*gray-plastic* - ((,(+ 0.1 *holder-bottom-wing-rad-x*) - ,(- 0.3 *holder-bottom-wing-rad-y*) - ,*holder-bottom-wing-rad-z*) - ,man-int:*rotation-around-z-90-list*)) - (holder-underbody :holder-underbody ,*yellow-plastic* - ((,(+ 0.05 *holder-underbody-rad-x*) 0.4 ,*holder-underbody-rad-z*) - (0 0 0 1))) - (holder-plane-horizontal :holder-plane-horizontal ,*yellow-plastic* - ((,(+ 0.05 *holder-plane-horizontal-rad-x*) - 0.6 - ,*holder-plane-horizontal-rad-z*) - (0 0 0 1))) - (holder-window :holder-window ,*gray-plastic* - ((,*holder-window-rad-x* - ,(+ 0.75 *holder-window-rad-y*) - ,*holder-window-rad-z*) - (0 0 0 1))) - (holder-plane-vertical :holder-plane-vertical ,*yellow-plastic* - ((,*holder-plane-vertical-rad-x* - ,(- 1.0 *holder-plane-vertical-rad-y*) - ,*holder-plane-vertical-rad-z*) - (0 0 0 1))) - (holder-top-wing :holder-top-wing ,*yellow-plastic* - ((,(+ 0.15 *holder-top-wing-rad-x*) - ,(- 1.15 *holder-top-wing-rad-y*) - ,*holder-top-wing-rad-z*) - ,man-int:*rotation-around-z-90-list*)) - - ;; rear wing is already well positioned - (rear-wing :rear-wing ,*yellow-plane* - ((0.079 0.599 0.056) - ,man-int:*rotation-around-z+90-list*)) - - ;; bolts are used intermediately - (bolt-1 :bolt ,*gray-plane* - ((0.015 0.0125 ,*bolt-rad-z*) (0 0 0 1))) - (bolt-2 :bolt ,*gray-plane* - ((0.0325 0.0375 ,*bolt-rad-z*) (0 0 0 1))) - (bolt-3 :bolt ,*gray-plane* - ((0.05 0.0125 ,*bolt-rad-z*) (0 0 0 1))) - (bolt-4 :bolt ,*gray-plane* - ((0.0675 0.0375 ,*bolt-rad-z*) (0 0 0 1))) - (bolt-5 :bolt ,*gray-plane* - ((0.085 0.0125 ,*bolt-rad-z*) (0 0 0 1))) - - ;; first part of scenario on horizontal holder - (chassis :chassis ,*yellow-plane* - ((0.2 0.9 ,*chassis-rad-z*) ,man-int:*rotation-around-z-90-list*)) - (bottom-wing :bottom-wing ,*cyan-plane* - ((0.134 0.25 0.093) (0 0 0 1))) - (underbody :underbody ,*red-plane* - ((0.145 0.399 0.024) (0 0 0 1))) - (motor-grill :motor-grill ,*black-plane* - ((0.238 0.399 0.039) ,man-int:*rotation-around-y+90-list*)) - (upper-body :upper-body ,*red-plane* - ((0.119 0.1003 0.0482) (0 0 0 1))) - (top-wing :top-wing ,*cyan-plane* - ((0.18522 1.11423 0.08852) (0 0 0 1))) - (window :window ,*transparent-plane* - ((0.024 0.775 0.01962) (0 0 0 1))) - - ;; second part of scenario on vertical holder - (propeller :propeller ,*yellow-plane* - ((0.075 1.10 0) (0 0 0 1))) - (front-wheel-1 :front-wheel ,*black-plane* - ((0.15 0.775 ,*front-wheel-rad-z*) (0 0 0 1))) - (front-wheel-2 :front-wheel ,*black-plane* - ((0.215 0.775 ,*front-wheel-rad-z*) (0 0 0 1))) - (nut-1 :nut ,*gray-plane* - ((0.15 0.725 ,*nut-rad-z*) (0 0 0 1))) - (nut-2 :nut ,*gray-plane* - ((0.215 0.725 ,*nut-rad-z*) (0 0 0 1))))) - - -(defun spawn-objects-on-plate (&optional (spawning-poses *object-spawning-data*)) - (btr-utils:kill-all-objects) - (btr:detach-all-objects (btr:get-robot-object)) - ;; let ((object-types '(:breakfast-cereal :cup :bowl :spoon :milk))) - ;; spawn objects at default poses - (let ((objects (mapcar (lambda (object-name-type-pose-list) - (destructuring-bind (object-name object-type object-color - object-pose-list) - object-name-type-pose-list - (let ((object-relative-pose - (cram-tf:list->pose object-pose-list))) - (btr-utils:spawn-object - object-name - object-type - :mass 0.0 - :color object-color - :pose (cram-tf:pose->list - (cl-tf:make-pose - (cl-transforms:v+ - (cl-transforms:make-3d-vector - (- *plate-x* *plate-rad-x*) - (- *plate-y* *plate-rad-y*) - (+ *plate-z* *plate-rad-z*)) - (cl-transforms:origin - object-relative-pose)) - (cl-transforms:orientation - object-relative-pose))))))) - spawning-poses))) - objects)) - - -(defmethod exe:generic-perform :before (designator) - (format t "~%PERFORMING~%~A~%~%" designator)) - - -(defparameter *base-x* -2.4) -(defparameter *base-very-left-side-left-hand-pose* `((,*base-x* 1.8 0) (0 0 0 1))) -(defparameter *base-left-side-left-hand-pose* `((,*base-x* 1.5 0) (0 0 0 1))) -(defparameter *base-somewhat-left-side-left-hand-pose* `((,*base-x* 1.3 0) (0 0 0 1))) -(defparameter *base-middle-side-left-hand-pose* `((,*base-x* 1.1 0) (0 0 0 1))) -;; (defparameter *base-right-side-left-hand-pose* `((,*base-x* 0.9 0) (0 0 0 1))) -(defparameter *base-right-side-left-hand-pose* `((,*base-x* 0.7 0) (0 0 0 1))) -(defparameter *base-very-right-side-left-hand-pose* `((,(- *base-x* 0.2) 0.65 0) (0 0 0 1))) - -;;; ASSEMBLY STEPS: -;;; (1) put chassis on holder (bump inwards) -;;; (2) put bottom wing on chassis -;;; * maybe: dont hit the top-wing with the arm -;;; (3) put underbody on bottom wing -;;; (4) put upperbody on underbody -;;; (5) screw rear hole -;;; (6) put top wing on body -;;; (7) screw top wing -;;; (8) put window on body -;;; (9) screw window -;;; (10) put plane on vertical holder -;;; (11) put propeller on grill -;;; (12) screw propeller -;;; * put wheel on -;;; * screw nut onto wheel -;;; * put other wheel on -;;; * screw nut onto wheel -;;; * screw bottom body -(defun demo () - ;;(setf cram-robosherlock::*no-robosherlock-mode* t) - (spawn-objects-on-plate) - (initialize-attachments) - (urdf-proj:with-projected-robot - - ;; 1 - (go-connect :chassis *base-very-left-side-left-hand-pose* - :holder-plane-horizontal *base-middle-side-left-hand-pose* - :horizontal-attachment) - ;; 2 - (go-connect :bottom-wing *base-very-right-side-left-hand-pose* - :chassis *base-left-side-left-hand-pose* - :wing-attachment) - - ;; 3 - (go-connect :underbody *base-middle-side-left-hand-pose* - :bottom-wing *base-middle-side-left-hand-pose* - :body-attachment) - - ;; we put the underbody on the bottom-wing but by doing that - ;; we also put it on the rear-wing. - ;; as there is no explicit placing action, the two will not be - ;; attached automatically. - ;; so we have to attach them manually unfortunately. - ;; this is required for later moving the whole plane onto another holder - (btr:attach-object 'underbody 'rear-wing) - - ;; 4 - (go-connect :upper-body *base-right-side-left-hand-pose* - :underbody *base-left-side-left-hand-pose* - :body-on-body) - ;; 5 - (go-connect :bolt *base-right-side-left-hand-pose* - :upper-body *base-left-side-left-hand-pose* - :rear-thread) - ;; 6 - (go-connect :top-wing *base-left-side-left-hand-pose* - :upper-body *base-left-side-left-hand-pose* - :wing-attachment) - ;; 7 - (go-connect :bolt *base-right-side-left-hand-pose* - :top-wing *base-left-side-left-hand-pose* - :middle-thread) - ;; 8 - (go-connect :window *base-somewhat-left-side-left-hand-pose* - :top-wing *base-left-side-left-hand-pose* - :window-attachment) - ;; 9 - (go-connect :bolt *base-right-side-left-hand-pose* - :window *base-left-side-left-hand-pose* - :window-thread) - - ;; 10 - (go-connect :top-wing *base-somewhat-left-side-left-hand-pose* - :holder-plane-vertical *base-left-side-left-hand-pose* - ;; or `((,(- *base-x* 0.00) 1.45 0) (0 0 0 1)) - :vertical-attachment) - - ;; 11 - (go-connect :propeller `((,(- *base-x* 0.15) 2 0) (0 0 0 1)) - :motor-grill *base-left-side-left-hand-pose* - ;; or `((,(- *base-x* 0.15) 1.8 0) (0 0 0 1)) - :propeller-attachment) - - ;; 12 - (go-connect :bolt *base-right-side-left-hand-pose* - :propeller *base-left-side-left-hand-pose* - ;; or `((,*base-x* 1.85 0) (0 0 0 1)) - :propeller-thread) - - ;;(go-connect :top-wing *base-left-side-left-hand-pose* - ;; :holder-plane-horizontal *base-middle-side-left-hand-pose* - ;; :horizontal-attachment) - - (exe:perform - (desig:an action - (type positioning-arm) - (left-configuration park) - (right-configuration park))))) - -(defun initialize-attachments () - (btr:attach-object 'motor-grill 'underbody)) - -(defun go-perceive (?object-type ?nav-goal) - ;; park arms - (exe:perform - (desig:an action - (type positioning-arm) - (left-configuration park) - (right-configuration park))) - ;; drive to right location - (let ((?pose (cl-transforms-stamped:pose->pose-stamped - cram-tf:*fixed-frame* - 0.0 - (btr:ensure-pose ?nav-goal)))) - (exe:perform - (desig:an action - (type going) - (target (desig:a location - (pose ?pose)))))) - ;; look down - (exe:perform - (desig:an action - (type looking) - (direction down-left))) - ;; perceive object - (let ((?object - (exe:perform - (desig:an action - (type detecting) - (object (desig:an object (type ?object-type))))))) - ;; look away - (exe:perform - (desig:an action - (type looking) - (direction away))) - ?object)) - -(defun go-pick (?object-type ?nav-goal) - ;; go and perceive object - (let ((?object - (go-perceive ?object-type ?nav-goal))) - ;; pick object - (exe:perform - (desig:an action - (type picking-up) - (arm left) - (object ?object))) - ?object)) - -(defun go-pick-place (?object-type ?nav-goal) - ;; go and pick up object - (let ((?object - (go-pick ?object-type ?nav-goal))) - ;; put the cookie down - (exe:perform - (desig:an action - (type placing) - (object ?object))))) - -(defun go-connect (?object-type ?nav-goal ?other-object-type ?other-nav-goal ?attachment-type) - ;; go and pick up object - (let ((?object - (go-pick ?object-type ?nav-goal))) - ;; go and perceive other object - (let ((?other-object - (go-perceive ?other-object-type ?other-nav-goal))) - (exe:perform - (desig:an action - (type placing) - (arm left) - (object ?object) - ;; this location designator is resolved in - ;; cram_boxy_plans/src/action-designators.lisp - (target (desig:a location - (on ?other-object) - (for ?object) - (attachment ?attachment-type))))) - (values ?object ?other-object)))) - -#+examples -( - (boxy-proj:with-projected-robot - (cram-executive:perform - (desig:an action - (type looking) - (direction down)))) - - (boxy-proj:with-projected-robot - (cram-executive:perform - (desig:an action - (type detecting) - (object (desig:an object (type chassis)))))) - - (boxy-proj:with-simulated-robot - (exe:perform - (desig:an action - (type opening-gripper) - (gripper left)))) - - (boxy-proj:with-projected-robot - (cram-executive:perform - (desig:an action - (type placing) - (arm left)))) - ) - - - - - - - -#+everything-below-is-pr2-s-stuff-so-need-new-things-for-boxy -( -(defun demo-hard-coded () - (spawn-objects-on-plate) - - (boxy-proj:with-simulated-robot - - (dolist (object-type '(:breakfast-cereal :cup :bowl :spoon :milk)) - - (let ((placing-target - (cl-transforms-stamped:pose->pose-stamped - "map" 0.0 - (cram-bullet-reasoning:ensure-pose - (cdr (assoc object-type *object-placing-poses*))))) - (arm-to-use - (cdr (assoc object-type *object-grasping-arms*)))) - - (pick-object object-type arm-to-use) - (place-object placing-target arm-to-use))))) -) diff --git a/cram_boxy/cram_boxy_assembly_demo/src/setup.lisp b/cram_boxy/cram_boxy_assembly_demo/src/setup.lisp deleted file mode 100644 index 3a217f6d00..0000000000 --- a/cram_boxy/cram_boxy_assembly_demo/src/setup.lisp +++ /dev/null @@ -1,117 +0,0 @@ -;;; -;;; Copyright (c) 2018, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software -;;; without specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :demo) - -;; roslaunch cram_boxy_assembly_demo sandbox.launch - -(defvar *kitchen-urdf* nil) -(defparameter *robot-parameter* "robot_description") -(defparameter *kitchen-parameter* "kitchen_description") - -(defun setup-bullet-world () - (setf btr:*current-bullet-world* (make-instance 'btr:bt-reasoning-world)) - - (let ((robot (or rob-int:*robot-urdf* - (setf rob-int:*robot-urdf* - (cl-urdf:parse-urdf - (roslisp:get-param *robot-parameter*))))) - (kitchen (or *kitchen-urdf* - (let ((kitchen-urdf-string - (roslisp:get-param *kitchen-parameter* nil))) - (when kitchen-urdf-string - (setf *kitchen-urdf* (cl-urdf:parse-urdf - kitchen-urdf-string))))))) - ;; set Boxy URDF root link to be base_footprint not odom, - ;; as with odom lots of problems concerning object-pose in bullet happen - (setf (slot-value rob-int:*robot-urdf* 'cl-urdf:root-link) - (or (gethash cram-tf:*robot-base-frame* - (cl-urdf:links rob-int:*robot-urdf*)) - (error "[setup-bullet-world] cram-tf:*robot-base-frame* was undefined or smt."))) - ;; get rid of Boxy's camera obstacle thing, it's bad for visibility reasoning - ;; it's an annoying hack anyway... - ;; (setf (slot-value - ;; (gethash "neck_obstacle" - ;; (cl-urdf:links rob-int:*robot-urdf*)) - ;; 'cl-urdf:collision) - ;; NIL) - ;; (setf (slot-value - ;; (gethash "neck_look_target" - ;; (cl-urdf:links rob-int:*robot-urdf*)) - ;; 'cl-urdf:collision) - ;; NIL) - - (assert - (cut:force-ll - (prolog `(and - (btr:bullet-world ?w) - (btr:debug-window ?w) - (btr:assert ?w (btr:object :static-plane :floor ((0 0 0) (0 0 0 1)) - :normal (0 0 1) :constant 0)) - (btr:assert ?w (btr:object :urdf :kitchen ((0 0 0) (0 0 0 1)) - :collision-group :static-filter - :collision-mask (:default-filter - :character-filter) - :urdf ,kitchen - :compound T)) - (-> (cram-robot-interfaces:robot ?robot) - (btr:assert ?w (btr:object :urdf ?robot ((0 0 0) (0 0 0 1)) :urdf ,robot)) - (warn "ROBOT was not defined. Have you loaded a robot package?"))))))) - - (let ((robot-object (btr:get-robot-object))) - (if robot-object - (btr:set-robot-state-from-tf cram-tf:*transformer* robot-object) - (warn "ROBOT was not defined. Have you loaded a robot package?")))) - -(defun init-projection () - (def-fact-group costmap-metadata (costmap:costmap-size - costmap:costmap-origin - costmap:costmap-resolution - costmap:orientation-samples - costmap:orientation-sample-step) - (<- (costmap:costmap-size 12 12)) - (<- (costmap:costmap-origin -6 -6)) - (<- (costmap:costmap-resolution 0.04)) - (<- (costmap:orientation-samples 2)) - (<- (costmap:orientation-sample-step 0.1))) - - ;; (setf cram-tf:*transformer* (make-instance 'cl-tf2:buffer-client)) - - (setup-bullet-world) - - (setf cram-tf:*tf-default-timeout* 2.0) - - (setf prolog:*break-on-lisp-errors* t) - - (cram-bullet-reasoning:clear-costmap-vis-object) - - (btr:add-objects-to-mesh-list "assembly_models" :directory "fixtures" :extension "stl") - (btr:add-objects-to-mesh-list "assembly_models" :directory "battat/convention" :extension "stl")) - -(roslisp-utilities:register-ros-init-function init-projection) diff --git a/cram_boxy/cram_boxy_description/src/arms.lisp b/cram_boxy/cram_boxy_description/src/arms.lisp index 9d79e9ebf9..e5ff998509 100644 --- a/cram_boxy/cram_boxy_description/src/arms.lisp +++ b/cram_boxy/cram_boxy_description/src/arms.lisp @@ -37,111 +37,135 @@ (defparameter *standard-to-boxy-gripper-transform* (cl-transforms-stamped:make-identity-transform)) -(defparameter *left-parking-joint-states* - '(("left_arm_0_joint" -1.858d0) - ("left_arm_1_joint" 0.70571d0) - ("left_arm_2_joint" 0.9614d0) - ("left_arm_3_joint" -0.602d0) - ("left_arm_4_joint" -2.5922d0) - ("left_arm_5_joint" -1.94065d0) - ("left_arm_6_joint" -1.28735d0))) - -(defparameter *right-parking-joint-states* - '(("right_arm_0_joint" 0.0) - ("right_arm_1_joint" 0.0) - ("right_arm_2_joint" 0.0) - ("right_arm_3_joint" 0.0) - ("right_arm_4_joint" 0.0) - ("right_arm_5_joint" 0.0) - ("right_arm_6_joint" 0.0))) - -(defparameter *left-nicer-configuration* - '(-1.2274070978164673 - 0.8496202230453491 - -0.10349386930465698 - -1.0852965116500854 - -0.4587952196598053 - 1.259474515914917 - -0.06962397694587708)) - -(def-fact-group boxy-arm-facts (end-effector-link - robot-tool-frame +(def-fact-group boxy-arm-facts (arm arm-joints arm-links - gripper-joint gripper-link - gripper-meter-to-joint-multiplier - standard-to-particular-gripper-transform - ;; robot-arms-parking-joint-states - ;; robot-arms-carrying-joint-states - robot-joint-states - tcp-in-ee-pose) - - (<- (end-effector-link boxy :left "left_arm_7_link")) - (<- (end-effector-link boxy :right "right_arm_7_link")) - - (<- (robot-tool-frame boxy :left "left_gripper_tool_frame")) - (<- (robot-tool-frame boxy :right "right_gripper_tool_frame")) - - (<- (arm-joints boxy :left ("left_arm_0_joint" - "left_arm_1_joint" - "left_arm_2_joint" - "left_arm_3_joint" - "left_arm_4_joint" - "left_arm_5_joint" - "left_arm_6_joint"))) - (<- (arm-joints boxy :right ("right_arm_0_joint" - "right_arm_1_joint" - "right_arm_2_joint" - "right_arm_3_joint" - "right_arm_4_joint" - "right_arm_5_joint" - "right_arm_6_joint"))) - - (<- (arm-links boxy :left ("left_arm_1_link" - "left_arm_2_link" - "left_arm_3_link" - "left_arm_4_link" - "left_arm_5_link" - "left_arm_6_link" - "left_arm_7_link"))) - (<- (arm-links boxy :right ("right_arm_1_link" - "right_arm_2_link" - "right_arm_3_link" - "right_arm_4_link" - "right_arm_5_link" - "right_arm_6_link" - "right_arm_7_link"))) - - (<- (gripper-joint boxy :left "left_gripper_joint")) - (<- (gripper-joint boxy :right "right_gripper_joint")) - - (<- (gripper-link boxy :left ?link) + hand-links hand-link hand-finger-link + gripper-joint gripper-meter-to-joint-multiplier + standard<-particular-gripper-transform + end-effector-link robot-tool-frame + tcp-in-ee-pose + robot-joint-states) + + (<- (arm :boxy-description :left)) + (<- (arm :boxy-description :right)) + + (<- (arm-joints :boxy-description :left ("left_arm_0_joint" + "left_arm_1_joint" + "left_arm_2_joint" + "left_arm_3_joint" + "left_arm_4_joint" + "left_arm_5_joint" + "left_arm_6_joint"))) + (<- (arm-joints :boxy-description :right ("right_arm_0_joint" + "right_arm_1_joint" + "right_arm_2_joint" + "right_arm_3_joint" + "right_arm_4_joint" + "right_arm_5_joint" + "right_arm_6_joint"))) + + (<- (arm-links :boxy-description :left ("left_arm_1_link" + "left_arm_2_link" + "left_arm_3_link" + "left_arm_4_link" + "left_arm_5_link" + "left_arm_6_link" + "left_arm_7_link"))) + (<- (arm-links :boxy-description :right ("right_arm_1_link" + "right_arm_2_link" + "right_arm_3_link" + "right_arm_4_link" + "right_arm_5_link" + "right_arm_6_link" + "right_arm_7_link"))) + + (<- (hand-links :boxy-description :left (;; "left_gripper_base_link" + "left_gripper_finger_left_link" + "left_gripper_finger_right_link" + "left_gripper_gripper_left_link" + "left_gripper_gripper_right_link" + "left_gripper_tool_frame"))) + (<- (hand-links :boxy-description :right (;; "right_gripper_base_link" + "right_gripper_finger_left_link" + "right_gripper_finger_right_link" + "right_gripper_gripper_left_link" + "right_gripper_gripper_right_link" + "right_gripper_tool_frame"))) + + (<- (hand-link :boxy-description :left ?link) (bound ?link) (lisp-fun search "left_gripper" ?link ?pos) (lisp-pred identity ?pos)) - (<- (gripper-link boxy :right ?link) + (<- (hand-link :boxy-description :right ?link) (bound ?link) (lisp-fun search "right_gripper" ?link ?pos) (lisp-pred identity ?pos)) - (<- (gripper-meter-to-joint-multiplier boxy 1.0)) - - (<- (standard-to-particular-gripper-transform boxy ?transform) - (symbol-value *standard-to-boxy-gripper-transform* ?transform)) - - (<- (robot-joint-states boxy :arm :left :carry ?joint-states) - (symbol-value *left-parking-joint-states* ?joint-states)) - - (<- (robot-joint-states boxy :arm :right :carry ?joint-states) - (symbol-value *right-parking-joint-states* ?joint-states)) + (<- (hand-finger-link :boxy-description ?arm ?link) + (bound ?link) + (hand-link :boxy-description ?arm ?link) + (lisp-fun search "finger" ?link ?pos) + (lisp-pred identity ?pos)) - (<- (robot-joint-states boxy :arm :left :park ?joint-states) - (symbol-value *left-parking-joint-states* ?joint-states)) + (<- (gripper-joint :boxy-description :left "left_gripper_joint")) + (<- (gripper-joint :boxy-description :right "right_gripper_joint")) - (<- (robot-joint-states boxy :arm :right :park ?joint-states) - (symbol-value *right-parking-joint-states* ?joint-states)) + (<- (gripper-meter-to-joint-multiplier :boxy-description 1.0)) - (<- (robot-joint-states boxy :arm :left :flip ?joint-states) - (symbol-value *left-nicer-configuration* ?joint-states)) + (<- (standard<-particular-gripper-transform :boxy-description ?transform) + (symbol-value *standard-to-boxy-gripper-transform* ?transform)) - (<- (tcp-in-ee-pose boxy ?pose) - (symbol-value *tcp-in-ee-pose* ?pose))) + (<- (end-effector-link :boxy-description :left "left_arm_7_link")) + (<- (end-effector-link :boxy-description :right "right_arm_7_link")) + + (<- (robot-tool-frame :boxy-description :left "left_gripper_tool_frame")) + (<- (robot-tool-frame :boxy-description :right "right_gripper_tool_frame")) + + (<- (tcp-in-ee-pose :boxy-description ?pose) + (symbol-value *tcp-in-ee-pose* ?pose)) + + (<- (robot-joint-states :boxy-description :arm :left :carry + (("left_arm_0_joint" -1.858d0) + ("left_arm_1_joint" 0.70571d0) + ("left_arm_2_joint" 0.9614d0) + ("left_arm_3_joint" -0.602d0) + ("left_arm_4_joint" -2.5922d0) + ("left_arm_5_joint" -1.94065d0) + ("left_arm_6_joint" -1.28735d0)))) + (<- (robot-joint-states :boxy-description :arm :left :park ?joint-states) + (robot-joint-states :boxy-description :arm :left :carry ?joint-states)) + (<- (robot-joint-states :boxy-description :arm :left :carry-top ?joint-states) + (robot-joint-states :boxy-description :arm :left :carry ?joint-states)) + (<- (robot-joint-states :boxy-description :arm :left :carry-side-gripper-vertical + ?joint-states) + (robot-joint-states :boxy-description :arm :left :carry ?joint-states)) + (<- (robot-joint-states :boxy-description :arm :left :carry-top-basket + ?joint-states) + (robot-joint-states :boxy-description :arm :left :carry ?joint-states)) + (<- (robot-joint-states :boxy-description :arm :left :hand-over ?joint-states) + (robot-joint-states :boxy-description :arm :left :carry ?joint-states)) + + (<- (robot-joint-states :boxy-description :arm :right :carry + (("right_arm_0_joint" 1.858d0) + ("right_arm_1_joint" -0.70571d0) + ("right_arm_2_joint" -0.9614d0) + ("right_arm_3_joint" 0.602d0) + ("right_arm_4_joint" 2.5922d0) + ("right_arm_5_joint" 1.94065d0) + ("right_arm_6_joint" 1.28735d0)))) + (<- (robot-joint-states :boxy-description :arm :right :park ?joint-states) + (robot-joint-states :boxy-description :arm :right :carry ?joint-states)) + (<- (robot-joint-states :boxy-description :arm :right :carry-top ?joint-states) + (robot-joint-states :boxy-description :arm :right :carry ?joint-states)) + (<- (robot-joint-states :boxy-description :arm :right :carry-side-gripper-vertical + ?joint-states) + (robot-joint-states :boxy-description :arm :right :carry ?joint-states)) + + (<- (robot-joint-states :boxy-description :arm :left :flip + (("left_arm_0_joint" -1.2274070978164673) + ("left_arm_1_joint" 0.8496202230453491) + ("left_arm_2_joint" -0.10349386930465698) + ("left_arm_3_joint" -1.0852965116500854) + ("left_arm_4_joint" -0.4587952196598053) + ("left_arm_5_joint" 1.259474515914917) + ("left_arm_6_joint" -0.06962397694587708))))) diff --git a/cram_boxy/cram_boxy_description/src/general-knowledge.lisp b/cram_boxy/cram_boxy_description/src/general-knowledge.lisp index 4fcdde72e6..ffd6fb3577 100644 --- a/cram_boxy/cram_boxy_description/src/general-knowledge.lisp +++ b/cram_boxy/cram_boxy_description/src/general-knowledge.lisp @@ -29,30 +29,26 @@ (in-package :boxy-descr) -(def-fact-group boxy-metadata (robot - robot-odom-frame - robot-base-frame robot-torso-link-joint - arm - camera-frame) - (<- (robot boxy)) +(def-fact-group boxy-metadata (robot-odom-frame + robot-base-frame + robot-torso-link-joint) + (<- (robot-odom-frame :boxy-description "odom")) + (<- (robot-base-frame :boxy-description "base_footprint")) + (<- (robot-torso-link-joint :boxy-description + "triangle_base_link" "triangle_base_joint"))) - (<- (robot-odom-frame boxy "odom")) - - (<- (robot-base-frame boxy "base_footprint")) - (<- (robot-torso-link-joint boxy "triangle_base_link" "triangle_base_joint")) - - (<- (arm boxy :left)) - (<- (arm boxy :right)) - - (<- (camera-frame boxy "head_mount_kinect2_rgb_optical_frame"))) (def-fact-group location-costmap-metadata (costmap:costmap-padding costmap:costmap-manipulation-padding costmap:costmap-in-reach-distance costmap:costmap-reach-minimal-distance + costmap:orientation-samples + costmap:orientation-sample-step costmap:visibility-costmap-size) - (<- (costmap:costmap-padding 0.5)) - (<- (costmap:costmap-manipulation-padding 0.5)) - (<- (costmap:costmap-in-reach-distance 1.2)) - (<- (costmap:costmap-reach-minimal-distance 0.2)) - (<- (costmap:visibility-costmap-size 2))) + (<- (costmap:costmap-padding :boxy-description 0.5)) + (<- (costmap:costmap-manipulation-padding :boxy-description 0.2)) + (<- (costmap:costmap-in-reach-distance :boxy-description 1.7)) + (<- (costmap:costmap-reach-minimal-distance :boxy-description 0.65)) + (<- (costmap:orientation-samples :boxy-description 1)) + (<- (costmap:orientation-sample-step :boxy-description 0.3)) + (<- (costmap:visibility-costmap-size :boxy-description 2))) diff --git a/cram_boxy/cram_boxy_description/src/neck.lisp b/cram_boxy/cram_boxy_description/src/neck.lisp index 74146c199c..9f298c879e 100644 --- a/cram_boxy/cram_boxy_description/src/neck.lisp +++ b/cram_boxy/cram_boxy_description/src/neck.lisp @@ -29,45 +29,49 @@ (in-package :boxy-descr) -(defparameter *neck-good-looking-down-state* - '(("neck_shoulder_pan_joint" -1.176d0) - ("neck_shoulder_lift_joint" -3.1252d0) - ("neck_elbow_joint" -0.8397d0) - ("neck_wrist_1_joint" 0.83967d0) - ("neck_wrist_2_joint" 1.1347d0) - ("neck_wrist_3_joint" -0.0266d0))) - -(defparameter *neck-good-looking-left-state* - '(("neck_shoulder_pan_joint" -0.776d0) - ("neck_shoulder_lift_joint" -3.1252d0) - ("neck_elbow_joint" -0.8397d0) - ("neck_wrist_1_joint" 0.83967d0) - ("neck_wrist_2_joint" 1.1347d0) - ("neck_wrist_3_joint" -0.0266d0))) - -(defparameter *neck-parking-joint-states* - '(("neck_shoulder_pan_joint" -1.3155d0) - ("neck_shoulder_lift_joint" -1.181355d0) - ("neck_elbow_joint" -1.9562d0) - ("neck_wrist_1_joint" 0.142417d0) - ("neck_wrist_2_joint" 1.13492d0) - ("neck_wrist_3_joint" 0.143467d0))) - (defparameter *neck-ee-p-camera* (cl-transforms:make-pose - (cl-transforms:make-3d-vector 0.0986269622673131 0.12544403167962803 -0.03128420761449102) - (cl-transforms:make-quaternion 0.9999584853467481 -0.0018697606579721564 - 0.003765215266400738 0.008087476255186993))) + (cl-transforms:make-3d-vector + 0.09862691563322334d0 0.03128412196559971d0 0.04354402436024185d0) + (cl-transforms:make-quaternion + -0.7013586107397135d0 -0.003984622804686699d0 0.0013402975558304106d0 + 0.7127960729748405d0))) + -(def-fact-group boxy-neck-facts (robot-neck-links +(def-fact-group boxy-neck-facts (camera-frame + camera-in-neck-ee-pose + neck-camera-z-offset + neck-camera-pose-unit-vector-multiplier + neck-camera-resampling-step + neck-camera-x-axis-limit neck-camera-y-axis-limit + neck-camera-z-axis-limit + camera-horizontal-angle camera-vertical-angle + camera-minimal-height camera-maximal-height + robot-neck-links robot-neck-joints robot-neck-base-link - ;; robot-neck-parking-joint-states - ;; robot-neck-looking-joint-states - robot-joint-states - camera-in-neck-ee-pose) + robot-joint-states) + + (<- (camera-frame :boxy-description "head_mount_kinect2_rgb_optical_frame")) + + (<- (camera-in-neck-ee-pose :boxy-description ?pose) + (symbol-value *neck-ee-p-camera* ?pose)) + + (<- (neck-camera-z-offset :boxy-description 0.1)) + (<- (neck-camera-pose-unit-vector-multiplier :boxy-description 0.4)) + (<- (neck-camera-resampling-step :boxy-description 0.1)) + (<- (neck-camera-x-axis-limit :boxy-description 0.2)) + (<- (neck-camera-y-axis-limit :boxy-description 0.2)) + (<- (neck-camera-z-axis-limit :boxy-description 0.2)) - (<- (robot-neck-links boxy + ;; These are values taken from the Kinect's wikipedia page for the 360 variant + (<- (camera-horizontal-angle :boxy-description 0.99483)) ; ca 57 degrees + (<- (camera-vertical-angle :boxy-description 0.75049)) ; ca 43 degrees + + ;; (<- (camera-minimal-height :boxy-description 1.0)) + ;; (<- (camera-maximal-height :boxy-description 2.5)) + + (<- (robot-neck-links :boxy-description "neck_shoulder_link" "neck_upper_arm_link" "neck_forearm_link" @@ -75,7 +79,7 @@ "neck_wrist_2_link" "neck_wrist_3_link")) - (<- (robot-neck-joints boxy + (<- (robot-neck-joints :boxy-description "neck_shoulder_pan_joint" "neck_shoulder_lift_joint" "neck_elbow_joint" @@ -83,19 +87,30 @@ "neck_wrist_2_joint" "neck_wrist_3_joint")) - (<- (robot-neck-base-link boxy "neck_base_link")) - - (<- (robot-joint-states boxy :neck ?there-is-only-one-neck :away ?joint-states) - (symbol-value *neck-parking-joint-states* ?joint-states)) - - (<- (robot-joint-states boxy :neck ?there-is-only-one-neck :forward ?joint-states) - (symbol-value *neck-parking-joint-states* ?joint-states)) - - (<- (robot-joint-states boxy :neck ?there-is-only-one-neck :down ?joint-states) - (symbol-value *neck-good-looking-down-state* ?joint-states)) - - (<- (robot-joint-states boxy :neck ?there-is-only-one-neck :down-left ?joint-states) - (symbol-value *neck-good-looking-left-state* ?joint-states)) + (<- (robot-neck-base-link :boxy-description "neck_base_link")) - (<- (camera-in-neck-ee-pose boxy ?pose) - (symbol-value *neck-ee-p-camera* ?pose))) + (<- (robot-joint-states :boxy-description :neck ?there-is-only-one-neck :away + (("neck_shoulder_pan_joint" -1.3155d0) + ("neck_shoulder_lift_joint" -1.181355d0) + ("neck_elbow_joint" -1.9562d0) + ("neck_wrist_1_joint" 0.142417d0) + ("neck_wrist_2_joint" 1.13492d0) + ("neck_wrist_3_joint" 0.143467d0)))) + (<- (robot-joint-states :boxy-description :neck ?there-is-only-one-neck :forward + ?joint-states) + (robot-joint-states :boxy-description :neck ?there-is-only-one-neck :away + ?joint-states)) + (<- (robot-joint-states :boxy-description :neck ?there-is-only-one-neck :down + (("neck_shoulder_pan_joint" -1.176d0) + ("neck_shoulder_lift_joint" -3.1252d0) + ("neck_elbow_joint" -0.8397d0) + ("neck_wrist_1_joint" 0.83967d0) + ("neck_wrist_2_joint" 1.1347d0) + ("neck_wrist_3_joint" -0.0266d0)))) + (<- (robot-joint-states :boxy-description :neck ?only-one-neck :down-left + (("neck_shoulder_pan_joint" -0.776d0) + ("neck_shoulder_lift_joint" -3.1252d0) + ("neck_elbow_joint" -0.8397d0) + ("neck_wrist_1_joint" 0.83967d0) + ("neck_wrist_2_joint" 1.1347d0) + ("neck_wrist_3_joint" -0.0266d0))))) diff --git a/cram_boxy/cram_boxy_description/src/package.lisp b/cram_boxy/cram_boxy_description/src/package.lisp index 13a1a0cb78..d1c0ee0791 100644 --- a/cram_boxy/cram_boxy_description/src/package.lisp +++ b/cram_boxy/cram_boxy_description/src/package.lisp @@ -31,5 +31,4 @@ (defpackage cram-boxy-description (:nicknames #:boxy-descr) - (:use #:common-lisp #:cram-prolog #:cram-robot-interfaces) - (:export #:boxy)) + (:use #:common-lisp #:cram-prolog #:cram-robot-interfaces)) diff --git a/cram_boxy/cram_boxy_designators/src/motions.lisp b/cram_boxy/cram_boxy_designators/src/motions.lisp deleted file mode 100644 index e00baa1324..0000000000 --- a/cram_boxy/cram_boxy_designators/src/motions.lisp +++ /dev/null @@ -1,58 +0,0 @@ -;;; -;;; Copyright (c) 2017, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of Willow Garage, Inc. nor the names of its -;;; contributors may be used to endorse or promote products derived from -;;; this software without specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :boxy-desig) - -(defun calculate-pose-from-direction (distance) - (let* ((left-pose - (cl-transforms-stamped:make-pose-stamped - cram-tf:*robot-left-tool-frame* - 0.0 - (cl-transforms:make-3d-vector 0.0 0.0 distance) - (cl-transforms:make-identity-rotation)))) - left-pose)) - -(def-fact-group boxy-motion-designators (desig:motion-grounding) - - (<- (desig:motion-grounding ?designator (move-tcp-wiggle ?arm ?pose)) - (property ?designator (:type :wiggling-tcp)) - (property ?designator (:arm ?arm)) - (property ?designator (:target ?location-designator)) - (desig:designator-groundings ?location-designator ?poses) - (member ?pose ?poses)) - - (<- (desig:motion-grounding ?designator (move-tcp-wiggle :left ?pose)) - (property ?designator (:type :wiggling-tcp)) - ;; (property ?designator (:arm ?arm)) - ;; (property ?designator (:direction ?direction-keyword)) - ;; (property ?designator (:frame ?reference-frame)) - (property ?designator (:arm :left)) - (property ?designator (:direction :forward)) - (property ?designator (:distance ?distance)) - (lisp-fun calculate-pose-from-direction ?distance ;; ?arm ?direction-keyword ?reference-frame - ?pose))) diff --git a/cram_boxy/cram_boxy_low_level/package.xml b/cram_boxy/cram_boxy_low_level/package.xml index 3fc8a98b14..1710e2d04f 100644 --- a/cram_boxy/cram_boxy_low_level/package.xml +++ b/cram_boxy/cram_boxy_low_level/package.xml @@ -12,7 +12,7 @@ roslisp roslisp_utilities - actionlib + actionlib_lisp cram_simple_actionlib_client cram_language cram_math diff --git a/cram_boxy/cram_boxy_low_level/src/package.lisp b/cram_boxy/cram_boxy_low_level/src/package.lisp index 4ff9d30338..919abdc1c2 100644 --- a/cram_boxy/cram_boxy_low_level/src/package.lisp +++ b/cram_boxy/cram_boxy_low_level/src/package.lisp @@ -33,16 +33,6 @@ (:nicknames #:boxy-ll) (:use #:common-lisp) (:export - ;; simple-actionlib-client - #:make-simple-action-client - #:call-simple-action-client - ;; joint-states - #:joint-state - #:joint-states - #:joint-positions - #:normalize-joint-angles - ;; nav-pcontroller - #:move-base-nav-pcontroller ;; neck #:move-neck-joints ;; grippers diff --git a/cram_boxy/cram_boxy_plans/src/action-designators.lisp b/cram_boxy/cram_boxy_plans/src/action-designators.lisp deleted file mode 100644 index 37a184e3ab..0000000000 --- a/cram_boxy/cram_boxy_plans/src/action-designators.lisp +++ /dev/null @@ -1,114 +0,0 @@ -;;; -;;; Copyright (c) 2016, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Institute for Artificial Intelligence/ -;;; Universitaet Bremen nor the names of its contributors may be used to -;;; endorse or promote products derived from this software without -;;; specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :boxy-plans) - -;; (defun cram-manipulation-interfaces:get-object-transform (object-designator) -;; (let* ((object-type (desig:desig-prop-value object-designator :type)) -;; (object-frame (concatenate 'string -;; (remove #\- (string-capitalize (symbol-name object-type))) -;; "1"))) -;; (cl-transforms-stamped:lookup-transform -;; cram-tf:*transformer* -;; cram-tf:*robot-base-frame* -;; object-frame -;; :time 0.0 -;; :timeout cram-tf:*tf-default-timeout*))) - - - -;; TODO: spatial-relations-cm defines pose validators for FOR-ON relations. -;; These validators reject solutions from the result below. -;; SOLUTION: either create pose validators specific for costmaps, -;; OR, which is better, make sure costmap validators know they are validating results -;; from the costmap. But how to do this?? -(def-fact-group location-designators (desig:location-grounding) - (<- (desig:location-grounding ?location-designator ?pose-stamped) - (desig:current-designator ?location-designator ?current-location-designator) - (desig:desig-prop ?current-location-designator (:for ?object-designator)) - (desig:desig-prop ?current-location-designator (:on ?other-object-designator)) - (desig:desig-prop ?current-location-designator (:attachment ?attachment-type)) - (desig:current-designator ?object-designator ?current-object-designator) - (spec:property ?current-object-designator (:type ?object-type)) - (spec:property ?current-object-designator (:name ?object-name)) - (desig:current-designator ?other-object-designator ?current-other-object-designator) - (spec:property ?current-other-object-designator (:type ?other-object-type)) - (spec:property ?current-other-object-designator (:name ?other-object-name)) - (lisp-fun man-int:get-object-transform ?current-other-object-designator - ?other-object-transform) - (lisp-fun man-int:get-object-placement-transform - ?object-name ?object-type - ?other-object-name ?other-object-type ?other-object-transform - ?attachment-type - ?attachment-transform) - (lisp-fun cram-tf:strip-transform-stamped ?attachment-transform ?pose-stamped))) - - - -(def-fact-group boxy-designators (desig:action-grounding) - - ;; (<- (desig:action-grounding ?action-designator (wiggle ?left-poses ?right-poses)) - ;; (property ?action-designator (:type :wiggling)) - ;; (once (or (property ?action-designator (:left-poses ?left-poses)) - ;; (equal ?left-poses nil))) - ;; (once (or (property ?action-designator (:right-poses ?right-poses)) - ;; (equal ?right-poses nil)))) - - (<- (desig:action-grounding ?action-designator (cram-inspect ?augmented-designator)) - (property ?action-designator (:type :inspecting)) - (property ?action-designator (:object ?object-designator)) - (property ?action-designator (:for ?for-value)) - (-> (lisp-type ?for-value desig:object-designator) - (equal ?description-to-add (:for (:object))) - (equal ?description-to-add (:for (?for-value)))) - (desig:desig-description ?object-designator ?properties) - (equal ?augmented-description (?description-to-add . ?properties)) - (desig:designator :object ?augmented-description ?augmented-designator) - (-> (lisp-type ?for-value desig:object-designator) - (and (desig:current-designator ?for-value ?for-object-designator) - ;; (property ?for-object-designator (:type ?for-object-type)) - (prolog:slot-value ?for-object-designator desig:quantifier ?for-quantifier) - (prolog:slot-value ?augmented-designator desig:quantifier ?for-quantifier)) - (true))) - - ;; (<- (desig:action-grounding ?action-designator (perceive :inspecting ?object-designator)) - ;; (property ?action-designator (:type :inspecting)) - ;; (property ?action-designator (:object ?object-designator))) - - (<- (desig:action-grounding ?action-designator (look ?left-goal-pose ?right-goal-pose)) - (property ?action-designator (:type :looking)) - (property ?action-designator (:camera :wrist)) - (property ?action-designator (:object ?object-designator)) - (desig:current-designator ?object-designator ?current-object-designator) - (lisp-fun cram-manipulation-interfaces:get-object-transform - ?current-object-designator ?object-transform) - ;; infer missing information - (lisp-fun man-int:get-object-look-from-pose ?object-transform ?left-goal-pose) - ;; the only wrist camera is on left arm - (equal ?right-goal-pose NIL))) diff --git a/cram_boxy/cram_boxy_plans/src/action-plans.lisp b/cram_boxy/cram_boxy_plans/src/action-plans.lisp deleted file mode 100644 index 07999cc72e..0000000000 --- a/cram_boxy/cram_boxy_plans/src/action-plans.lisp +++ /dev/null @@ -1,78 +0,0 @@ -;;; -;;; Copyright (c) 2016, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Institute for Artificial Intelligence/ -;;; Universitaet Bremen nor the names of its contributors may be used to -;;; endorse or promote products derived from this software without -;;; specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :boxy-plans) - -;; (cpl:def-cram-function wiggle (left-poses right-poses) -;; (let (?arm ?target-pose) -;; (if (car left-poses) -;; (setf ?arm :left -;; ?target-pose (car left-poses)) -;; (if (car right-poses) -;; (setf ?arm :right -;; ?target-pose (car right-poses)) -;; (error "pushing action needs a goal for at least one arm."))) - -;; (cpl:with-failure-handling -;; ((common-fail:low-level-failure (e) ; ignore failures -;; (roslisp:ros-warn (boxy-plans wiggle) "~a" e) -;; (return))) - -;; (exe:perform -;; (desig:a motion -;; (type wiggling-tcp) -;; (arm ?arm) -;; (pose ?target-pose)))))) - - -(cpl:def-cram-function cram-inspect (?object-designator) - (cpl:with-retry-counters ((perceive-retries 4)) - (cpl:with-failure-handling - ((common-fail:perception-object-not-found (e) - (cpl:do-retry perceive-retries - (roslisp:ros-warn (boxy-plans perceive) "~a" e) - (cpl:sleep 1.0) - (cpl:retry)))) - (exe:perform - (desig:a motion - (type inspecting) - (object ?object-designator))) - ;; (cram-robosherlock:perceive detect-or-inspect object-designator) - ))) - -(cpl:def-cram-function look (?left-goal-pose ?right-goal-pose) - (roslisp:ros-info (boxy-plans look) "Looking with wrist camera") - (exe:perform (desig:an action - (type reaching) - (left-poses (?left-goal-pose)) - (right-poses (?right-goal-pose)))) - (cpl:sleep 1.0) - (print "slept 1") - (cpl:sleep 1.0) - (print "slept 2")) diff --git a/cram_boxy/cram_boxy_plans/src/high-level-plans.lisp b/cram_boxy/cram_boxy_plans/src/high-level-plans.lisp deleted file mode 100644 index 3e2d262545..0000000000 --- a/cram_boxy/cram_boxy_plans/src/high-level-plans.lisp +++ /dev/null @@ -1,104 +0,0 @@ -;;; -;;; Copyright (c) 2016, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Institute for Artificial Intelligence/ -;;; Universitaet Bremen nor the names of its contributors may be used to -;;; endorse or promote products derived from this software without -;;; specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :boxy-plans) - -(defun find-object-on-holder (?object-type ?holder-object-type &key (one-or-all :one)) - (declare (type keyword one-or-all)) - "`one-or-all' can only be :one or :all" - ;; detect holder object with kinect - (let ((?holder-object - (exe:perform (desig:an action - (type detecting) - (object (desig:an object (type ?holder-object-type))))))) - ;; move wrist with camera above object to look closer - (exe:perform - (desig:an action - (type looking) - (object ?holder-object) - (camera wrist))) - ;; inspect object using camera wrist - (ecase one-or-all - (:one (exe:perform (desig:an action - (type inspecting) - (object (desig:an object (type ?holder-object-type))) - (for (desig:an object (type ?object-type)))))) - (:all (exe:perform (desig:an action - (type inspecting) - (object (desig:an object (type ?holder-object-type))) - (for (desig:all objects (type ?object-type))))))))) - -(defun find-object-on-surface (?object-type) - ;; move arms from field of view - (exe:perform (desig:an action - (type positioning-arm) - (left-configuration park) - (right-configuration park))) - ;; detect object with kinect - (let* ((?object - (exe:perform (desig:an action - (type detecting) - (object (desig:an object (type ?object-type))))))) - ;; move wrist with camera above object to look closer - (exe:perform - (desig:an action - (type looking) - (object ?object) - (camera wrist))) - ;; inspect object using camera wrist - (exe:perform (desig:an action - (type inspecting) - (object (desig:an object (type ?object-type))) - (for pose))))) - -(defun find-object (object-type &key holder-object-type (one-or-all :one)) - (if holder-object-type - (find-object-on-holder object-type holder-object-type :one-or-all one-or-all) - (find-object-on-surface object-type))) - -(defun attach (?object-type ?holder-object-type ?with-object-type ?with-holder-object-type) - (let (;; find object to which to attach - (?with-object (find-object ?with-object-type - :holder-object-type ?with-holder-object-type)) - ;; find object - (?object (find-object ?object-type - :holder-object-type ?holder-object-type))) - ;; pick up object - (exe:perform - (desig:an action - (type picking-up) - (object ?object) - (arm left))) - ;; attach objects - (exe:perform - (desig:a action - (type connecting) - (arm left) - (object ?object) - (with-object ?with-object))))) diff --git a/cram_boxy/cram_boxy_process_modules/src/definitions-old.lisp b/cram_boxy/cram_boxy_process_modules/src/definitions-old.lisp new file mode 100644 index 0000000000..936067582e --- /dev/null +++ b/cram_boxy/cram_boxy_process_modules/src/definitions-old.lisp @@ -0,0 +1,85 @@ +;;; +;;; Copyright (c) 2017, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :boxy-pm) + +;;;;;;;;;;;;;;;;; TORSO ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +;; (cpm:def-process-module torso-pm (motion-designator) +;; (destructuring-bind (command argument) (desig:reference motion-designator) +;; (ecase command +;; (cram-common-designators:move-torso +;; (handler-case +;; (boxy-ll:move-torso :goal-position argument)))))) + +;;;;;;;;;;;;;;;;;;;; NECK ;;;;;;;;;;;;;;;;;;;;;;;; + +(cpm:def-process-module neck-pm (motion-designator) + (destructuring-bind (command goal-pose goal-configuration) + (desig:reference motion-designator) + (declare (ignore goal-pose)) + (ecase command + (cram-common-designators:move-head + (boxy-ll:move-neck-joints :goal-configuration goal-configuration))))) + +;;;;;;;;;;;;;;;;;;;; GRIPPERS ;;;;;;;;;;;;;;;;;;;;;;;; + +(cpm:def-process-module grippers-pm (motion-designator) + (destructuring-bind (command action-type-or-position which-gripper &optional effort) + (desig:reference motion-designator) + (ecase command + (cram-common-designators:move-gripper-joint + (boxy-ll:move-gripper-joint :action-type-or-position action-type-or-position + :left-or-right which-gripper + :effort effort))))) + +;;;;;;;;;;;;;;;;;;;; BODY ;;;;;;;;;;;;;;;;;;;;;;;; + +(cpm:def-process-module body-pm (motion-designator) + (destructuring-bind (command argument-1 &rest rest-arguments) + (desig:reference motion-designator) + (ecase command + (cram-common-designators:move-tcp + (let ((goal-left argument-1) + (goal-right (car rest-arguments))) + (unless (listp goal-left) + (setf goal-left (list goal-left))) + (unless (listp goal-right) + (setf goal-right (list goal-right))) + (multiple-value-bind (goal-left goal-right) + (cut:equalize-two-list-lengths goal-left goal-right) + (mapc (lambda (single-pose-left single-pose-right) + (cram-tf:visualize-marker (list single-pose-left single-pose-right) + :r-g-b-list '(1 0 1)) + (boxy-ll:move-arm-cartesian :goal-pose-stamped-left single-pose-left + :goal-pose-stamped-right single-pose-right)) + goal-left goal-right)))) + (cram-common-designators:move-joints + (boxy-ll:move-arm-joints :goal-joint-states-left argument-1 + :goal-joint-states-right (car rest-arguments)))))) diff --git a/cram_boxy/cram_boxy_process_modules/src/definitions.lisp b/cram_boxy/cram_boxy_process_modules/src/definitions.lisp index 936067582e..03a5148013 100644 --- a/cram_boxy/cram_boxy_process_modules/src/definitions.lisp +++ b/cram_boxy/cram_boxy_process_modules/src/definitions.lisp @@ -29,25 +29,6 @@ (in-package :boxy-pm) -;;;;;;;;;;;;;;;;; TORSO ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -;; (cpm:def-process-module torso-pm (motion-designator) -;; (destructuring-bind (command argument) (desig:reference motion-designator) -;; (ecase command -;; (cram-common-designators:move-torso -;; (handler-case -;; (boxy-ll:move-torso :goal-position argument)))))) - -;;;;;;;;;;;;;;;;;;;; NECK ;;;;;;;;;;;;;;;;;;;;;;;; - -(cpm:def-process-module neck-pm (motion-designator) - (destructuring-bind (command goal-pose goal-configuration) - (desig:reference motion-designator) - (declare (ignore goal-pose)) - (ecase command - (cram-common-designators:move-head - (boxy-ll:move-neck-joints :goal-configuration goal-configuration))))) - ;;;;;;;;;;;;;;;;;;;; GRIPPERS ;;;;;;;;;;;;;;;;;;;;;;;; (cpm:def-process-module grippers-pm (motion-designator) @@ -55,31 +36,7 @@ (desig:reference motion-designator) (ecase command (cram-common-designators:move-gripper-joint - (boxy-ll:move-gripper-joint :action-type-or-position action-type-or-position - :left-or-right which-gripper - :effort effort))))) - -;;;;;;;;;;;;;;;;;;;; BODY ;;;;;;;;;;;;;;;;;;;;;;;; - -(cpm:def-process-module body-pm (motion-designator) - (destructuring-bind (command argument-1 &rest rest-arguments) - (desig:reference motion-designator) - (ecase command - (cram-common-designators:move-tcp - (let ((goal-left argument-1) - (goal-right (car rest-arguments))) - (unless (listp goal-left) - (setf goal-left (list goal-left))) - (unless (listp goal-right) - (setf goal-right (list goal-right))) - (multiple-value-bind (goal-left goal-right) - (cut:equalize-two-list-lengths goal-left goal-right) - (mapc (lambda (single-pose-left single-pose-right) - (cram-tf:visualize-marker (list single-pose-left single-pose-right) - :r-g-b-list '(1 0 1)) - (boxy-ll:move-arm-cartesian :goal-pose-stamped-left single-pose-left - :goal-pose-stamped-right single-pose-right)) - goal-left goal-right)))) - (cram-common-designators:move-joints - (boxy-ll:move-arm-joints :goal-joint-states-left argument-1 - :goal-joint-states-right (car rest-arguments)))))) + (boxy-ll:move-gripper-joint + :action-type-or-position action-type-or-position + :left-or-right which-gripper + :effort effort))))) diff --git a/cram_boxy/cram_boxy_process_modules/src/interface.lisp b/cram_boxy/cram_boxy_process_modules/src/interface.lisp index a9ccebe9d2..b451e38732 100644 --- a/cram_boxy/cram_boxy_process_modules/src/interface.lisp +++ b/cram_boxy/cram_boxy_process_modules/src/interface.lisp @@ -31,28 +31,29 @@ (def-fact-group boxy-matching-pms (cpm:matching-process-module cpm:available-process-module) - (<- (cpm:matching-process-module ?motion-designator neck-pm) - (desig:desig-prop ?motion-designator (:type :looking))) - (<- (cpm:matching-process-module ?motion-designator grippers-pm) (or (desig:desig-prop ?motion-designator (:type :gripping)) (desig:desig-prop ?motion-designator (:type :opening-gripper)) (desig:desig-prop ?motion-designator (:type :closing-gripper)) (desig:desig-prop ?motion-designator (:type :moving-gripper-joint)))) - (<- (cpm:matching-process-module ?motion-designator body-pm) + (<- (cpm:matching-process-module ?motion-designator giskard:giskard-pm) (or (desig:desig-prop ?motion-designator (:type :moving-tcp)) (desig:desig-prop ?motion-designator (:type :moving-arm-joints)) - (desig:desig-prop ?motion-designator (:type :wiggling-tcp)))) + (desig:desig-prop ?motion-designator (:type :pulling)) + (desig:desig-prop ?motion-designator (:type :pushing)) + (desig:desig-prop ?motion-designator (:type :wiggling-tcp)) + (desig:desig-prop ?motion-designator (:type :going)) + (desig:desig-prop ?motion-designator (:type :moving-torso)) + (desig:desig-prop ?motion-designator (:type :looking)))) (<- (cpm:available-process-module ?pm) - (member ?pm (neck-pm grippers-pm body-pm)) + (member ?pm (grippers-pm giskard:giskard-pm)) (not (cpm:projection-running ?_)))) (defmacro with-real-robot (&body body) `(cram-process-modules:with-process-modules-running - (rs:robosherlock-perception-pm navp:navp-pm - boxy-pm:neck-pm boxy-pm:grippers-pm boxy-pm:body-pm) + (rs:robosherlock-perception-pm grippers-pm giskard:giskard-pm) (cpl-impl::named-top-level (:name :top-level) ,@body))) diff --git a/cram_boxy/cram_boxy_projection/THIS-PACKAGE-IS-DEPRECATED b/cram_boxy/cram_boxy_projection/THIS-PACKAGE-IS-DEPRECATED deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/cram_boxy/cram_boxy_projection/package.xml b/cram_boxy/cram_boxy_projection/package.xml deleted file mode 100644 index 2d629daac6..0000000000 --- a/cram_boxy/cram_boxy_projection/package.xml +++ /dev/null @@ -1,41 +0,0 @@ - - cram_boxy_projection - 0.7.0 - - Projection process modules for Boxy - - Gayane Kazhoyan - Gayane Kazhoyan - BSD - http://cram-system.org - https://github.com/cram2/cram/issues - https://github.com/cram2/cram - - catkin - - cram_projection - cram_prolog - cram_designators - cram_utilities - cram_bullet_reasoning - cram_tf - cram_robot_interfaces - cl_transforms - cl_transforms_stamped - cl_tf - cram_occasions_events - cram_plan_occasions_events - cram_boxy_description - cram_common_designators - cram_boxy_designators - cram_common_failures - cram_process_modules - roslisp_utilities - alexandria - cram_semantic_map - cram_bullet_reasoning_belief_state - cram_simple_actionlib_client - cram_ik_interface - - - diff --git a/cram_boxy/cram_boxy_projection/src/giskard.lisp b/cram_boxy/cram_boxy_projection/src/giskard.lisp deleted file mode 100644 index b00f09397c..0000000000 --- a/cram_boxy/cram_boxy_projection/src/giskard.lisp +++ /dev/null @@ -1,404 +0,0 @@ -;;; -;;; Copyright (c) 2016, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Institute for Artificial Intelligence/ -;;; Universitaet Bremen nor the names of its contributors may be used to -;;; endorse or promote products derived from this software without -;;; specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :boxy-proj) - -(defun make-giskard-action-client () - (actionlib-client:make-simple-action-client - 'giskard-action - "qp_controller/command" "giskard_msgs/MoveAction" - 60)) - -(roslisp-utilities:register-ros-init-function make-giskard-action-client) - -(defparameter *giskard-convergence-delta-joint* 0.17 "in radiants, about 10 degrees") - -(defun make-giskard-joint-action-goal (joint-state-left joint-state-right) - (declare (type list joint-state-left joint-state-right)) - (roslisp:make-message - 'giskard_msgs-msg:MoveGoal - :type (roslisp:symbol-code 'giskard_msgs-msg:MoveGoal :plan_and_execute) - :cmd_seq (vector (roslisp:make-message - 'giskard_msgs-msg:movecmd - :controllers (vector (roslisp:make-message - 'giskard_msgs-msg:controller - :type (roslisp:symbol-code - 'giskard_msgs-msg:controller - :joint) - :p_gain 10 - :weight 1 - :max_speed (cma:degrees->radians 30) - :goal_state (roslisp:make-message - 'sensor_msgs-msg:jointstate - :name (apply #'vector - (first - joint-state-left)) - :position (apply #'vector - (second - joint-state-left)))) - (roslisp:make-message - 'giskard_msgs-msg:controller - :type (roslisp:symbol-code - 'giskard_msgs-msg:controller - :joint) - :p_gain 10 - :weight 1 - :max_speed (cma:degrees->radians 30) - :goal_state (roslisp:make-message - 'sensor_msgs-msg:jointstate - :name (apply #'vector - (first - joint-state-right)) - :position (apply #'vector - (second - joint-state-right))))) - :collisions (vector (roslisp:make-message - 'giskard_msgs-msg:collisionentry - :type (roslisp:symbol-code - 'giskard_msgs-msg:collisionentry - :avoid_all_collisions) - :min_dist 0.05)))))) - -;; (defun ensure-giskard-joint-input-parameters (left-goal right-goal) -;; (flet ((ensure-giskard-joint-goal (goal arm) -;; (if (and (listp goal) (= (length goal) 7)) -;; goal -;; (and (roslisp:ros-warn (low-level giskard) -;; "Joint goal ~a was not a list of 7. Ignoring." -;; goal) -;; (get-arm-joint-states arm))))) -;; (values (ensure-giskard-joint-goal left-goal :left) -;; (ensure-giskard-joint-goal right-goal :right)))) - -(defun move-arms-giskard-joint (&key goal-configuration-left goal-configuration-right - action-timeout) - (declare (type list goal-configuration-left goal-configuration-right) - (type (or null number) action-timeout)) - (multiple-value-bind (result status) - (actionlib-client:call-simple-action-client - 'giskard-action - :action-goal (make-giskard-joint-action-goal - goal-configuration-left goal-configuration-right) - :action-timeout action-timeout) - (values result status))) - - - -(defparameter *giskard-convergence-delta-xy* 0.005 "in meters") -(defparameter *giskard-convergence-delta-theta* 0.1 "in radiants, about 6 degrees") - -(defun make-giskard-cartesian-action-goal (left-pose right-pose - pose-base-frame left-tool-frame right-tool-frame - collision-mode) - (declare (type (or null cl-transforms-stamped:pose-stamped) left-pose right-pose) - (type string pose-base-frame left-tool-frame right-tool-frame)) - (roslisp:make-message - 'giskard_msgs-msg:MoveGoal - :type (roslisp:symbol-code 'giskard_msgs-msg:MoveGoal :plan_and_execute) - :cmd_seq (vector (roslisp:make-message - 'giskard_msgs-msg:movecmd - :controllers - (map 'vector #'identity - (remove nil - (list - (when left-pose - (roslisp:make-message - 'giskard_msgs-msg:controller - :type (roslisp:symbol-code - 'giskard_msgs-msg:controller - :translation_3d) - :root_link pose-base-frame - :tip_link left-tool-frame - :p_gain 3 - :weight 1 - :max_speed 0.3 - :goal_pose (cl-transforms-stamped:to-msg left-pose))) - (when left-pose - (roslisp:make-message - 'giskard_msgs-msg:controller - :type (roslisp:symbol-code - 'giskard_msgs-msg:controller - :rotation_3d) - :root_link pose-base-frame - :tip_link left-tool-frame - :p_gain 3 - :weight 1 - :max_speed (cma:degrees->radians 30) - :goal_pose (cl-transforms-stamped:to-msg left-pose))) - (when right-pose - (roslisp:make-message - 'giskard_msgs-msg:controller - :type (roslisp:symbol-code - 'giskard_msgs-msg:controller - :translation_3d) - :root_link pose-base-frame - :tip_link right-tool-frame - :p_gain 3 - :weight 1 - :max_speed 0.3 - :goal_pose (cl-transforms-stamped:to-msg right-pose))) - (when right-pose - (roslisp:make-message - 'giskard_msgs-msg:controller - :type (roslisp:symbol-code - 'giskard_msgs-msg:controller - :rotation_3d) - :root_link pose-base-frame - :tip_link right-tool-frame - :p_gain 3 - :weight 1 - :max_speed (cma:degrees->radians 30) - :goal_pose (cl-transforms-stamped:to-msg right-pose)))))) - :collisions - (case collision-mode - (:allow-all - (vector (roslisp:make-message - 'giskard_msgs-msg:collisionentry - :type (roslisp:symbol-code - 'giskard_msgs-msg:collisionentry - :allow_all_collisions)))) - (:avoid-all - (vector (roslisp:make-message - 'giskard_msgs-msg:collisionentry - :type (roslisp:symbol-code - 'giskard_msgs-msg:collisionentry - :avoid_all_collisions) - :min_dist 0.05))) - (t - (vector (roslisp:make-message - 'giskard_msgs-msg:collisionentry - :type (roslisp:symbol-code - 'giskard_msgs-msg:collisionentry - :avoid_all_collisions) - :min_dist 0.05)))))))) - -(defun ensure-giskard-cartesian-input-parameters (frame left-pose right-pose) - (values (when left-pose - (cram-tf:ensure-pose-in-frame left-pose frame)) - (when right-pose - (cram-tf:ensure-pose-in-frame right-pose frame)))) - -(defun ensure-giskard-cartesian-goal-reached (result status goal-position-left goal-position-right - goal-frame-left goal-frame-right - convergence-delta-xy convergence-delta-theta) - (when (eql status :preempted) - (roslisp:ros-warn (low-level giskard) "Giskard action preempted.") - (return-from ensure-giskard-cartesian-goal-reached)) - (when (eql status :timeout) - (roslisp:ros-warn (pr2-ll giskard-cart) "Giskard action timed out.")) - (when (eql status :aborted) - (roslisp:ros-warn (pr2-ll giskard-cart) "Giskard action aborted! With result ~a" result) - ;; (cpl:fail 'common-fail:manipulation-goal-not-reached - ;; :description "Giskard did not converge to goal because of collision") - ) - (when goal-position-left - (unless (cram-tf:tf-frame-converged goal-frame-left goal-position-left - convergence-delta-xy convergence-delta-theta) - (cpl:fail 'common-fail:manipulation-goal-not-reached - :description (format nil "Giskard did not converge to goal: -~a should have been at ~a with delta-xy of ~a and delta-angle of ~a." - goal-frame-left goal-position-left - convergence-delta-xy convergence-delta-theta)))) - (when goal-position-right - (unless (cram-tf:tf-frame-converged goal-frame-right goal-position-right - convergence-delta-xy convergence-delta-theta) - (cpl:fail 'common-fail:manipulation-goal-not-reached - :description (format nil "Giskard did not converge to goal: -~a should have been at ~a with delta-xy of ~a and delta-angle of ~a." - goal-frame-right goal-position-right - convergence-delta-xy convergence-delta-theta))))) - -(defun move-arms-giskard-cartesian (&key - goal-pose-left goal-pose-right action-timeout - collision-mode - (pose-base-frame cram-tf:*robot-base-frame*) - (left-tool-frame cram-tf:*robot-left-tool-frame*) - (right-tool-frame cram-tf:*robot-right-tool-frame*) - (convergence-delta-xy *giskard-convergence-delta-xy*) - (convergence-delta-theta *giskard-convergence-delta-theta*)) - (declare (type (or null cl-transforms-stamped:pose-stamped) goal-pose-left goal-pose-right) - (type (or null number) action-timeout convergence-delta-xy convergence-delta-theta) - (type (or null string) pose-base-frame left-tool-frame right-tool-frame)) - (if (or goal-pose-left goal-pose-right) - (multiple-value-bind (goal-pose-left goal-pose-right) - (ensure-giskard-cartesian-input-parameters pose-base-frame goal-pose-left goal-pose-right) - (cram-tf:visualize-marker (list goal-pose-left goal-pose-right) :r-g-b-list '(1 0 1)) - (multiple-value-bind (result status) - (let ((goal (make-giskard-cartesian-action-goal - goal-pose-left goal-pose-right - pose-base-frame left-tool-frame right-tool-frame - collision-mode))) - (actionlib-client:call-simple-action-client - 'giskard-action - :action-goal goal - :action-timeout action-timeout)) - (ensure-giskard-cartesian-goal-reached result status goal-pose-left goal-pose-right - left-tool-frame right-tool-frame - convergence-delta-xy convergence-delta-theta) - (values result status))) - (roslisp:ros-info (pr2-ll giskard-cart) "Got an empty goal..."))) - - - -#+old-giskard -( - (defun make-giskard-action-client () - (actionlib-client:make-simple-action-client - 'giskard-action - "controller_action_server/move" "giskard_msgs/WholeBodyAction" - 60)) - - (roslisp-utilities:register-ros-init-function make-giskard-action-client) - - (defparameter *giskard-convergence-delta-joint* 0.17 "in radiants, about 10 degrees") - - (defun make-giskard-joint-action-goal (left-configuration right-configuration - &optional convergence-delta-joint) - (declare (type list left-configuration right-configuration) - (ignore convergence-delta-joint)) - (roslisp:make-message - 'giskard_msgs-msg:WholeBodyGoal - (:type :command) - (roslisp:symbol-code 'giskard_msgs-msg:wholebodycommand :standard_controller) - (:type :left_ee :command) - (roslisp:symbol-code 'giskard_msgs-msg:armcommand :joint_goal) - (:goal_configuration :left_ee :command) - (apply #'vector left-configuration) - (:type :right_ee :command) - (roslisp:symbol-code 'giskard_msgs-msg:armcommand :joint_goal) - (:goal_configuration :right_ee :command) - (apply #'vector right-configuration))) - - ;; (defun ensure-giskard-joint-input-parameters (left-goal right-goal) - ;; (flet ((ensure-giskard-joint-goal (goal arm) - ;; (if (and (listp goal) (= (length goal) 7)) - ;; goal - ;; (and (roslisp:ros-warn (low-level giskard) - ;; "Joint goal ~a was not a list of 7. Ignoring." - ;; goal) - ;; (get-arm-joint-states arm))))) - ;; (values (ensure-giskard-joint-goal left-goal :left) - ;; (ensure-giskard-joint-goal right-goal :right)))) - - (defun move-arms-giskard-joint (&key goal-configuration-left goal-configuration-right - action-timeout) - (declare (type list goal-configuration-left goal-configuration-right) - (type (or null number) action-timeout)) - (multiple-value-bind (result status) - (actionlib-client:call-simple-action-client - 'giskard-action - :action-goal (make-giskard-joint-action-goal - goal-configuration-left goal-configuration-right) - :action-timeout action-timeout) - (values result status))) - - - - (defparameter *giskard-convergence-delta-xy* 0.005 "in meters") - (defparameter *giskard-convergence-delta-theta* 0.1 "in radiants, about 6 degrees") - - (defun make-giskard-cartesian-action-goal (left-pose right-pose - &optional convergence-delta-xy convergence-delta-theta) - (declare (ignore convergence-delta-xy convergence-delta-theta) - (type (or cl-transforms:pose cl-transforms-stamped:pose-stamped) - left-pose right-pose)) - (roslisp:make-message - 'giskard_msgs-msg:WholeBodyGoal - (:type :command) - (roslisp:symbol-code 'giskard_msgs-msg:wholebodycommand :standard_controller) - (:type :left_ee :command) - (roslisp:symbol-code 'giskard_msgs-msg:armcommand :cartesian_goal) - (:goal_pose :left_ee :command) - (cl-transforms-stamped:to-msg left-pose) - ;; (:type :right_ee :command) - ;; (roslisp:symbol-code 'giskard_msgs-msg:armcommand :joint_goal) - ;; (:goal_configuration :right_ee :command) - ;; ;; sending right arm goal as a joint state because our right arm is broken at the moment - ;; (apply #'vector (get-arm-joint-states :right)) - )) - - (defun ensure-giskard-cartesian-input-parameters (frame left-pose right-pose) - (values (cram-tf:ensure-pose-in-frame - (or left-pose - (cl-transforms-stamped:pose->pose-stamped - cram-tf:*robot-left-tool-frame* - 0.0 - (cl-transforms:make-identity-pose))) - frame) - (cram-tf:ensure-pose-in-frame - (or right-pose - (cl-transforms-stamped:pose->pose-stamped - cram-tf:*robot-right-tool-frame* - 0.0 - (cl-transforms:make-identity-pose))) - frame))) - - (defun ensure-giskard-cartesian-goal-reached (status goal-position-left goal-position-right - goal-frame-left goal-frame-right - convergence-delta-xy convergence-delta-theta) - (when (eql status :timeout) - (cpl:fail 'common-fail:actionlib-action-timed-out :description "Giskard action timed out")) - (when (eql status :preempted) - (roslisp:ros-warn (low-level giskard) "Giskard action preempted.") - (return-from ensure-giskard-cartesian-goal-reached)) - (when goal-position-left - (unless (cram-tf:tf-frame-converged goal-frame-left goal-position-left - convergence-delta-xy convergence-delta-theta) - (cpl:fail 'common-fail:manipulation-goal-not-reached - :description (format nil "Giskard did not converge to goal: ~ - ~a should have been at ~a with delta-xy of ~a ~ - and delta-angle of ~a." - goal-frame-left goal-position-left - convergence-delta-xy convergence-delta-theta))))) - - (defun move-arms-giskard-cartesian (&key - goal-pose-left goal-pose-right action-timeout - (pose-base-frame cram-tf:*robot-base-frame*) - (left-tool-frame cram-tf:*robot-left-tool-frame*) - (right-tool-frame cram-tf:*robot-right-tool-frame*) - (convergence-delta-xy *giskard-convergence-delta-xy*) - (convergence-delta-theta *giskard-convergence-delta-theta*)) - (declare (type (or null cl-transforms-stamped:pose-stamped) goal-pose-left goal-pose-right) - (type (or null string) pose-base-frame left-tool-frame right-tool-frame) - (type (or null number) action-timeout convergence-delta-xy convergence-delta-theta)) - (multiple-value-bind (goal-pose-left goal-pose-right) - (ensure-giskard-cartesian-input-parameters pose-base-frame goal-pose-left goal-pose-right) - (multiple-value-bind (result status) - (actionlib-client:call-simple-action-client - 'giskard-action - :action-goal (make-giskard-cartesian-action-goal - goal-pose-left goal-pose-right - convergence-delta-xy convergence-delta-theta) - :action-timeout action-timeout) - (ensure-giskard-cartesian-goal-reached status goal-pose-left goal-pose-right - left-tool-frame right-tool-frame - convergence-delta-xy convergence-delta-theta) - (values result status)))) - - ) diff --git a/cram_boxy/cram_boxy_projection/src/ik.lisp b/cram_boxy/cram_boxy_projection/src/ik.lisp deleted file mode 100644 index a58f276945..0000000000 --- a/cram_boxy/cram_boxy_projection/src/ik.lisp +++ /dev/null @@ -1,212 +0,0 @@ -;;; -;;; Copyright (c) 2018, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Institute for Artificial Intelligence/ -;;; Universitaet Bremen nor the names of its contributors may be used to -;;; endorse or promote products derived from this software without -;;; specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :boxy-proj) - -(defparameter *ik-service-name* "kdl_ik_service/get_ik") - -(defun call-ik-service (left-or-right cartesian-pose &optional seed-state) - (declare (type keyword left-or-right) - (type cl-transforms-stamped:pose-stamped cartesian-pose) - (ignore seed-state)) - (let* ((robot-info-bindings - (cut:lazy-car - (prolog:prolog - `(and (cram-robot-interfaces:robot ?robot) - (cram-robot-interfaces:arm-joints ?robot ,left-or-right ?joints) - (cram-robot-interfaces:end-effector-link ?robot ,left-or-right ?ee-link) - (cram-robot-interfaces:robot-torso-link-joint ?robot ?torso-link ?_))))) - (ee-link - (cut:var-value '?ee-link robot-info-bindings)) - (torso-link - (cut:var-value '?torso-link robot-info-bindings)) - (joint-names - (cut:var-value '?joints robot-info-bindings)) - (joint-state-msg - (btr::make-robot-joint-state-msg - (btr:get-robot-object) - :joint-names joint-names))) - (roslisp:with-fields ((response-error-code (val error_code)) - (joint-state (joint_state solution))) - (progn - (roslisp:wait-for-service *ik-service-name* 10.0) - (roslisp:call-service - *ik-service-name* - 'moveit_msgs-srv:getpositionik - (roslisp:make-request - 'moveit_msgs-srv:getpositionik - (:ik_link_name :ik_request) ee-link - (:pose_stamped :ik_request) (cl-transforms-stamped:to-msg - (cram-tf:ensure-pose-in-frame - cartesian-pose torso-link :use-zero-time t)) - (:joint_state :robot_state :ik_request) joint-state-msg - (:timeout :ik_request) 1.0))) - (cond ((eql response-error-code - (roslisp-msg-protocol:symbol-code - 'moveit_msgs-msg:moveiterrorcodes - :success)) - joint-state) - ((eql response-error-code - (roslisp-msg-protocol:symbol-code - 'moveit_msgs-msg:moveiterrorcodes - :no_ik_solution)) - nil) - (T - (error 'simple-error - :format-control "IK service failed: ~a" - :format-arguments (list - (roslisp-msg-protocol:code-symbol - 'moveit_msgs-msg:moveiterrorcodes - response-error-code)))))))) - -(defparameter *torso-step* 0.01) - -(defun call-ik-service-with-torso-resampling (left-or-right cartesian-pose - &key seed-state test-angle torso-angle - torso-lower-limit torso-upper-limit) - (labels ((call-ik-service-with-torso-resampling-inner (left-or-right cartesian-pose - &key seed-state test-angle - torso-angle - torso-lower-limit torso-upper-limit) - (let ((ik-solution (call-ik-service left-or-right cartesian-pose seed-state))) - (if (not ik-solution) - (when (or (not test-angle) (> test-angle torso-lower-limit)) - ;; When we have no ik solution and have a valid torso angle to try, - ;; use it to resample. - (let* ((next-test-angle - (if test-angle - (max torso-lower-limit (- test-angle *torso-step*)) - torso-upper-limit)) - (torso-offset - (if test-angle - (- test-angle torso-angle) - 0)) - (next-torso-offset - (- next-test-angle torso-angle)) - (pseudo-pose - (cram-tf:translate-pose cartesian-pose - :z-offset (- torso-offset - next-torso-offset)))) - (call-ik-service-with-torso-resampling-inner - left-or-right pseudo-pose - :seed-state seed-state - :test-angle next-test-angle - :torso-angle torso-angle - :torso-lower-limit torso-lower-limit - :torso-upper-limit torso-upper-limit))) - (values ik-solution (or test-angle torso-angle)))))) - - (let ((old-debug-lvl (roslisp:debug-level NIL))) - (unwind-protect - (progn - (roslisp:set-debug-level NIL 9) - (call-ik-service-with-torso-resampling-inner - left-or-right cartesian-pose - :seed-state seed-state - :test-angle test-angle - :torso-angle torso-angle - :torso-lower-limit torso-lower-limit - :torso-upper-limit torso-upper-limit)) - (roslisp:set-debug-level NIL old-debug-lvl))))) - - - -#+commentedoutfornow -( - (defun set-robot-state-to-ik-result () - (btr:set-robot-state-from-joints - (call-ik) - (btr:get-robot-object))) - - (defun ensure-giskard-cartesian-input-parameters (frame left-pose right-pose) - (values (when left-pose - (cram-tf:ensure-pose-in-frame left-pose frame)) - (when right-pose - (cram-tf:ensure-pose-in-frame right-pose frame)))) - - (defun ensure-giskard-cartesian-goal-reached (result status goal-position-left goal-position-right - goal-frame-left goal-frame-right - convergence-delta-xy convergence-delta-theta) - (when (eql status :preempted) - (roslisp:ros-warn (low-level giskard) "Giskard action preempted.") - (return-from ensure-giskard-cartesian-goal-reached)) - (when (eql status :timeout) - (roslisp:ros-warn (pr2-ll giskard-cart) "Giskard action timed out.")) - (when (eql status :aborted) - (roslisp:ros-warn (pr2-ll giskard-cart) "Giskard action aborted! With result ~a" result) - ;; (cpl:fail 'common-fail:manipulation-goal-not-reached - ;; :description "Giskard did not converge to goal because of collision") - ) - (when goal-position-left - (unless (cram-tf:tf-frame-converged goal-frame-left goal-position-left - convergence-delta-xy convergence-delta-theta) - (cpl:fail 'common-fail:manipulation-goal-not-reached - :description (format nil "Giskard did not converge to goal: -~a should have been at ~a with delta-xy of ~a and delta-angle of ~a." - goal-frame-left goal-position-left - convergence-delta-xy convergence-delta-theta)))) - (when goal-position-right - (unless (cram-tf:tf-frame-converged goal-frame-right goal-position-right - convergence-delta-xy convergence-delta-theta) - (cpl:fail 'common-fail:manipulation-goal-not-reached - :description (format nil "Giskard did not converge to goal: -~a should have been at ~a with delta-xy of ~a and delta-angle of ~a." - goal-frame-right goal-position-right - convergence-delta-xy convergence-delta-theta))))) - - (defun move-arms-giskard-cartesian (&key - goal-pose-left goal-pose-right action-timeout - collision-mode - (pose-base-frame cram-tf:*robot-base-frame*) - (left-tool-frame cram-tf:*robot-left-tool-frame*) - (right-tool-frame cram-tf:*robot-right-tool-frame*) - (convergence-delta-xy *giskard-convergence-delta-xy*) - (convergence-delta-theta *giskard-convergence-delta-theta*)) - (declare (type (or null cl-transforms-stamped:pose-stamped) goal-pose-left goal-pose-right) - (type (or null number) action-timeout convergence-delta-xy convergence-delta-theta) - (type (or null string) pose-base-frame left-tool-frame right-tool-frame)) - (if (or goal-pose-left goal-pose-right) - (multiple-value-bind (goal-pose-left goal-pose-right) - (ensure-giskard-cartesian-input-parameters pose-base-frame goal-pose-left goal-pose-right) - (cram-tf:visualize-marker (list goal-pose-left goal-pose-right) :r-g-b-list '(1 0 1)) - (multiple-value-bind (result status) - (let ((goal (make-giskard-cartesian-action-goal - goal-pose-left goal-pose-right - pose-base-frame left-tool-frame right-tool-frame - collision-mode))) - (actionlib-client:call-simple-action-client - 'giskard-action - :action-goal goal - :action-timeout action-timeout)) - (ensure-giskard-cartesian-goal-reached result status goal-pose-left goal-pose-right - left-tool-frame right-tool-frame - convergence-delta-xy convergence-delta-theta) - (values result status))) - (roslisp:ros-info (pr2-ll giskard-cart) "Got an empty goal..."))) - ) diff --git a/cram_boxy/cram_boxy_projection/src/low-level.lisp b/cram_boxy/cram_boxy_projection/src/low-level.lisp deleted file mode 100644 index 8e21c2e90c..0000000000 --- a/cram_boxy/cram_boxy_projection/src/low-level.lisp +++ /dev/null @@ -1,575 +0,0 @@ -;;; -;;; Copyright (c) 2011, Lorenz Moesenlechner -;;; 2018, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software -;;; without specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :boxy-proj) - -(defparameter *debug-short-sleep-duration* 0.0 - "in seconds, sleeps after each movement during reasoning") -(defparameter *debug-long-sleep-duration* 0.0 - "in seconds, sleeps to show colliding configurations") - -(defun robot-transform-in-map () - (let ((pose-in-map - (cut:var-value - '?pose - (car (prolog:prolog - `(and (cram-robot-interfaces:robot ?robot) - (btr:bullet-world ?w) - (btr:object-pose ?w ?robot ?pose))))))) - (cram-tf:pose->transform-stamped - cram-tf:*fixed-frame* - cram-tf:*robot-base-frame* - (cut:current-timestamp) - pose-in-map))) - -;;;;;;;;;;;;;;;;; NAVIGATION ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(defun drive (target) - (declare (type cl-transforms-stamped:pose-stamped target)) - (let* ((world btr:*current-bullet-world*) - (world-state (btr::get-state world))) - (unwind-protect - (assert - (prolog:prolog - `(and (cram-robot-interfaces:robot ?robot) - (btr:bullet-world ?w) - (btr:assert ?w (btr:object-pose ?robot ,target))))) - (when (btr:robot-colliding-objects-without-attached '(:floor)) - (unless (< (abs *debug-short-sleep-duration*) 0.0001) - (cpl:sleep *debug-short-sleep-duration*)) - (btr::restore-world-state world-state world) - (cpl:fail 'common-fail:navigation-pose-unreachable :pose-stamped target))))) - -;;;;;;;;;;;;;;;;; TORSO ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(defun move-torso (joint-angle) - (declare (type number joint-angle)) - (let* ((bindings - (car - (prolog:prolog - `(and (cram-robot-interfaces:robot ?robot) - (btr:bullet-world ?w) - (cram-robot-interfaces:robot-torso-link-joint ?robot ?_ ?joint) - (cram-robot-interfaces:joint-lower-limit ?robot ?joint ?lower) - (cram-robot-interfaces:joint-upper-limit ?robot ?joint ?upper))))) - (lower-limit - (cut:var-value '?lower bindings)) - (upper-limit - (cut:var-value '?upper bindings)) - (cropped-joint-angle - (if (< joint-angle lower-limit) - lower-limit - (if (> joint-angle upper-limit) - upper-limit - joint-angle)))) - (prolog:prolog - `(btr:assert (btr:joint-state ?w ?robot ((?joint ,cropped-joint-angle)))) - bindings) - (unless (< (abs (- joint-angle cropped-joint-angle)) 0.0001) - (cpl:fail 'common-fail:torso-goal-not-reached - :description (format nil "Torso goal ~a was out of joint limits" joint-angle) - :torso joint-angle)))) - -;;;;;;;;;;;;;;;;; PTU ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(defun look-at-joint-angles (joint-angles) - (declare (type list joint-angles)) - (assert - (prolog:prolog - `(and (cram-robot-interfaces:robot ?robot) - (btr:bullet-world ?w) - (cram-robot-interfaces:robot-neck-joints ?robot . ?joint-names) - (prolog:lisp-fun mapcar list ?joint-names ,joint-angles ?joint-states) - (btr:assert ?w (btr:joint-state ?robot ?joint-states)))))) - -(defun look-at-joint-states (joint-states) - (declare (type list joint-states)) - (assert - (prolog:prolog - `(and (cram-robot-interfaces:robot ?robot) - (btr:bullet-world ?w) - (btr:assert ?w (btr:joint-state ?robot ,joint-states)))))) - -(defparameter *camera-pose-unit-vector-multiplyer* 0.4) -(defparameter *camera-pose-z-offset* 0.2) -(defparameter *camera-resampling-step* 0.1) -(defparameter *camera-x-axis-limit* 0.5) -(defparameter *camera-y-axis-limit* 0.5) - -(defun get-neck-ik (ee-link cartesian-pose base-link joint-names) - (let ((joint-state-msg - (or (ik:call-ik-service-with-resampling - (cl-tf:pose->pose-stamped - base-link - 0.0 - cartesian-pose) - base-link ee-link - (btr::make-robot-joint-state-msg - (btr:get-robot-object) - :joint-names joint-names) - *camera-resampling-step* :x - 0 (- *camera-x-axis-limit*) *camera-x-axis-limit*) - (ik:call-ik-service-with-resampling - (cl-tf:pose->pose-stamped - base-link - 0.0 - cartesian-pose) - base-link ee-link - (btr::make-robot-joint-state-msg - (btr:get-robot-object) - :joint-names joint-names) - *camera-resampling-step* :y - 0 (- *camera-y-axis-limit*) *camera-y-axis-limit*)))) - (when joint-state-msg - (map 'list #'identity (roslisp:msg-slot-value joint-state-msg :position))))) - -(defun calculate-camera-pose-from-object-pose (neck-base-t-object) - "Takes the vector from neck-base to object, sets its Z to 0, -then normalizes to get a unit vector, then multiplies with a multiplier to make it shorter - (multiplier should be comparable to maximum length between neck base and camera), -then pulls the vector up in Z a bit to avoid colliding with bottom parts of robot, -and that would be the desired camera position. -Next, to calculate desired camera rotation, looks at the object from camera position, -calculates an angle that would have to be applied around X axis to align camera's Z -with the object, calculates similar angle around Y axis and applies the rotations. " - (let* ((neck-base-t-object-vector - (cl-transforms:translation neck-base-t-object)) - (neck-base-t-object-vector-without-z - (cl-transforms:copy-3d-vector neck-base-t-object-vector :z 0.0)) - (neck-base-t-object-unit-vector - (cl-transforms:normalize-vector neck-base-t-object-vector-without-z)) - (neck-base-t-object-short-vector - (cl-transforms:v* neck-base-t-object-unit-vector *camera-pose-unit-vector-multiplyer*)) - (neck-base-t-object-short-vector-lifted - (cl-transforms:v+ neck-base-t-object-short-vector - (cl-transforms:make-3d-vector 0 0 *camera-pose-z-offset*))) - - (neck-base-t-camera-not-oriented - (cl-transforms:make-transform - neck-base-t-object-short-vector-lifted - (cl-transforms:make-quaternion -1 0 0 0))) - (camera-not-oriented-t-neck-base - (cl-transforms:transform-inv - neck-base-t-camera-not-oriented)) - (camera-not-oriented-t-object - (cl-transforms:transform* - camera-not-oriented-t-neck-base - neck-base-t-object)) - (rotation-angle-around-x - (- (atan - (cl-transforms:y (cl-transforms:translation camera-not-oriented-t-object)) - (cl-transforms:z (cl-transforms:translation camera-not-oriented-t-object))))) - (neck-base-t-camera-rotated-around-x - (cram-tf:rotate-transform-in-own-frame - neck-base-t-camera-not-oriented - :x rotation-angle-around-x)) - (camera-rotated-around-x-t-neck-base - (cl-transforms:transform-inv - neck-base-t-camera-rotated-around-x)) - (camera-rotated-around-x-t-object - (cl-transforms:transform* - camera-rotated-around-x-t-neck-base - neck-base-t-object)) - (rotation-angle-around-y - (atan - (cl-transforms:x (cl-transforms:translation camera-rotated-around-x-t-object)) - (cl-transforms:z (cl-transforms:translation camera-rotated-around-x-t-object)))) - (neck-base-t-camera - (cram-tf:rotate-transform-in-own-frame - neck-base-t-camera-rotated-around-x - :y rotation-angle-around-y))) - neck-base-t-camera)) - -(defun look-at-pose (object-pose) - (let* ((map-p-object - (cram-tf:ensure-pose-in-frame object-pose cram-tf:*fixed-frame* :use-zero-time t)) - (bindings - (cut:lazy-car - (prolog:prolog - `(and (cram-robot-interfaces:robot ?robot) - (cram-robot-interfaces:robot-neck-links ?robot . ?neck-frames) - (cram-robot-interfaces:robot-neck-joints ?robot . ?neck-joints) - (cram-robot-interfaces:robot-neck-base-link ?robot ?neck-base-frame) - (cram-robot-interfaces:camera-in-neck-ee-pose ?robot ?neck-ee-p-cam))))) - (neck-ee-frame - (car (last (cut:var-value '?neck-frames bindings)))) - (neck-joints - (cut:var-value '?neck-joints bindings)) - (neck-base-frame - (cut:var-value '?neck-base-frame bindings)) - (neck-ee-p-camera - (cut:var-value '?neck-ee-p-cam bindings)) - - (map-p-neck-base - (btr:link-pose (btr:get-robot-object) neck-base-frame)) - (neck-base-t-map - (cl-transforms:transform-inv - (cl-transforms:pose->transform map-p-neck-base))) - (neck-base-t-object - (cl-transforms:transform* - neck-base-t-map - (cl-transforms:pose->transform map-p-object))) - - (neck-base-t-camera - (calculate-camera-pose-from-object-pose neck-base-t-object)) - - (camera-t-neck-ee - (cl-transforms:transform-inv (cl-transforms:pose->transform neck-ee-p-camera))) - (neck-base-t-neck-ee - (cl-transforms:transform* neck-base-t-camera camera-t-neck-ee)) - (neck-base-p-neck-ee - (cl-transforms:transform->pose neck-base-t-neck-ee)) - - (joint-state - (get-neck-ik neck-ee-frame neck-base-p-neck-ee neck-base-frame neck-joints))) - - (if joint-state - (look-at-joint-angles joint-state) - (cpl:fail 'common-fail:ptu-goal-not-reached - :description "Look goal was not reachable")))) - -(defun look-at (pose configuration) - (if pose - (look-at-pose pose) - (if configuration - (if (typep (car configuration) 'list) - (look-at-joint-states configuration) - (look-at-joint-angles configuration)) - (error "LOOK action has to have either pose or configuration given.")))) - -;;;;;;;;;;;;;;;;; PERCEPTION ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(defun extend-perceived-object-designator (input-designator name-pose-type-list) - (destructuring-bind (name pose type) name-pose-type-list - (let* ((pose-stamped-in-fixed-frame - (cl-transforms-stamped:make-pose-stamped - cram-tf:*fixed-frame* - (cut:current-timestamp) - (cl-transforms:origin pose) - (cl-transforms:orientation pose))) - (transform-stamped-in-fixed-frame - (cram-tf:pose-stamped->transform-stamped - pose-stamped-in-fixed-frame - (roslisp-utilities:rosify-underscores-lisp-name name))) - (pose-stamped-in-base-frame - (cram-tf:multiply-transform-stampeds - cram-tf:*robot-base-frame* - (roslisp-utilities:rosify-underscores-lisp-name name) - (cram-tf:transform-stamped-inv (robot-transform-in-map)) - transform-stamped-in-fixed-frame - :result-as-pose-or-transform :pose)) - (transform-stamped-in-base-frame - (cram-tf:multiply-transform-stampeds - cram-tf:*robot-base-frame* - (roslisp-utilities:rosify-underscores-lisp-name name) - (cram-tf:transform-stamped-inv (robot-transform-in-map)) - transform-stamped-in-fixed-frame - :result-as-pose-or-transform :transform))) - (let ((output-designator - (desig:copy-designator - input-designator - :new-description - `((:type ,type) - (:name ,name) - (:pose ((:pose ,pose-stamped-in-base-frame) - (:transform ,transform-stamped-in-base-frame) - (:pose-in-map ,pose-stamped-in-fixed-frame) - (:transform-in-map ,transform-stamped-in-fixed-frame))))))) - (setf (slot-value output-designator 'desig:data) - (make-instance 'desig:object-designator-data - :object-identifier name - :pose pose-stamped-in-fixed-frame)) - ;; (desig:equate input-designator output-designator) - output-designator)))) - -(defun detect (input-designator) - (declare (type desig:object-designator input-designator)) - - (let* ((object-name (desig:desig-prop-value input-designator :name)) - (object-type (desig:desig-prop-value input-designator :type)) - (quantifier (desig:quantifier input-designator)) - - ;; find all visible objects with name `object-name' and of type `object-type' - (name-pose-type-lists ; e.g.: ((mondamin-1 :mondamin ) (mug-2 :mug )) - (cut:force-ll - (cut:lazy-mapcar - (lambda (solution-bindings) - (cut:with-vars-strictly-bound (?object-name ?object-pose ?object-type) - solution-bindings - (list ?object-name ?object-pose ?object-type))) - (prolog:prolog `(and (cram-robot-interfaces:robot ?robot) - (btr:bullet-world ?world) - ,@(when object-name - `((prolog:== ?object-name ,object-name))) - (btr:object ?world ?object-name) - ,@(when object-type - `((prolog:== ?object-type ,object-type))) - (btr:item-type ?world ?object-name ?object-type) - (btr:visible ?world ?robot ?object-name) - (btr:pose ?world ?object-name ?object-pose))))))) - - ;; check if objects were found - (unless name-pose-type-lists - (cpl:fail 'common-fail:perception-object-not-found :object input-designator - :description (format nil "Could not find object ~a." input-designator))) - - ;; Extend the input-designator with the information found through visibility check: - ;; name & pose & type of the object, - ;; equate the input-designator to the new output-designator. - ;; If multiple objects are visible, return multiple equated objects, - ;; otherwise only take first found object. I.e. need to find :an object (not :all objects) - (case quantifier - (:all (mapcar (alexandria:curry #'extend-perceived-object-designator input-designator) - name-pose-type-lists)) - ((:a :an) (extend-perceived-object-designator - input-designator - (first name-pose-type-lists))) - (t (error "[PROJECTION DETECT]: Quantifier can only be a/an or all."))))) - -;;;;;;;;;;;;;;;;; GRIPPERS ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(defun one-gripper-action (action-type arm &optional maximum-effort) - (declare (ignore maximum-effort)) - "Opens or closes the specific gripper." - (mapc - - (lambda (solution-bindings) - (prolog:prolog - `(and - (btr:bullet-world ?world) - (assert ?world (btr:joint-state ?robot - ((?joint ,(case action-type - (:open '?max-limit) - ((:close :grip) '?min-limit) - (t (if (numberp action-type) - action-type - (error "[PROJ GRIP] failed"))))))))) - solution-bindings)) - - (cut:force-ll - (prolog:prolog - `(and (cram-robot-interfaces:robot ?robot) - (cram-robot-interfaces:gripper-joint ?robot ,arm ?joint) - (cram-robot-interfaces:joint-lower-limit ?robot ?joint ?min-limit) - (cram-robot-interfaces:joint-upper-limit ?robot ?joint ?max-limit))))) - - ;; check if there is an object to grip - (when (eql action-type :grip) ; if action was gripping check if gripper collided with an item - (unless (prolog:prolog - `(and (btr:bullet-world ?world) - (cram-robot-interfaces:robot ?robot) - (btr:contact ?world ?robot ?object-name ?link) - (cram-robot-interfaces:gripper-link ?robot ,arm ?link) - (btr:%object ?world ?object-name ?object-instance) - (prolog:lisp-type ?object-instance btr:item))) - (cpl:fail 'common-fail:gripper-closed-completely - :description "There was no object to grip")))) - -(defun gripper-action (action-type arm &optional maximum-effort) - (if (and arm (listp arm)) - (cpl:par - (one-gripper-action action-type (first arm) maximum-effort) - (one-gripper-action action-type (second arm) maximum-effort)) - (one-gripper-action action-type arm maximum-effort))) - -;;;;;;;;;;;;;;;;; ARMS ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(defun move-joints (left-configuration right-configuration) - (declare (type list left-configuration right-configuration)) - (flet ((set-configuration (arm joint-values) - (when joint-values - (let ((joint-name-value-list - (if (listp (car joint-values)) - joint-values - (let ((joint-names - (cut:var-value - '?joints - (car (prolog:prolog - `(and (cram-robot-interfaces:robot ?robot) - (cram-robot-interfaces:arm-joints ?robot ,arm - ?joints))))))) - (unless (= (length joint-values) (length joint-names)) - (error "[PROJECTION MOVE-JOINTS] length of joints list is incorrect")) - (mapcar (lambda (name value) - (list name (* value 1.0d0))) - joint-names joint-values))))) - (assert - (prolog:prolog - `(and - (btr:bullet-world ?world) - (cram-robot-interfaces:robot ?robot) - (assert ?world (btr:joint-state ?robot ,joint-name-value-list))))))))) - (set-configuration :left left-configuration) - (set-configuration :right right-configuration))) - -(defparameter *tcp-pose-in-ee* (cl-transforms:make-pose - (cl-transforms:make-3d-vector 0 0 0.3191d0) - (cl-transforms:make-identity-rotation)) - "In meters, Teetcp, EE -> TCP but a Pose") - -(defparameter *torso-resampling-step* 0.1) - -(defun move-tcp (left-tcp-pose right-tcp-pose) - (declare (type (or cl-transforms-stamped:pose-stamped null) left-tcp-pose right-tcp-pose)) - (flet ((tcp-pose->ee-pose (tcp-pose tool-frame end-effector-frame) - (when tcp-pose - (cram-tf:strip-transform-stamped - (cram-tf:multiply-transform-stampeds - cram-tf:*robot-base-frame* - end-effector-frame - (cram-tf:pose->transform-stamped - cram-tf:*robot-base-frame* - tool-frame - 0.0 - tcp-pose) - (cram-tf:transform-stamped-inv - (cram-tf:pose->transform-stamped - end-effector-frame - tool-frame - 0.0 - *tcp-pose-in-ee*)))))) - (ee-pose-in-base->ee-pose-in-torso (ee-pose-in-base) - (when ee-pose-in-base - (if (string-equal - (cl-transforms-stamped:frame-id ee-pose-in-base) - cram-tf:*robot-base-frame*) - ;; tPe: tTe = tTb * bTe = tTm * mTb * bTe = (mTt)-1 * mTb * bTe - (let* ((map-torso-transform - (cram-tf:pose->transform-stamped - cram-tf:*fixed-frame* - cram-tf:*robot-torso-frame* - 0.0 - (btr:link-pose - (btr:get-robot-object) - cram-tf:*robot-torso-frame*))) - (torso-map-transform - (cram-tf:transform-stamped-inv map-torso-transform)) - (map-base-transform - (cram-tf:pose->transform-stamped - cram-tf:*fixed-frame* - cram-tf:*robot-base-frame* - 0.0 - (btr:pose (btr:get-robot-object)))) - (torso-base-transform - (cram-tf:multiply-transform-stampeds - cram-tf:*robot-torso-frame* - cram-tf:*robot-base-frame* - torso-map-transform - map-base-transform)) - (base-ee-transform - (cram-tf:pose-stamped->transform-stamped - ee-pose-in-base - ;; dummy link name for T x T to work - "end_effector_link"))) - (cram-tf:multiply-transform-stampeds - cram-tf:*robot-torso-frame* - "end_effector_link" - torso-base-transform - base-ee-transform - :result-as-pose-or-transform :pose)) - (error "Arm movement goals should be given in robot base frame")))) - (get-ik-joint-positions (ee-pose base-link end-effector-link joint-names - torso-joint-name - torso-joint-lower-limit torso-joint-upper-limit) - (when ee-pose - (multiple-value-bind (ik-solution-msg torso-angle) - (let ((torso-current-angle - (btr:joint-state - (btr:get-robot-object) - torso-joint-name)) - (seed-state-msg - (btr::make-robot-joint-state-msg - (btr:get-robot-object) - :joint-names joint-names))) - (ik:call-ik-service-with-resampling - ee-pose base-link end-effector-link seed-state-msg *torso-resampling-step* :z - torso-current-angle torso-joint-lower-limit torso-joint-upper-limit)) - (unless ik-solution-msg - (cpl:fail 'common-fail:manipulation-pose-unreachable - :description (format nil "~a is unreachable for EE." ee-pose))) - (values (map 'list #'identity (roslisp:msg-slot-value ik-solution-msg :position)) - torso-angle))))) - - (let* ((bindings - (cut:lazy-car - (prolog:prolog - `(and (cram-robot-interfaces:robot ?robot) - (cram-robot-interfaces:robot-tool-frame ?robot :left ?left-tool-frame) - (cram-robot-interfaces:robot-tool-frame ?robot :right ?right-tool-frame) - (cram-robot-interfaces:end-effector-link ?robot :left ?left-ee-frame) - (cram-robot-interfaces:end-effector-link ?robot :right ?right-ee-frame) - (cram-robot-interfaces:arm-joints ?robot :left ?left-arm-joints) - (cram-robot-interfaces:arm-joints ?robot :right ?right-arm-joints) - (cram-robot-interfaces:robot-torso-link-joint ?robot ?torso-link ?torso-joint) - (cram-robot-interfaces:joint-lower-limit ?robot ?torso-joint ?lower-limit) - (cram-robot-interfaces:joint-upper-limit ?robot ?torso-joint ?upper-limit))))) - (left-tcp-frame - (cut:var-value '?left-tool-frame bindings)) - (right-tcp-frame - (cut:var-value '?right-tool-frame bindings)) - (left-ee-frame - (cut:var-value '?left-ee-frame bindings)) - (right-ee-frame - (cut:var-value '?right-ee-frame bindings)) - (left-arm-joints - (cut:var-value '?left-arm-joints bindings)) - (right-arm-joints - (cut:var-value '?right-arm-joints bindings)) - (torso-link-name - (cut:var-value '?torso-link bindings)) - (torso-joint-name - (cut:var-value '?torso-joint bindings)) - (torso-lower-limit - (cut:var-value '?lower-limit bindings)) - (torso-upper-limit - (cut:var-value '?upper-limit bindings))) - - (multiple-value-bind (left-ik left-torso-angle) - (get-ik-joint-positions (ee-pose-in-base->ee-pose-in-torso - (tcp-pose->ee-pose left-tcp-pose - left-tcp-frame left-ee-frame)) - torso-link-name left-ee-frame left-arm-joints - torso-joint-name torso-lower-limit torso-upper-limit) - (multiple-value-bind (right-ik right-torso-angle) - (get-ik-joint-positions (ee-pose-in-base->ee-pose-in-torso - (tcp-pose->ee-pose right-tcp-pose - right-tcp-frame right-ee-frame)) - torso-link-name right-ee-frame right-arm-joints - torso-joint-name torso-lower-limit torso-upper-limit) - (cond - ((and left-torso-angle right-torso-angle) - (when (not (eq left-torso-angle right-torso-angle)) - (cpl:fail 'common-fail:manipulation-pose-unreachable - :description (format nil "In MOVE-TCP goals for the two arms ~ - require different torso angles)."))) - (move-torso left-torso-angle)) - (left-torso-angle (move-torso left-torso-angle)) - (right-torso-angle (move-torso right-torso-angle))) - (move-joints left-ik right-ik)))))) diff --git a/cram_boxy/cram_boxy_projection/src/process-modules.lisp b/cram_boxy/cram_boxy_projection/src/process-modules.lisp deleted file mode 100644 index afba91f62d..0000000000 --- a/cram_boxy/cram_boxy_projection/src/process-modules.lisp +++ /dev/null @@ -1,120 +0,0 @@ -;;; -;;; Copyright (c) 2018, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software -;;; without specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :boxy-proj) - -;;;;;;;;;;;;;;;;; NAVIGATION ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(cpm:def-process-module boxy-proj-navigation (motion-designator) - (destructuring-bind (command argument) (desig:reference motion-designator) - (ecase command - (cram-common-designators:move-base - (handler-case - (drive argument)))))) - -;;;;;;;;;;;;;;;;; TORSO ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(cpm:def-process-module boxy-proj-torso (motion-designator) - (destructuring-bind (command argument) (desig:reference motion-designator) - (ecase command - (cram-common-designators:move-torso - (handler-case - (move-torso argument)))))) - -;;;;;;;;;;;;;;;;; PTU ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(cpm:def-process-module boxy-proj-ptu (motion-designator) - (destructuring-bind (command goal-pose goal-configuration) (desig:reference motion-designator) - (ecase command - (cram-common-designators:move-head - (handler-case - (look-at goal-pose goal-configuration)))))) - -;;;;;;;;;;;;;;;;; PERCEPTION ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(cpm:def-process-module boxy-proj-perception (motion-designator) - (destructuring-bind (command argument-1) (desig:reference motion-designator) - (ecase command - (cram-common-designators:detect - (handler-case - (detect argument-1)))))) - -;;;;;;;;;;;;;;;;; GRIPPERS ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(cpm:def-process-module boxy-proj-grippers (motion-designator) - (destructuring-bind (command arg-1 arg-2 &rest arg-3) (desig:reference motion-designator) - (ecase command - (cram-common-designators:move-gripper-joint - (handler-case - (gripper-action arg-1 arg-2 (car arg-3))))))) - -;;;;;;;;;;;;;;;;; ARMS ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(cpm:def-process-module boxy-proj-arms (motion-designator) - (destructuring-bind (command arg-1 &rest arg-2) (desig:reference motion-designator) - (ecase command - (cram-common-designators:move-tcp - (handler-case - (move-tcp arg-1 (car arg-2)))) - (cram-common-designators::move-joints - (handler-case - (move-joints arg-1 (car arg-2)))) - (cram-common-designators::move-with-constraints - (roslisp:ros-warn (boxy pms) "move-with-constraints is not supported") - ;; (handler-case - ;; (move-with-constraints arg-1)) - )))) - - -;;;;;;;;;;;;;;;;;;;;; PREDICATES ;;;;;;;;;;;;;;;;;;;;;;;; - -(def-fact-group boxy-matching-pms (cpm:matching-process-module) - - (<- (cpm:matching-process-module ?motion-designator boxy-proj-navigation) - (desig:desig-prop ?motion-designator (:type :going))) - - (<- (cpm:matching-process-module ?motion-designator boxy-proj-torso) - (desig:desig-prop ?motion-designator (:type :moving-torso))) - - (<- (cpm:matching-process-module ?motion-designator boxy-proj-ptu) - (desig:desig-prop ?motion-designator (:type :looking))) - - (<- (cpm:matching-process-module ?motion-designator boxy-proj-perception) - (desig:desig-prop ?motion-designator (:type :detecting))) - - (<- (cpm:matching-process-module ?motion-designator boxy-proj-grippers) - (or (desig:desig-prop ?motion-designator (:type :gripping)) - (desig:desig-prop ?motion-designator (:type :moving-gripper-joint)) - (desig:desig-prop ?motion-designator (:type :opening-gripper)) - (desig:desig-prop ?motion-designator (:type :closing-gripper)))) - - (<- (cpm:matching-process-module ?motion-designator boxy-proj-arms) - (or (desig:desig-prop ?motion-designator (:type :moving-tcp)) - (desig:desig-prop ?motion-designator (:type :moving-arm-joints)) - (desig:desig-prop ?motion-designator (:type :moving-with-constraints))))) diff --git a/cram_boxy/cram_boxy_projection/src/projection-environment.lisp b/cram_boxy/cram_boxy_projection/src/projection-environment.lisp deleted file mode 100644 index 214e418921..0000000000 --- a/cram_boxy/cram_boxy_projection/src/projection-environment.lisp +++ /dev/null @@ -1,130 +0,0 @@ -;;; Copyright (c) 2012, Lorenz Moesenlechner -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software -;;; without specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :boxy-proj) - -(defvar *last-timeline* nil) - -(cram-projection:define-projection-environment boxy-bullet-projection-environment - :special-variable-initializers - ((cram-tf:*transformer* - (make-instance 'cl-tf:transformer)) - ;; TODO: use custom tf topic "tf_sim" - ;; For that first change tf2_ros/TransformListener to accept custom topic names - ;; (*current-bullet-world* (cl-bullet:copy-world btr:*current-bullet-world*)) - (cram-bullet-reasoning:*current-timeline* - (btr:timeline-init btr:*current-bullet-world*)) - (desig:*default-role* - 'projection-role) - ;; (cut:*timestamp-function* #'projection-timestamp-function) - (cram-bullet-reasoning-belief-state::*object-identifier-to-instance-mappings* - (alexandria:copy-hash-table - cram-bullet-reasoning-belief-state::*object-identifier-to-instance-mappings*)) - (cet:*episode-knowledge* - cet:*episode-knowledge*)) - :process-module-definitions - (boxy-proj-navigation - boxy-proj-torso - boxy-proj-ptu - boxy-proj-perception - boxy-proj-grippers - boxy-proj-arms) - :startup (progn - (cram-bullet-reasoning-belief-state:set-tf-from-bullet) - (cram-bullet-reasoning-belief-state:update-bullet-transforms)) - :shutdown (setf *last-timeline* cram-bullet-reasoning:*current-timeline*)) - - -(def-fact-group boxy-available-pms (cpm:available-process-module - cpm:projection-running) - - (<- (cpm:available-process-module ?pm) - (bound ?pm) - (once (member ?pm (boxy-proj-navigation - boxy-proj-torso - boxy-proj-ptu - boxy-proj-perception - boxy-proj-grippers - boxy-proj-arms))) - (symbol-value cram-projection:*projection-environment* boxy-bullet-projection-environment)) - - (<- (cpm::projection-running ?pm) - ;; (bound ?pm) - (once (member ?pm (boxy-proj-navigation - boxy-proj-torso - boxy-proj-ptu - boxy-proj-perception - boxy-proj-grippers - boxy-proj-arms))) - (symbol-value cram-projection:*projection-environment* boxy-bullet-projection-environment))) - - -(defmacro with-simulated-robot (&body body) - `(let ((results - (proj:with-projection-environment boxy-bullet-projection-environment - (cpl-impl::named-top-level (:name :top-level) - ,@body)))) - (car (cram-projection::projection-environment-result-result results)))) - -(defmacro with-projected-robot (&body args) - "Alias for WITH-SIMULATED-ROBOT." - `(with-simulated-robot ,@args)) - - -#+below-is-a-very-simple-example-of-how-to-use-projection -( - (let ((robot (cl-urdf:parse-urdf (roslisp:get-param "robot_description"))) - (kitchen (cl-urdf:parse-urdf (roslisp:get-param "kitchen_description")))) - (prolog:prolog `(and - (btr:bullet-world ?w) - (btr:debug-window ?w) - (assert ?w (btr:object :static-plane floor ((0 0 0) (0 0 0 1)) - :normal (0 0 1) :constant 0)) - (assert ?w (btr:object :semantic-map sem-map ((0 0 0) (0 0 0 1)) - :urdf ,kitchen)) - (cram-robot-interfaces:robot ?robot) - (assert ?w (btr:object :urdf ?robot ((0 0 0) (0 0 0 1)) - :urdf ,robot))))) - - (ros-load-manifest:load-system "cram_executive" :cram-executive) - - (proj:with-projection-environment boxy-proj::boxy-bullet-projection-environment - (cpl:top-level - (exe:perform - (let ((?pose (cl-tf:make-pose-stamped - cram-tf:*robot-base-frame* 0.0 - (cl-transforms:make-3d-vector -4 -5 0) - (cl-transforms:make-identity-rotation)))) - (desig:a motion (type going) (pose ?pose)))) - (exe:perform - (let ((?pose (cl-tf:make-pose-stamped - cram-tf:*robot-base-frame* 0.0 - (cl-transforms:make-3d-vector 0.5 0.3 1.0) - (cl-transforms:make-identity-rotation)))) - (desig:a motion (type moving-tcp) (left-pose ?pose)))))) -) diff --git a/cram_common/cram_commander/src/action-designator-server.lisp b/cram_common/cram_commander/src/action-designator-server.lisp index 00efb3c231..cb67c5dbe5 100644 --- a/cram_common/cram_commander/src/action-designator-server.lisp +++ b/cram_common/cram_commander/src/action-designator-server.lisp @@ -31,7 +31,7 @@ ;; (defgeneric main () ;; (:method :before () -;; (let ((agent-ros-name (rosify (current-robot-symbol)))) +;; (let ((agent-ros-name (rosify (rob-int:get-robot-name)))) ;; (roslisp-utilities:startup-ros :name agent-ros-name)))) (defun try-reference-designator-json (designator-json-string) diff --git a/cram_common/cram_common_designators/src/motions.lisp b/cram_common/cram_common_designators/src/motions.lisp index a7cf334c96..4af4f28144 100644 --- a/cram_common/cram_common_designators/src/motions.lisp +++ b/cram_common/cram_common_designators/src/motions.lisp @@ -94,42 +94,85 @@ (<- (motion-grounding ?designator (move-tcp ?left-pose ?right-pose ?collision-mode - ?collision-object-b ?collision-object-b-link + ?collision-object-b + ?collision-object-b-link ?collision-object-a - ?move-the-ass)) + ?move-base ?prefer-base + ?align-planes-left + ?align-planes-right)) (property ?designator (:type :moving-tcp)) - (-> (property ?designator (:left-pose ?left-pose)) - (true) - (equal ?left-pose nil)) - (-> (property ?designator (:right-pose ?right-pose)) - (true) - (equal ?right-pose nil)) - (-> (desig:desig-prop ?designator (:collision-mode ?collision-mode)) - (true) - (equal ?collision-mode nil)) - (-> (desig:desig-prop ?designator (:collision-object-b ?collision-object-b)) - (true) - (equal ?collision-object-b nil)) - (-> (desig:desig-prop ?designator (:collision-object-b-link ?collision-object-b-link)) - (true) - (equal ?collision-object-b-link nil)) - (-> (desig:desig-prop ?designator (:collision-object-a ?collision-object-a)) - (true) - (equal ?collision-object-a nil)) - (-> (desig:desig-prop ?designator (:move-the-ass ?move-the-ass)) - (true) - (equal ?move-the-ass nil))) - - (<- (motion-grounding ?designator (move-joints ?left-config ?right-config)) + (once (or (property ?designator (:left-pose ?left-pose)) + (equal ?left-pose nil))) + (once (or (property ?designator (:right-pose ?right-pose)) + (equal ?right-pose nil))) + (once (or (desig:desig-prop ?designator (:collision-mode ?collision-mode)) + (equal ?collision-mode nil))) + (once (or (desig:desig-prop ?designator (:collision-object-b ?collision-object-b)) + (equal ?collision-object-b nil))) + (once (or (desig:desig-prop ?designator (:collision-object-b-link + ?collision-object-b-link)) + (equal ?collision-object-b-link nil))) + (once (or (desig:desig-prop ?designator (:collision-object-a ?collision-object-a)) + (equal ?collision-object-a nil))) + (once (or (desig:desig-prop ?designator (:move-base ?move-base)) + (equal ?move-base nil))) + (once (or (desig:desig-prop ?designator (:prefer-base ?prefer-base)) + (equal ?prefer-base nil))) + (once (or (desig:desig-prop ?designator (:align-planes-left ?align-planes-left)) + (equal ?align-planes-left nil))) + (once (or (desig:desig-prop ?designator (:align-planes-right ?align-planes-right)) + (equal ?align-planes-right nil)))) + + (<- (motion-grounding ?designator (?push-or-pull ?arm ?poses + ?joint-angle + ?collision-mode + ?collision-object-b + ?collision-object-b-link + ?collision-object-a + ?move-base ?prefer-base + ?align-planes-left + ?align-planes-right)) + (or (and (property ?designator (:type :pushing)) + (equal ?push-or-pull move-arm-push)) + (and (property ?designator (:type :pulling)) + (equal ?push-or-pull move-arm-pull))) + (property ?designator (:arm ?arm)) + (property ?designator (:poses ?poses)) + (once (or (desig:desig-prop ?designator (:joint-angle ?joint-angle)) + (equal ?joint-angle nil))) + (once (or (desig:desig-prop ?designator (:collision-mode ?collision-mode)) + (equal ?collision-mode nil))) + (once (or (desig:desig-prop ?designator (:collision-object-b ?collision-object-b)) + (equal ?collision-object-b nil))) + (once (or (desig:desig-prop ?designator (:collision-object-b-link + ?collision-object-b-link)) + (equal ?collision-object-b-link nil))) + (once (or (desig:desig-prop ?designator (:collision-object-a ?collision-object-a)) + (equal ?collision-object-a nil))) + (once (or (desig:desig-prop ?designator (:move-base ?move-base)) + (equal ?move-base nil))) + (once (or (desig:desig-prop ?designator (:prefer-base ?prefer-base)) + (equal ?prefer-base nil))) + (once (or (desig:desig-prop ?designator (:align-planes-left ?align-planes-left)) + (equal ?align-planes-left nil))) + (once (or (desig:desig-prop ?designator (:align-planes-right ?align-planes-right)) + (equal ?align-planes-right nil)))) + + (<- (motion-grounding ?designator (move-joints ?left-config ?right-config + ?collision-mode + ?align-planes-left + ?align-planes-right)) (property ?designator (:type :moving-arm-joints)) (once (or (property ?designator (:left-joint-states ?left-config)) (equal ?left-config nil))) (once (or (property ?designator (:right-joint-states ?right-config)) - (equal ?right-config nil)))) - - (<- (motion-grounding ?designator (move-with-constraints ?constraints-string)) - (property ?designator (:type :moving-with-constraints)) - (property ?designator (:constraints ?constraints-string)))) + (equal ?right-config nil))) + (once (or (property ?designator (:collision-mode ?collision-mode)) + (equal ?collision-mode nil))) + (once (or (property ?designator (:align-planes-left ?align-planes-left)) + (equal ?align-planes-left nil))) + (once (or (property ?designator (:align-planes-right ?align-planes-right)) + (equal ?align-planes-right nil))))) (def-fact-group world-state-detecting (motion-grounding) @@ -141,3 +184,37 @@ (property ?object-designator (:type ?_)) (property ?object-designator (:name ?_))) (property ?object-designator (:name ?_))))) + + + +#+wiggling-stuff +( + (defun calculate-pose-from-direction (distance) + (let* ((left-pose + (cl-transforms-stamped:make-pose-stamped + cram-tf:*robot-left-tool-frame* + 0.0 + (cl-transforms:make-3d-vector 0.0 0.0 distance) + (cl-transforms:make-identity-rotation)))) + left-pose)) + + (def-fact-group boxy-motion-designators (desig:motion-grounding) + + (<- (desig:motion-grounding ?designator (move-tcp-wiggle ?arm ?pose)) + (property ?designator (:type :wiggling-tcp)) + (property ?designator (:arm ?arm)) + (property ?designator (:target ?location-designator)) + (desig:designator-groundings ?location-designator ?poses) + (member ?pose ?poses)) + + (<- (desig:motion-grounding ?designator (move-tcp-wiggle :left ?pose)) + (property ?designator (:type :wiggling-tcp)) + ;; (property ?designator (:arm ?arm)) + ;; (property ?designator (:direction ?direction-keyword)) + ;; (property ?designator (:frame ?reference-frame)) + (property ?designator (:arm :left)) + (property ?designator (:direction :forward)) + (property ?designator (:distance ?distance)) + (lisp-fun calculate-pose-from-direction ?distance ;; ?arm ?direction-keyword ?reference-frame + ?pose))) + ) diff --git a/cram_common/cram_common_designators/src/package.lisp b/cram_common/cram_common_designators/src/package.lisp index 2721122347..931ba3ebb8 100644 --- a/cram_common/cram_common_designators/src/package.lisp +++ b/cram_common/cram_common_designators/src/package.lisp @@ -1,19 +1,20 @@ +;;; ;;; Copyright (c) 2012, Lorenz Moesenlechner ;;; All rights reserved. -;;; +;;; ;;; Redistribution and use in source and binary forms, with or without ;;; modification, are permitted provided that the following conditions are met: -;;; +;;; ;;; * Redistributions of source code must retain the above copyright ;;; notice, this list of conditions and the following disclaimer. ;;; * Redistributions in binary form must reproduce the above copyright ;;; notice, this list of conditions and the following disclaimer in the ;;; documentation and/or other materials provided with the distribution. ;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software ;;; without specific prior written permission. -;;; +;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" ;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE ;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE @@ -29,13 +30,9 @@ (in-package :cl-user) (defpackage cram-common-designators - (:use #:common-lisp ;#:cram-plan-occasions-events #:cram-robot-interfaces - #:prolog #:desig #:spec ;; #:cram-semantic-map - ;; #:cl-transforms-stamped - ) - ;; (:import-from #:cram-tf - ;; *fixed-frame* *transformer* *tf-default-timeout*) + (:use #:common-lisp #:prolog #:desig #:spec) (:export ;; motions #:move-base #:move-torso #:move-head #:detect #:inspect #:move-gripper-joint - #:move-tcp #:move-joints #:move-with-constraints #:world-state-detect)) + #:move-tcp #:move-arm-push #:move-arm-pull #:move-joints #:move-with-constraints + #:world-state-detect)) diff --git a/cram_boxy/cram_boxy_plans/cram-boxy-plans.asd b/cram_common/cram_common_failures/cram-common-failures-tests.asd similarity index 72% rename from cram_boxy/cram_boxy_plans/cram-boxy-plans.asd rename to cram_common/cram_common_failures/cram-common-failures-tests.asd index 446eea2fba..b5990fc5e7 100644 --- a/cram_boxy/cram_boxy_plans/cram-boxy-plans.asd +++ b/cram_common/cram_common_failures/cram-common-failures-tests.asd @@ -1,4 +1,4 @@ -;;; Copyright (c) 2017, Gayane Kazhoyan +;;; Copyright (c) 2020, Amar Fayaz ;;; All rights reserved. ;;; ;;; Redistribution and use in source and binary forms, with or without @@ -10,8 +10,8 @@ ;;; notice, this list of conditions and the following disclaimer in the ;;; documentation and/or other materials provided with the distribution. ;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software ;;; without specific prior written permission. ;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" @@ -26,33 +26,31 @@ ;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE ;;; POSSIBILITY OF SUCH DAMAGE. -(defsystem cram-boxy-plans - :author "Gayane Kazhoyan" - :maintainer "Gayane Kazhoyan" +(defsystem cram-common-failures-tests + :author "Amar Fayaz" :license "BSD" - :depends-on (roslisp ; for debug statements - - cram-designators - cram-executive + :depends-on (lisp-unit + roslisp cram-language cram-prolog - cram-occasions-events - - cram-designator-specification + cl-urdf cram-common-failures - cram-plan-occasions-events - cram-mobile-pick-place-plans - - cram-manipulation-interfaces + cram-bullet-reasoning + cram-pr2-description + cram-robot-interfaces + cl-transforms + cl-transforms-stamped + cram-designators cram-object-knowledge + cram-location-costmap + cram-btr-visibility-costmap + cram-btr-spatial-relations-costmap + cram-occupancy-grid-costmap + cram-robot-pose-gaussian-costmap) - cl-transforms-stamped - cl-transforms) :components - ((:module "src" + ((:module "tests" :components ((:file "package") - (:file "action-plans" :depends-on ("package")) - (:file "action-designators" :depends-on ("package" "action-plans")) - (:file "high-level-plans" :depends-on ("package" "action-designators")))))) + (:file "different-location-solution-test" :depends-on ("package")))))) diff --git a/cram_common/cram_common_failures/src/failure-handling-strategies.lisp b/cram_common/cram_common_failures/src/failure-handling-strategies.lisp index 2da91b40bf..ba8b3ba860 100644 --- a/cram_common/cram_common_failures/src/failure-handling-strategies.lisp +++ b/cram_common/cram_common_failures/src/failure-handling-strategies.lisp @@ -29,6 +29,9 @@ (in-package :common-fail) +(defparameter *default-distance-threshold* 0.05 + "Distance threshold used as a default for identifying unique poses") + (defmacro retry-with-designator-solutions (iterator-desig retries (&key @@ -78,7 +81,8 @@ after each iteration of the retry." `(progn (roslisp:ros-warn ,warning-namespace "~a" ,error-object-or-string) (cpl:do-retry ,retries - (let ((next-solution-element (cut:lazy-car (cut:lazy-cdr ,iterator-list)))) + (let ((next-solution-element + (cut:lazy-car (cut:lazy-cdr ,iterator-list)))) (if next-solution-element (progn (roslisp:ros-warn ,warning-namespace "Retrying.~%") @@ -91,7 +95,9 @@ after each iteration of the retry." (cpl:fail ,rethrow-failure)))) (defun next-different-location-solution (designator - &optional (distance-threshold 0.05)) + &optional + (distance-threshold + *default-distance-threshold*)) "Returns a new designator solution that is at a different place than the current solution of `designator'." (declare (type desig:location-designator designator)) @@ -106,7 +112,8 @@ after each iteration of the retry." error-object-or-string warning-namespace reset-designators - (distance-threshold 0.05) + (distance-threshold + *default-distance-threshold*) (rethrow-failure NIL)) &body body) "Macro that iterates through different solutions of the specified diff --git a/cram_common/cram_common_failures/src/manipulation.lisp b/cram_common/cram_common_failures/src/manipulation.lisp index d90d5e2a90..5f4bcfc3e5 100644 --- a/cram_common/cram_common_failures/src/manipulation.lisp +++ b/cram_common/cram_common_failures/src/manipulation.lisp @@ -37,7 +37,7 @@ (define-condition manipulation-pose-unreachable (manipulation-low-level-failure) () (:documentation "Thrown when no IK solution can be found.")) -(define-condition gripper-low-level-failure (manipulation-low-level-failure) +(define-condition gripper-low-level-failure (low-level-failure) ((action :initarg :object :initform nil :reader gripper-failure-action))) (define-condition gripper-closed-completely (gripper-low-level-failure) ()) diff --git a/cram_common/cram_common_failures/tests/different-location-solution-test.lisp b/cram_common/cram_common_failures/tests/different-location-solution-test.lisp new file mode 100644 index 0000000000..5204bac343 --- /dev/null +++ b/cram_common/cram_common_failures/tests/different-location-solution-test.lisp @@ -0,0 +1,104 @@ +;;; +;;; Copyright (c) 2020, Amar Fayaz +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :cram-common-failures-tests) + +(defparameter *target-location* (cl-transforms-stamped:make-pose-stamped + "map" + 0.0 + (cl-transforms:make-3d-vector 0 1 0) + (cl-transforms:make-quaternion 0 0 0 1))) + +(defparameter *test-location* (let ((?target *target-location*)) + (desig:a location + (reachable-for pr2) + (location (desig:a location + (pose ?target)))))) + +(defun setup-world () + (setf rob-int:*robot-urdf* + (cl-urdf:parse-urdf + (roslisp:get-param rob-int:*robot-description-parameter*))) + (prolog:prolog + `(and (btr:bullet-world ?world) + (rob-int:robot ?robot) + (assert (btr:object ?world :urdf ?robot ((0 0 0) (0 0 0 1)) + :urdf ,rob-int:*robot-urdf*)))) + (btr:detach-all-objects (btr:get-robot-object))) + + +;; roslaunch cram_pr2_pick_place_demo sandbox.launch + +(define-test next-different-location-solution-test + (unless (eq roslisp::*node-status* :RUNNING) + (roslisp-utilities:startup-ros)) + (setup-world) + (let ((first-location (desig:reference *test-location*)) + (new-location (desig:reference + (common-fail:next-different-location-solution + *test-location*)))) + (assert-true (< cram-common-failures::*default-distance-threshold* + (cl-transforms:v-dist + (cl-transforms:origin first-location) + (cl-transforms:origin new-location)))))) + + +(define-test retry-with-diff-loc-designator-test + (unless (eq roslisp::*node-status* :RUNNING) + (roslisp-utilities:startup-ros)) + (setup-world) + (let ((location-output)) + (assert-error 'common-fail:object-nowhere-to-be-found + (cpl:with-retry-counters ((robot-location-retries 8)) + (cpl:with-failure-handling + (((or common-fail:navigation-goal-in-collision + common-fail:looking-high-level-failure + common-fail:perception-low-level-failure) (e) + (common-fail:retry-with-loc-designator-solutions + *test-location* + robot-location-retries + (:error-object-or-string e + :warning-namespace + (fd-plans search-for-object) + :rethrow-failure + 'common-fail:object-nowhere-to-be-found) + (push + (desig:reference *test-location*) + location-output)))) + (cpl:fail 'common-fail:looking-high-level-failure)))) + + (assert-true (eq 8 (length location-output))) + (maplist (lambda (pose-list) + (when (>= (length pose-list) 2) + (assert-true + (< cram-common-failures::*default-distance-threshold* + (cl-transforms:v-dist + (cl-transforms:origin (first pose-list)) + (cl-transforms:origin (second pose-list))))))) + location-output))) diff --git a/cram_boxy/cram_boxy_plans/src/package.lisp b/cram_common/cram_common_failures/tests/package.lisp similarity index 89% rename from cram_boxy/cram_boxy_plans/src/package.lisp rename to cram_common/cram_common_failures/tests/package.lisp index 55b59a50d6..3f16b401e5 100644 --- a/cram_boxy/cram_boxy_plans/src/package.lisp +++ b/cram_common/cram_common_failures/tests/package.lisp @@ -1,5 +1,5 @@ ;;; -;;; Copyright (c) 2017, Gayane Kazhoyan +;;; Copyright (c) 2020, Amar Fayaz ;;; All rights reserved. ;;; ;;; Redistribution and use in source and binary forms, with or without @@ -29,7 +29,7 @@ (in-package :cl-user) -(defpackage cram-boxy-plans - (:nicknames #:boxy-plans) - (:use #:common-lisp #:cram-prolog #:cram-designator-specification) +(defpackage cram-common-failures-tests + (:nicknames :common-fail-tests) + (:use #:common-lisp #:cram-common-failures #:lisp-unit) (:export)) diff --git a/cram_common/cram_designator_specification/src/specs.lisp b/cram_common/cram_designator_specification/src/specs.lisp index cabfa57b13..b5719a2fd9 100644 --- a/cram_common/cram_designator_specification/src/specs.lisp +++ b/cram_common/cram_designator_specification/src/specs.lisp @@ -89,7 +89,7 @@ (<- (%property ?designator (?list-key ?value)) (lisp-pred typep ?designator desig:motion-designator) - (member ?list-key (:joint-states :left-joint-states :right-joint-states)) + (member ?list-key (:poses :joint-states :left-joint-states :right-joint-states)) (property-member (?list-key ?value) ?designator) (assert-type ?value list "MOTION SPEC:PROPERTY"))) @@ -104,21 +104,22 @@ (<- (%property ?designator (?list-key ?value)) (lisp-pred typep ?designator desig:action-designator) - (member ?list-key (:left-poses :right-poses)) + (member ?list-key (:poses :left-poses :right-poses :arms :grasps)) (property-member (?list-key ?value) ?designator) (assert-type ?value list "ACTION SPEC:PROPERTY")) (<- (%property ?designator (?keyword-or-list-key ?value)) (lisp-pred typep ?designator desig:action-designator) (member ?keyword-or-list-key (:gripper :arm :direction :grasp :camera :type - :link :configuration + :context :link :configuration :left-configuration :right-configuration)) (property-member (?keyword-or-list-key ?value) ?designator) (assert-type ?value (or keyword list) "ACTION SPEC:PROPERTY")) (<- (%property ?designator (?object-key ?object)) (lisp-pred typep ?designator desig:action-designator) - (member ?object-key (:object :on-object :with-object :supporting-object :container-object)) + (member ?object-key (:object :on-object :with-object :supporting-object + :container-object)) (property-member (?object-key ?object) ?designator) (assert-type ?object desig:object-designator "ACTION SPEC:PROPERTY")) @@ -128,18 +129,17 @@ (property-member (?number-key ?value) ?designator) (assert-type ?value number "ACTION SPEC:PROPERTY")) - (<- (%property ?designator (?number-key ?value)) - (lisp-pred typep ?designator desig:action-designator) - (member ?number-key (:joint-angle)) - (property-member (?number-key ?value) ?designator) - (assert-type ?value (or keyword number) "MOTION SPEC:PROPERTY")) - (<- (%property ?designator (?string-key ?value)) (lisp-pred typep ?designator desig:action-designator) (member ?string-key (:frame)) (property-member (?string-key ?value) ?designator) (assert-type ?value string "ACTION SPEC:PROPERTY")) + (<- (%property ?designator (:joint-angle ?value)) + (lisp-pred typep ?designator desig:action-designator) + (property-member (:joint-angle ?value) ?designator) + (assert-type ?value (or keyword number) "ACTION SPEC:PROPERTY")) + (<- (%property ?designator (:for ?for-value)) (lisp-pred typep ?designator desig:action-designator) (property-member (:for ?for-value) ?designator) @@ -153,16 +153,32 @@ (property-member (:pose ?pose-stamped) ?designator) (assert-type ?pose-stamped cl-transforms-stamped:pose-stamped "LOCATION SPEC:PROPERTY")) - (<- (%property ?designator (:object ?value)) + (<- (%property ?designator (?list-key ?list-value)) (lisp-pred typep ?designator desig:location-designator) - (property-member (:object ?value) ?designator) + (member ?list-key (:poses :attachments)) + (property-member (?list-key ?list-value) ?designator) + (assert-type ?list-value list "LOCATION SPEC:PROPERTY")) + + (<- (%property ?designator (?object-desig-key ?value)) + (lisp-pred typep ?designator desig:location-designator) + (member ?object-desig-key (:object + :in :on :above + :left-of :right-of :in-front-of :behind + :far-from :near)) + (property-member (?object-desig-key ?value) ?designator) (assert-type ?value desig:object-designator "LOCATION SPEC:PROPERTY")) (<- (%property ?designator (?keyword-key ?value)) (lisp-pred typep ?designator desig:location-designator) - (member ?keyword-key (:arm)) + (member ?keyword-key (:arm :attachment)) (property-member (?keyword-key ?value) ?designator) - (assert-type ?value keyword "LOCATION SPEC:PROPERTY"))) + (assert-type ?value keyword "LOCATION SPEC:PROPERTY")) + + (<- (%property ?designator (?number-key ?value)) + (lisp-pred typep ?designator desig:location-designator) + (member ?number-key (:z-offset)) + (property-member (?number-key ?value) ?designator) + (assert-type ?value number "LOCATION SPEC:PROPERTY"))) (def-fact-group object-designator-specs (%property) @@ -178,10 +194,10 @@ (property-member (?keyword-key ?name) ?designator) (assert-type ?name symbol "OBJECT SPEC:PROPERTY")) - (<- (%property ?designator (:part-of ?environment)) + (<- (%property ?designator (:part-of ?environment-or-robot)) (lisp-pred typep ?designator desig:object-designator) - (property-member (:part-of ?environment) ?designator) - (assert-type ?environment keyword "OBJECT SPEC:PROPERTY")) + (property-member (:part-of ?environment-or-robot) ?designator) + (assert-type ?environment-or-robot symbol "OBJECT SPEC:PROPERTY")) (<- (%property ?designator (:handle-axis ?axis)) (lisp-pred typep ?designator desig:object-designator) @@ -191,4 +207,9 @@ (<- (%property ?designator (:pose ?pose)) (lisp-pred typep ?designator desig:object-designator) (property-member (:pose ?pose) ?designator) - (assert-type ?pose list "OBEJCT SPEC:PROPERTY"))) + (assert-type ?pose list "OBEJCT SPEC:PROPERTY")) + + (<- (%property ?designator (:location ?location)) + (lisp-pred typep ?designator desig:object-designator) + (property-member (:location ?location) ?designator) + (assert-type ?location desig:location-designator "OBJECT SPEC:PROPERTY"))) diff --git a/cram_common/cram_location_costmap/cram-location-costmap.asd b/cram_common/cram_location_costmap/cram-location-costmap.asd index 8068cd2586..c7c56db659 100644 --- a/cram_common/cram_location_costmap/cram-location-costmap.asd +++ b/cram_common/cram_location_costmap/cram-location-costmap.asd @@ -61,4 +61,6 @@ (:file "ros-grid-cells" :depends-on ("package" "2d-value-map")) (:file "ros-occupancy-grid" :depends-on ("package")) (:file "visualization" - :depends-on ("package" "occupancy-grid" "location-costmap")))))) + :depends-on ("package" "occupancy-grid" "location-costmap")) + ;; implemented for optimizing costmaps but not integrated yet + (:file "quadtree" :depends-on ("package")))))) diff --git a/cram_common/cram_location_costmap/src/designator-integration.lisp b/cram_common/cram_location_costmap/src/designator-integration.lisp index fa2763e5cc..28b9d6e6bc 100644 --- a/cram_common/cram_location_costmap/src/designator-integration.lisp +++ b/cram_common/cram_location_costmap/src/designator-integration.lisp @@ -35,6 +35,9 @@ (defvar *costmap-cache* (tg:make-weak-hash-table :test 'eq :weakness :key)) (defvar *costmap-max-values (tg:make-weak-hash-table :test 'eq :weakness :key)) +(defun reset-costmap-cache () + (setf *costmap-cache* (tg:make-weak-hash-table :test 'eq :weakness :key))) + (defun get-cached-costmap (desig) (let ((first-designator (first-desig desig))) (or (gethash first-designator *costmap-cache*) @@ -79,17 +82,27 @@ (get-cached-costmap-maxvalue cm)))) (if (> costmap-value *costmap-valid-solution-threshold*) (let ((costmap-heights - (generate-heights cm (cl-transforms:x p) (cl-transforms:y p)))) + (generate-heights + cm + (cl-transforms:x p) + (cl-transforms:y p)))) (cond ((not costmap-heights) :accept) ((find-if (lambda (height) + ;; The z of the pose has to be within + ;; 1 cm of the costmap heights (< (abs (- height (cl-transforms:z p))) - 1e-3)) + 1e-2)) costmap-heights) - :accept))) + :accept) + (t + :reject))) :reject)) (cma:invalid-probability-distribution () - :maybe-reject))) + :maybe-reject) + (error (e) + (warn "[BTR:LOCATION-COSTMAP-POSE-VALIDATOR] Error: ~A~%" e) + :unknown))) :unknown)) diff --git a/cram_common/cram_location_costmap/src/facts.lisp b/cram_common/cram_location_costmap/src/facts.lisp index 20b0c36adc..c2656506c3 100644 --- a/cram_common/cram_location_costmap/src/facts.lisp +++ b/cram_common/cram_location_costmap/src/facts.lisp @@ -39,11 +39,13 @@ ;;; ...) ;;; examples are in table_costmap and semantic_map_costmap -(defun make-angle-to-point-generator (position &key (samples 1) sample-step) +(defun make-angle-to-point-generator (position + &key (samples 1) sample-step sample-offset) "Returns a function that takes an X and Y coordinate and returns a lazy-list of quaternions to face towards `position'" (make-orientation-generator (alexandria:rcurry #'angle-to-point-direction position) - :samples samples :sample-step sample-step)) + :samples samples :sample-step sample-step + :sample-offset sample-offset)) (defun angle-to-point-direction (x y position) "Returns a function that takes an X and Y coordinate and returns a @@ -52,23 +54,30 @@ quaternion to face towards `position'" (cl-transforms:pose (cl-transforms:origin position)) (cl-transforms:3d-vector position))) (p-rel (cl-transforms:v- point (cl-transforms:make-3d-vector x y 0)))) - (atan (cl-transforms:y p-rel) (cl-transforms:x p-rel)))) + (cl-transforms:normalize-angle + (atan (cl-transforms:y p-rel) (cl-transforms:x p-rel))))) -(defun make-orientation-generator (main-direction-function &key (samples 1) sample-step) +(defun make-orientation-generator (main-direction-function + &key (samples 1) sample-step sample-offset) "Returns a lazy-list of quaternions around the main direction generated by `main-direction-function' if PREVIOUS-ORIENTATION is NIL, otherwise PREVIOUS-ORIENTATION. `samples' indicates how many rotations should be returned. -If the value is greater than 1, the samples' orientations differ by `sample-step'." +If the value is greater than 1, the samples' orientations differ by `sample-step'. +The order is random, so the main direction is NOT prioritized." (flet ((make-angles (samples sample-step) - (cons (cl-transforms:euler->quaternion :az 0.0d0) - (loop for angle from sample-step - below (* sample-step (ceiling (/ samples 2))) - by sample-step - appending (list (cl-transforms:euler->quaternion :az angle) - (cl-transforms:euler->quaternion :az (- angle))))))) + (alexandria:shuffle + (cons + (cl-transforms:euler->quaternion :az (or sample-offset 0.0d0)) + (loop + for angle from sample-step + below (* sample-step (ceiling (/ samples 2))) + by sample-step + appending (list (cl-transforms:euler->quaternion :az angle) + (cl-transforms:euler->quaternion :az (- angle)))))))) (let ((angle-differences (if (and sample-step (> samples 1)) (make-angles samples sample-step) - (list (cl-transforms:make-identity-rotation))))) + (list (cl-transforms:euler->quaternion + :az (or sample-offset 0.0d0)))))) (lambda (x y previous-orientations) (or previous-orientations (let ((angle (funcall main-direction-function x y))) @@ -168,58 +177,66 @@ If the value is greater than 1, the samples' orientations differ by `sample-step (def-fact-group location-costmap-metadata (costmap-size costmap-origin costmap-resolution - orientation-samples orientation-sample-step - costmap-padding costmap-manipulation-padding + orientation-samples + orientation-sample-step + reachability-orientation-offset + costmap-padding + costmap-manipulation-padding costmap-in-reach-distance costmap-reach-minimal-distance visibility-costmap-size) ;; costmap dimensions in meters, diameter not radius ;; depends on the size of the environment the robot operates in - (<- (costmap-size ?width ?height) + (<- (costmap-size ?environment-name ?width ?height) (fail)) ;; the coordinate of the left bottom corner of the costmap in meters in map frame ;; depends on the environment - (<- (costmap-origin ?x ?y) + (<- (costmap-origin ?environment-name ?x ?y) (fail)) ;; size of one costmap cell in meters ;; the smaller the number the higher the accuracy and the slower the algorithms - (<- (costmap-resolution ?resolution) + (<- (costmap-resolution ?environment-name ?resolution) (fail)) ;; number of orientations to generate for orientation generators ;; mostly used in gaussian-cm - (<- (orientation-samples ?samples) + (<- (orientation-samples ?robot-name ?samples) (fail)) ;; when generating ORIENTATION-SAMPLES number of samples, ;; what should be the distance between different samples in radians - (<- (orientation-sample-step ?step-in-radian) + (<- (orientation-sample-step ?robot-name ?step-in-radian) + (fail)) + + ;; when generating ORIENTATION-SAMPLES number of samples, + ;; what should be the angle offset from looking directly at target + (<- (reachability-orientation-offset ?robot-name ?offset-in-radian) (fail)) ;; padding offset from obstacles, depends on the robot base dimension ;; mostly used for visibility - (<- (costmap-padding ?padding-in-meters) + (<- (costmap-padding ?robot-name ?padding-in-meters) (fail)) ;; padding offset from obstacles when manipulating objects ;; can be different from COSTMAP-PADDING if the arm needs extra padding when grasping - (<- (costmap-manipulation-padding ?padding-in-meters) + (<- (costmap-manipulation-padding ?robot-name ?padding-in-meters) (fail)) ;; maximum length at which a robot can reach an object from its base location - (<- (costmap-in-reach-distance ?distance-in-meters) + (<- (costmap-in-reach-distance ?robot-name ?distance-in-meters) (fail)) ;; minimum distance from which the robot can reach an object from its base location ;; actually should probably be merged with COSTMAP-MANIPULATION-PADDING ;; at least the numbers should be very close to each other - (<- (costmap-reach-minimal-distance ?distance-in-meters) + (<- (costmap-reach-minimal-distance ?robot-name ?distance-in-meters) (fail)) ;; maximum distance from which the robot can perceive an object ;; i.e. the radius of the visibility gaussian costmap - (<- (visibility-costmap-size ?radius-in-meters) + (<- (visibility-costmap-size ?robot-name ?radius-in-meters) (fail))) diff --git a/cram_common/cram_location_costmap/src/location-costmap.lisp b/cram_common/cram_location_costmap/src/location-costmap.lisp index 295a293065..ea706f471a 100644 --- a/cram_common/cram_location_costmap/src/location-costmap.lisp +++ b/cram_common/cram_location_costmap/src/location-costmap.lisp @@ -108,7 +108,7 @@ (defgeneric costmap-generator-name->score (name) (:documentation "Returns the score for the costmap generator with - name `name'. Greater scores result in earlier evaluation.") + name `name'. Greater scores result in later evaluation.") (:method ((name number)) name)) @@ -125,7 +125,7 @@ calls the generator functions and runs normalization." (setf (slot-value map 'cost-functions) (sort (remove-duplicates (slot-value map 'cost-functions) :key #'generator-name) - #'> :key (compose + #'< :key (compose #'costmap-generator-name->score #'generator-name))) (let ((new-cost-map (cma:make-double-matrix diff --git a/cram_common/cram_location_costmap/src/location-prolog-handlers.lisp b/cram_common/cram_location_costmap/src/location-prolog-handlers.lisp index e29980cf32..cc07f492b5 100644 --- a/cram_common/cram_location_costmap/src/location-prolog-handlers.lisp +++ b/cram_common/cram_location_costmap/src/location-prolog-handlers.lisp @@ -1,10 +1,10 @@ ;;; ;;; Copyright (c) 2010, Lorenz Moesenlechner ;;; All rights reserved. -;;; +;;; ;;; Redistribution and use in source and binary forms, with or without ;;; modification, are permitted provided that the following conditions are met: -;;; +;;; ;;; * Redistributions of source code must retain the above copyright ;;; notice, this list of conditions and the following disclaimer. ;;; * Redistributions in binary form must reproduce the above copyright @@ -13,7 +13,7 @@ ;;; * Neither the name of Willow Garage, Inc. nor the names of its ;;; contributors may be used to endorse or promote products derived from ;;; this software without specific prior written permission. -;;; +;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" ;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE ;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE @@ -31,14 +31,20 @@ (defun costmap-metadata () (with-vars-bound (?width ?height ?resolution ?origin-x ?origin-y) - (lazy-car (prolog `(and (costmap-size ?width ?height) - (costmap-origin ?origin-x ?origin-y) - (costmap-resolution ?resolution)))) - (check-type ?width number) - (check-type ?height number) - (check-type ?resolution number) - (check-type ?origin-x number) - (check-type ?origin-y number) + (lazy-car (prolog `(and (rob-int:environment-name ?environment) + (costmap-size ?environment ?width ?height) + (costmap-origin ?environment ?origin-x ?origin-y) + (costmap-resolution ?environment ?resolution)))) + (unless (and (typep ?width 'number) + (typep ?height 'number) + (typep ?resolution 'number) + (typep ?origin-x 'number) + (typep ?origin-y 'number)) + (error "[CM:COSTMAP-METADATA] environment metadata is not defined.~%~ + Has the name of the environment in the URDF change~%~ + and you don't have the newest version? To check call~%~ + (rob-int:get-environment-name) and see if there is a + COSTMAP:COSTMAP-SIZE predicate defined anywhere for this name.")) (list :width ?width :height ?height :resolution ?resolution :origin-x ?origin-x :origin-y ?origin-y))) diff --git a/cram_common/cram_location_costmap/src/package.lisp b/cram_common/cram_location_costmap/src/package.lisp index 7e83cf1ebf..374e4d187b 100644 --- a/cram_common/cram_location_costmap/src/package.lisp +++ b/cram_common/cram_location_costmap/src/package.lisp @@ -1,10 +1,10 @@ ;;; ;;; Copyright (c) 2010, Lorenz Moesenlechner ;;; All rights reserved. -;;; +;;; ;;; Redistribution and use in source and binary forms, with or without ;;; modification, are permitted provided that the following conditions are met: -;;; +;;; ;;; * Redistributions of source code must retain the above copyright ;;; notice, this list of conditions and the following disclaimer. ;;; * Redistributions in binary form must reproduce the above copyright @@ -13,7 +13,7 @@ ;;; * Neither the name of Willow Garage, Inc. nor the names of its ;;; contributors may be used to endorse or promote products derived from ;;; this software without specific prior written permission. -;;; +;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" ;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE ;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE @@ -109,8 +109,27 @@ #:costmap-in-reach-distance #:costmap-reach-minimal-distance #:visibility-costmap-size #:orientation-samples #:orientation-sample-step + #:reachability-orientation-offset ;; facts #:make-angle-to-point-generator #:make-orientation-generator - #:2d-pose-covariance) + #:2d-pose-covariance + ;; designator-integration + #:reset-costmap-cache + ;; quadtree + #:make-quadtree-internal + #:make-quadtree + #:matrix->quadtree + ;; these are too generic names, should be prefixed with quadtree- or smt + ;; #:boundary + ;; #:insert + ;; #:query + ;; #:object-equal + ;; #:same-coords-as + ;; #:point-intersect-p + #:clear-quadtree + #:get-in-quadtree + #:merge-quadtrees + #:normalize-quadtree + #:quadtree-map) (:import-from #:cram-math invalid-probability-distribution)) diff --git a/cram_common/cram_location_costmap/src/quadtree.lisp b/cram_common/cram_location_costmap/src/quadtree.lisp new file mode 100644 index 0000000000..7637786f7e --- /dev/null +++ b/cram_common/cram_location_costmap/src/quadtree.lisp @@ -0,0 +1,838 @@ +;;; +;;; Copyright (c) 2019, Thomas Lipps +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. +;;; + +(in-package :location-costmap) + +;; --------------------- BASE ------------------------ + +(defvar *max-depth* 50) +(defvar *middlepoint-offset* 0.00001) ;; [mm/10] + +(defstruct (quadtree (:constructor %make-quadtree)) + object + nw ne sw se + boundary + depth + max-depth) + +(defun make-quadtree (x0 y0 x1 y1 &key (max-depth *max-depth*)) + (%make-quadtree-internal x0 y0 x1 y1 0 max-depth)) + +(defun %make-quadtree-internal (x0 y0 x1 y1 depth max-depth) + ;; do not use this: use make-quadtree instead! + (declare (float x0 y0 x1 y1)) + (unless (<= 0 depth max-depth) + (error "The value ~S is an linvalid value as depth." depth)) + (%make-quadtree :boundary (list x0 y0 x1 y1) + :depth depth + :max-depth max-depth)) + +(defun boundary (quadtree) + (quadtree-boundary quadtree)) + +(defun quadtree-x0 (quadtree-boundary) + (when quadtree-boundary + (first quadtree-boundary))) + +(defun quadtree-y0 (quadtree-boundary) + (when quadtree-boundary + (second quadtree-boundary))) + +(defun quadtree-x1 (quadtree-boundary) + (when quadtree-boundary + (third quadtree-boundary))) + +(defun quadtree-y1 (quadtree-boundary) + (when quadtree-boundary + (fourth quadtree-boundary))) + +(defun node-p (quadtree) + (and (quadtree-nw quadtree) + t)) + +(defun leaf-p (quadtree) + (not (node-p quadtree))) + +(defun full-p (quadtree) + (quadtree-object quadtree)) + +(defun max-depth-p (quadtree) + (= (quadtree-depth quadtree) + (quadtree-max-depth quadtree))) + +(defun root-p (quadtree) + (= (quadtree-depth quadtree) 0)) + +(defun quadtree-leaves (quadtree) + (remove-if-not #'leaf-p (quadtree->list quadtree))) + +(defun subtrees (quadtree) + (when quadtree + (list (quadtree-nw quadtree) (quadtree-ne quadtree) + (quadtree-sw quadtree) (quadtree-se quadtree)))) + +(defun query (quadtree x y &optional trees) + (declare (type double-float x y)) + (let ((ret (query-tree quadtree x y '()))) + (when ret + (values (quadtree-object (first (last ret))) + (when trees + ret))))) + +(defun query-tree (quadtree x y path) + (declare (type double-float x y)) + (when (coord-intersect-p quadtree x y) + (if (node-p quadtree) + (or (query-tree (quadtree-nw quadtree) x y + (append path (list (quadtree-nw quadtree)))) + (query-tree (quadtree-ne quadtree) x y + (append path (list (quadtree-ne quadtree)))) + (query-tree (quadtree-sw quadtree) x y + (append path (list (quadtree-sw quadtree)))) + (query-tree (quadtree-se quadtree) x y + (append path (list (quadtree-se quadtree))))) + (when (quadtree-object quadtree) + path)))) + +(defun quadtree-resolution (qt) + (destructuring-bind (x0 y0 x1 y1) (quadtree-boundary qt) + (let ((res0 (round-to (abs (- x1 x0)) 5)) + (res1 (round-to (abs (- y1 y0)) 5))) + (if (equal res0 res1) + res0 + (error 'simple-error "oh no"))))) + +(defun clear-subtrees-of (quadtree) + (setf (quadtree-nw quadtree) nil + (quadtree-ne quadtree) nil + (quadtree-sw quadtree) nil + (quadtree-se quadtree) nil) + t) + +(defun clear-quadtree (quadtree) + (setf (quadtree-object quadtree) nil) + (clear-subtrees-of quadtree) + t) + +(defun object-equal (p1 p2) + (declare (type 3d-vector p1 p2)) + (and (same-coords-as p1 p2) + (same-value-as p1 p2))) + +(defun same-coords-as (p1 p2) + (declare (type 3d-vector p1 p2)) + (and (equal (x p1) + (x p2)) + (equal (y p1) + (y p2)))) + +(defun same-value-as (p1 p2) + (declare (type 3d-vector p1 p2)) + (equal (z p1) + (z p2))) + +;; --------------------- BASE INTERSECTION CALC -------------------- + +(defun 2d-dot-product (v-1 v-2) + "Returns the dot-product" + (+ (* (x v-1) (x v-2)) + (* (y v-1) (y v-2)))) + +(defun point-intersect-p (quadtree P) + "Calculates if point P is in the boundary of the given `quadtree'." + (declare (type 3d-vector P)) + (let* ((corner-points (quadtree-boundary->corner-points quadtree)) + (A (first corner-points)) ;; D---C + (B (second corner-points)) ;; | / | + (C (third corner-points)) ;; A---B + (AB (v- B A)) + (AP (v- P A)) + (BC (v- C B)) + (BP (v- P B))) + (and (<= 0 (2d-dot-product AB AP) (2d-dot-product AB AB)) + (<= 0 (2d-dot-product BC BP) (2d-dot-product BC BC))))) + +(defun coord-intersect-p (quadtree x y) + (declare (type double-float x y)) + (point-intersect-p quadtree (make-3d-vector x y 0.0d0))) + +(defun quadtree-boundary->corner-points (qt) + "Returns the points of the corners `A', `B', `C' and `D' of given +quadtree `qt' in a list." + (when qt + (destructuring-bind (x0 y0 x1 y1) (quadtree-boundary qt) ;; D---C + (let* ((A (make-3d-vector x0 y0 0.0d0)) ;; | M | + (C (make-3d-vector x1 y1 0.0d0)) ;; A---B + (AM (v* ;; calc middlepoint of boundary + (v- C A) + 0.5d0)) + (B (v+ + A AM + (rotate ;; calc point M, which is between a and c + (axis-angle->quaternion + (make-3d-vector 0 0 1) + (+ pi (/ pi 2))) ;; rotate around 270°C + AM))) + (D (v+ + A AM + (rotate ;; calc point M, which is between a and c + (axis-angle->quaternion + (make-3d-vector 0 0 1) + (/ pi 2)) ;; rotate around 90°C + AM)))) + (mapcar #'v-round-to (list A B C D)))))) + + +;; -------------------------- BASIC FUNS WITH QUADTREEs ---------------- + +(defun set-in-quadtree (quadtree x y) + (declare (type double-float x y)) + (insert quadtree (make-3d-vector x y 1.0d0))) + +(defun get-in-quadtree (quadtree x y &optional neighbor-p) + (declare (type double-float x y)) + (funcall (lambda (queried) + (if neighbor-p + (when (same-coords-as (make-3d-vector x y 0.0d0) queried) + queried) + queried)) + (query quadtree x y))) + +(defun quadtree-map (quadtree fun &key compose-old-and-new-fun) + "Maps a function `fun' over the objects saved in `quadtree': meaning +`fun' needs to take one argument which is of type `3d-vector' and + returns a `3d-vector' too. The input and output of `fun' can then be + composed with the function `compose-old-and-new-fun' which should a + `3d-vector'." + (when (and quadtree fun) + (loop for subtree in (subtrees quadtree) do + (with-slots (object) quadtree + (when (and subtree object) + (if compose-old-and-new-fun + (let ((composed (funcall compose-old-and-new-fun + object + (funcall fun object)))) + (declare (type 3d-vector composed)) + (setf object composed)) + (setf object (funcall fun object)))))) + quadtree)) + +(defun normalize-quadtree (quadtree) + (let* ((leaves-and-nodes (quadtree->list quadtree :with-leaves t)) + (leaves (remove-if #'node-p leaves-and-nodes)) + (sum 0.0d0)) + (loop for leave in leaves do + (incf sum (z (quadtree-object leave)))) + (loop for entry in leaves-and-nodes do + (with-slots (object) entry + (setf object (make-3d-vector (x object) + (y object) + (float (/ (z object) + sum)))))))) + +(defun matrix->quadtree (origin-x origin-y resolution matrix &optional (threshold 0.0d0)) + "Creates an quadtree from the matrix `matrix'. The elements from `matrix' will +be mapped to the centers of the points. Since adding zeros is important too, this +will be done too. `origin-x' and `origin-y' have to be the bottom left corner and +`resolution' is the width of a cell in the returned quadtree." + (declare (type double-float origin-x origin-y resolution) + (type (simple-array * 2) matrix)) + (let* ((width (coerce (* (array-dimension matrix 1) resolution) 'double-float)) + (height (coerce (* (array-dimension matrix 0) resolution) 'double-float)) + (x0 origin-x) + (x1 (+ origin-x width)) + (y0 origin-y) + (y1 (+ origin-y height)) + (qt (make-quadtree x0 y0 x1 y1))) + (dotimes (y (array-dimension matrix 1)) + (let ((backward-y (- (1- (array-dimension matrix 1)) y))) + (dotimes (x (array-dimension matrix 0)) + (when (>= (aref matrix backward-y x) threshold) + (insert qt + (make-3d-vector + (+ (/ resolution 2) + (+ origin-x (* x resolution))) + (- (+ origin-y (* y resolution) resolution) + (/ resolution 2)) + (aref matrix backward-y x))))))) + qt)) + + + +;; (defun merge-quadtrees (qt1 &rest quadtrees)) + +;; (defun quadtree-equal (q1 q2)) + +;; --------------------- SUBDIVIDING ------------------------ + +(defun subdevide (quadtree &key erease-object) + (unless (leaf-p quadtree) + (error "The quadtree ~A is already subdevided." quadtree)) + (destructuring-bind (x0 y0 x1 y1) (boundary quadtree) + (declare (double-float x0 y0 x1 y1)) + (let ((xmid (/ (+ x1 x0) 2.0)) + (ymid (/ (+ y1 y0) 2.0)) + (depth (1+ (the fixnum (quadtree-depth quadtree)))) + (max-depth (quadtree-max-depth quadtree))) + (setf (quadtree-nw quadtree) + (%make-quadtree-internal x0 ymid xmid y1 depth max-depth) + (quadtree-ne quadtree) + (%make-quadtree-internal xmid ymid x1 y1 depth max-depth) + (quadtree-sw quadtree) + (%make-quadtree-internal x0 y0 xmid ymid depth max-depth) + (quadtree-se quadtree) + (%make-quadtree-internal xmid y0 x1 ymid depth max-depth)))) + (let ((object (quadtree-object quadtree))) + (if object + (if erease-object + (progn + (insert (quadtree-nw quadtree) + (quadtree-empty-middlepoint (quadtree-nw quadtree))) + (insert (quadtree-ne quadtree) + (quadtree-empty-middlepoint (quadtree-ne quadtree))) + (insert (quadtree-sw quadtree) + (quadtree-empty-middlepoint (quadtree-sw quadtree))) + (insert (quadtree-se quadtree) + (quadtree-empty-middlepoint (quadtree-se quadtree))) + (setf (quadtree-object quadtree) + (quadtree-empty-middlepoint quadtree))) + (progn + (insert (quadtree-nw quadtree) object) + (insert (quadtree-ne quadtree) object) + (insert (quadtree-sw quadtree) object) + (insert (quadtree-se quadtree) object))) + (progn + (insert (quadtree-nw quadtree) + (quadtree-empty-middlepoint (quadtree-nw quadtree))) + (insert (quadtree-ne quadtree) + (quadtree-empty-middlepoint (quadtree-ne quadtree))) + (insert (quadtree-sw quadtree) + (quadtree-empty-middlepoint (quadtree-sw quadtree))) + (insert (quadtree-se quadtree) + (quadtree-empty-middlepoint (quadtree-se quadtree))) + (setf (quadtree-object quadtree) + (quadtree-empty-middlepoint quadtree))))) + quadtree) + +;; ------------------------- INSERTING -------------------------------- + +(defun intersects-with-subtrees-p (object subtrees) + "Returns if coords of given `object' intersect with all boundaries + of the given `subtrees'" + (declare (type 3d-vector object)) + (when (and object subtrees) + (every #'identity + (mapcar (lambda (st) + (point-intersect-p st object)) + subtrees)))) + + +(defun middlepoint-of-quadtree-p (object quadtree) + "Returns T, if the coords of `object' are the middlepoint of the + boundary in given `quadtree'." + (declare (type 3d-vector object)) + (when quadtree + (if (leaf-p quadtree) + (destructuring-bind (x0 y0 x1 y1) (boundary quadtree) ;; d---c + (let* ((A (make-3d-vector x0 y0 0.0d0)) ;; | / | + (C (make-3d-vector x1 y1 0.0d0)) ;; a---b + (M (v+ A + (v* ;; calc middlepoint of boundary + (v- c a) + 0.5d0)))) + (point-intersect-p (make-quadtree (- (x M) *middlepoint-offset*) + (- (y M) *middlepoint-offset*) + (+ (x M) *middlepoint-offset*) + (+ (y M) *middlepoint-offset*)) + object))) + (intersects-with-subtrees-p object (subtrees quadtree))))) + + +(defun add-offset-if-middlepoint (object quadtree) + (declare (type 3d-vector object)) + (when (middlepoint-of-quadtree-p object quadtree) + (setf object + (make-3d-vector (round-to (- (x object) *middlepoint-offset*) 5) + (round-to (- (y object) *middlepoint-offset*) 5) + (z object)))) + object) + +(defun quadtree-empty-middlepoint (quadtree) + (when quadtree + (destructuring-bind (x0 y0 x1 y1) (boundary quadtree) + (let ((START (make-3d-vector x0 y0 0.0d0)) + (END (make-3d-vector x1 y1 0.0d0))) + (v+ START + (v* + (v- END START) + 0.5d0)))))) + + +(defun insert (quadtree object &key wrt-resolution) + (cond + ;; When the object does not intersect the quadtree, just return nil. + ((not (if quadtree (point-intersect-p quadtree object))) nil) + ;; When the quadtree is a node, recursively insert the object to its children. + ((node-p quadtree) + (insert (quadtree-nw quadtree) object :wrt-resolution wrt-resolution) + (insert (quadtree-ne quadtree) object :wrt-resolution wrt-resolution) + (insert (quadtree-sw quadtree) object :wrt-resolution wrt-resolution) + (insert (quadtree-se quadtree) object :wrt-resolution wrt-resolution) + t) + ;; Insert the object to the quadtree, if leaf is free or if the + ;; resolution of the quadtree is smaller or equal to the given + ;; resolution. + ((and (not (full-p quadtree)) + (if wrt-resolution + (<= (quadtree-resolution quadtree) wrt-resolution) + t)) + (setf (quadtree-object quadtree) (add-offset-if-middlepoint object quadtree)) + t) + ;; If leaf is not free, but has same coords as object or + ;; resolution of this quadtree is smaller or equal to the given + ;; resolution, update the object + ((and (full-p quadtree) + (or + (if wrt-resolution + (<= (quadtree-resolution quadtree) wrt-resolution) + nil) + (same-coords-as (quadtree-object quadtree) object))) + (setf (quadtree-object quadtree) object) + t) + ;; When the quadtree is full and is not at its max depth, subdevide it and + ;; recursively insert the object. + ((and (not (max-depth-p quadtree)) + (if wrt-resolution + (> (quadtree-resolution quadtree) wrt-resolution) + t)) + (subdevide quadtree :erease-object wrt-resolution) + (insert quadtree object :wrt-resolution wrt-resolution)) + ;; Otherwise if the max-depth-p or the objects were equal (object-equal returned t), + ;; do nothing, since the object represents accordingly the given object. + (t + t))) + +;; --------------------------- MINIMIZING --------------------------- + +(defun max-quadtrees (quadtrees) + "Returns the biggest quadtress which are just these with the biggest +depth value." + (let ((maximum (alexandria::reduce #'max quadtrees :key #'quadtree-depth))) + (remove-if-not (alexandria:curry #'equal maximum) + quadtrees :key #'quadtree-depth))) + +(defun some-subtree-node-p (quadtree) + "Returns if some subtree from the given `quadtree' +is a node." + (some #'node-p (subtrees quadtree))) + +(defun quadtree->list (quadtree &key with-leaves) + (let ((parents `(,quadtree)) + (visited-parents '())) + ;; Traverse tree and save visited parents in given var + (loop while (first parents) do + (push (pop parents) visited-parents) + (loop for subtree in (subtrees (first visited-parents)) do + (when (node-p subtree) + (setf parents (append parents (list subtree)))))) + (if with-leaves + (remove-if-not (lambda (st) + (and (identity st) (leaf-p st) (full-p st))) + (alexandria::reduce #'append + (mapcar #'subtrees + visited-parents))) + visited-parents))) + + +(defun minimize-quadtree (quadtree) + ;; TODO: make quadtree more dynamic by removing blank spaces around + ;; the middle point by making the quadtree smaller: e. g. from + ;; 0 0 0 0 + ;; 0 1 1 0 + ;; 0 1 1 0 + ;; 0 0 0 0 + ;; to + ;; 1 1 + ;; 1 1 + (let ((nodes (quadtree->list quadtree))) + ;; Try to remove redundant subtrees + (loop while nodes do + (let ((current-max-quadtrees (max-quadtrees nodes))) + (when (every #'some-subtree-node-p current-max-quadtrees) + (return)) + (loop for parent in (remove-if #'some-subtree-node-p + current-max-quadtrees) + do (cleanup-leaves parent)) + (setf nodes (nthcdr (length current-max-quadtrees) nodes)))))) +;; since quadtree was searched in level order +;; visited-parents is sorted from a high to +;; low depth value + + +(defun pair-elements (l) + (when (> (length l) 1) + (append (list (subseq l 0 2)) (pair-elements (nthcdr 1 l))))) + +(defun clear-in-quadtree (quadtree x y &optional remove-subtrees-if-possible) + "Removes point with same coords and if subtrees of point are empty, +the the subtrees will be removed to save space: therfore the parent will +be updated" + (declare (type double-float x y)) + (let ((cleared-point (make-3d-vector x y 0.0d0))) + (multiple-value-bind (queried-point queried-trees) + (query quadtree x y t) + (when (same-coords-as cleared-point queried-point) + (setf (quadtree-object (first (last queried-trees 1))) + cleared-point) + (when remove-subtrees-if-possible + (let ((parent (first (last queried-trees 2)))) + (cleanup-leaves parent))))))) + +(defun cleanup-leaves (quadtree) +"If the filled subtrees of `quadtree' have the same value or are all empty, +these subtrees will be removed, since they are redundant." + (when quadtree + (let* ((non-empty-subtrees + (remove-if-not #'identity + (subtrees quadtree) + :key #'quadtree-object)) + (object-values-equal + (every #'identity (mapcar + (lambda (l) + (same-value-as (first l) (second l))) + (pair-elements + (mapcar #'quadtree-object + non-empty-subtrees)))))) + (when (and + object-values-equal + (every #'leaf-p non-empty-subtrees)) + (let ((value (if non-empty-subtrees + (quadtree-object (quadtree-nw quadtree)) + 0.0d0))) + (setf (quadtree-object quadtree) + (make-3d-vector + (x (quadtree-object quadtree)) + (y (quadtree-object quadtree)) + (z value))) + (clear-subtrees-of quadtree)))) + quadtree)) + + +;; ---------------------- HELPER FUN ---------------------- + +(defun round-to (number precision &optional (what #'round)) + (let ((div (expt 10 precision))) + (/ (funcall what (* number div)) div))) + +(defun v-round-to (v &optional (precision 3)) + "Rounds x and y of given vetor `v' w.r.t. the `precision'." + (declare (type 3d-vector v)) + (make-3d-vector (round-to (x v) precision) + (round-to (y v) precision) + (z v))) + +;; ---------------------- ROTATE -------------------------- + +(defun v-abs (v) + (declare (type 3d-vector v)) + (make-3d-vector (abs (x v)) (abs (y v)) (abs (z v)))) + +(defun rotate-quadtree (quadtree angle &optional M-root) + "TODO SHOULD BE CHANGED SINCE ROTATING BOUNDARIES NEEDS A LOT OF + CALCULATION (SEE BELOW)" + (destructuring-bind (x0 y0 x1 y1) (boundary quadtree) + (flet ((rotate-v (v) + (rotate + (axis-angle->quaternion + (make-3d-vector 0 0 1) + angle) + v))) + (let* ((START (make-3d-vector x0 y0 0.0d0)) + (END (make-3d-vector x1 y1 0.0d0)) + (M (v-abs (if M-root + M-root + (v+ + START + (v* + (v- END START) + 0.5d0))))) + (M-START (v- START M)) + (M-END (v- END M)) + (rotated-start (v+ (rotate-v M-START) + M)) + (rotated-end (v+ (rotate-v M-END) + M))) + (setf (quadtree-boundary quadtree) + (list (x rotated-start) + (y rotated-start) + (x rotated-end) + (y rotated-end))) + (when (quadtree-object quadtree) ;; TODO: check if below works 100% + (with-slots (object) quadtree + (let* ((M-of-quadtree (v* + (v- END START) + 0.5d0)) + (M-TO-M-of-quadtree (v- M M-of-quadtree)) + (rotated-obj (v+ + START + M + (rotate-v M-TO-M-of-quadtree)))) + (setf object + (make-3d-vector (x rotated-obj) + (y rotated-obj) + (z object)))))) + (mapcar (alexandria:rcurry #'rotate-quadtree angle M) + (remove-if-not #'identity (subtrees quadtree))))))) + + +;; ------- CALC OF INTERSECTING POINTS BETWEEN ROTATED QUADTREES ----------- + +#+this-part-is-commented-out-as-it-is-not-finished-yet +( + (defun quadtree-boundary->vectors (qt) + "Returns the boundary of the given quadtree `qt' as vectors AB, BC, + CD, DA in a list." + (mapcar #'v- (mapcar #'reverse (quadtree-boundary->edge-points qt)))) + + (defun quadtree-boundary->edge-points (qt) + "Returns the edges of the quadtree `qt' in a list containing lists + with start and end points (A, B, C or D) from each edge." + (when qt + (let* ((corner-points (quadtree-boundary->corner-points qt)) + (A (first corner-points)) + (B (second corner-points)) + (C (third corner-points)) + (D (fourth corner-points))) + (list `(,A ,B) `(,B ,C) `(,C ,D) `(,D ,A))))) + + + + (defun points->vector-points (points) + "Returns all (redundant) vectors/connections between each point in + `points'. The vectors are encoded as a list of a start and + end point. Therefore, a list of lists will be returned." + (when points + (let ((ret '())) + (loop for i from 0 to (1- (length points)) do + (loop for j from 0 to (1- (length points)) do + (when (not (equal j i)) + (push (list (nth i points) (nth j points)) ret)))) + ret))) + + + (defun intersecting-vector-points-lists (vec-points-list-1 + vec-points-list-2 &optional intersecting-counts-only-with-limited-vector-length-p) + "Gets two lists `vec-points-list-1' and `vec-points-list-2' which + are lists containing vectors in form of a start and end point. Meaning + vector AB is here a list: (list (point a) (point b)). Between each + of these sublists in `vec-points-list-1' and `vec-points-list-2' a + intersection point will be calculated (or the given + sublists/vectors are parallel to each other). A list of these + intersection points will be returned. If + `intersecting-counts-only-with-limited-vector-length-p' is T the + intersection between the given vectors/sublists has to be valid." + (when (and vec-points-list-1 vec-points-list-2) + (let ((ret '())) + (loop for vec-point-1 in vec-points-list-1 do + (loop for vec-point-2 in vec-points-list-2 do + (multiple-value-bind (intersected-point valid-intersection-p) + (point-of-intersection (first vec-point-1) (second vec-point-1) + (first vec-point-2) (second vec-point-2)) + (when intersected-point + (let ((round-intersected-point (v-round-to intersected-point))) + (when (or (not ret) + (not (member round-intersected-point ret :test #'v-equal))) + (if intersecting-counts-only-with-limited-vector-length-p + (when valid-intersection-p + (push round-intersected-point ret)) + (push round-intersected-point ret)))))))) + ret))) + + + (defun max-points-on-vector-points (ps vec-points) + "Takes points from `ps' and returns the points `min' and `max' in a + list, which are the farthest away from each other on the given vector + `vec-points'. `vec-points' is represented as a list of start (first) + and end (second) point of the vector." + (when (and ps (equal 2 (length vec-points))) + (let* ((points-on-vec (mapcar + #'v-round-to + (remove-if-not + (alexandria:rcurry #'point-on-vector-points-p vec-points) + ps))) + (min (first points-on-vec)) + (max (first points-on-vec))) + (when points-on-vec + (loop for p in points-on-vec do + (when (and (<= (x p) (x min)) + (<= (y p) (y min))) + (setf min p)) + (when (and (>= (x p) (x max)) + (>= (y p) (y max))) + (setf max p))) + (list min max))))) + + + (defun point-on-vector-points-p (p vec-points) + "Returns T if given point `p' is on the vector `vec-points' which is + represented as a list of a start (first) and end point (second) of the vector." + (declare (type 3d-vector p)) + (when (equal 2 (length vec-points)) + (point-on-vector-p (v- p (first vec-points)) + (v- (second vec-points) (first vec-points))))) + + + (defun point-on-vector-p (p vec) + "Returns T if given point `p' is on the given vector `vec'." + (declare (type 3d-vector p vec)) + (cond + ;; if (x vec) is zero + ((and (equal (x vec) 0.0d0) + (not (equal (y vec) 0.0d0))) + (and (equal (x p) 0.0d0) + (<= 0.0d0 (/ (y p) (y vec)) 1.0d0))) + ;; if (y vec) is zero + ((and (equal (y vec) 0.0d0) + (not (equal (x vec) 0.0d0))) + (and (equal (y p) 0.0d0) + (<= 0.0d0 (/ (x p) (x vec)) 1.0d0))) + ;; if (x vec) and (y vec) are zero + ((and (equal (x vec) 0.0d0) + (equal (y vec) 0.0d0)) + (and (equal (x p) 0.0d0) + (equal (y p) 0.0d0))) + ;; if neither (x vec) nor (y vec) are zero + (t + (let ((s (/ (x p) (x vec))) + (r (/ (y p) (y vec)))) + (and (equal s r) + (<= 0.0d0 s 1.0d0)))))) + + + (defun intersecting-points (qt1 qt2) + "Calculates the points bordering the area which the quadtrees + `qt1' and `qt2' both cover." + (when (and qt1 qt2 + (leaf-p qt1) + (leaf-p qt2)) + (let* ((qt1-edge-points (quadtree-boundary->edge-points qt1)) + (qt2-edge-points (quadtree-boundary->edge-points qt2)) + ;; calculates the intersection points between the edges + ;; of qt1 and qt2 + (intersecting-points-between-edges + (intersecting-vector-points-lists qt1-edge-points + qt2-edge-points)) + ;; creates new vectors from the intersection points from + ;; the edges of qt1 and qt2 <- bull + (vector-points-of-intersecting-points + (points->vector-points + (append intersecting-points-between-edges + (quadtree-boundary->corner-points qt1) + (quadtree-boundary->corner-points qt2)))) + ;; calculates all points which intersect with the edges of + ;; qt1 and qt2 + (all-intersecting-points + (append + (intersecting-vector-points-lists + vector-points-of-intersecting-points + qt2-edge-points + t) + (intersecting-vector-points-lists + vector-points-of-intersecting-points + qt1-edge-points + t))) + ;; removes all points which do not intersect within the + ;; boundaries of qt1 and qt2 + (intersecting-points-on-edges + (remove-if-not (lambda (p) + (and (point-intersect-p qt1 p) + (point-intersect-p qt2 p))) + all-intersecting-points)) + ;; calculates the points which are the farthest away + ;; on each edge of qt1 or qt2 + (max-intersecting-points-on-edges + (remove-if-not + #'identity + (mapcar (alexandria:curry + #'max-points-on-vector-points + intersecting-points-on-edges) + (append qt1-edge-points + qt2-edge-points))))) + (let ((ret '())) + (loop for pair in max-intersecting-points-on-edges + collect (loop for p in pair + collect (unless (member p ret :test #'v-equal) + (push p ret)))) + ret)))) + + + (defun v-equal (v w) + "Returns T, if x, y and z are equal between vector `v' and `w'." + (declare (type 3d-vector v w)) + (and (equal (x v) (x w)) + (equal (y v) (y w)) + (equal (z v) (z w)))) + + + (defun point-of-intersection (a b c d) + "This function calculates the possible intersection point between the vector AB + and the vector CD: meaning `a' is the start point of AB and `b' is the + end point (analog for `c', `d' and CD). It returns the intersecting + point and if the vectors intersected or the extension of + these. Explanation of the calculation is here: https://www.cambridge.org/core/services/aop-cambridge-core/content/view/C6F1EC3B8FA75FB4FADC3DBA35DE4D6C/9780511804120c7_p220-293_CBO.pdf/search_and_intersection.pdf" + (declare (type 3d-vector a b c d)) + (unless (or (v-equal a c) + (v-equal b d)) + (let ((denom (+ (* (x a) (- (y d) (y c))) + (* (x b) (- (y c) (y d))) + (* (x d) (- (y b) (y a))) + (* (x c) (- (y a) (y b)))))) + (unless (equal denom 0.0d0) + (let* ((num-s (+ (* (x a) (- (y d) (y c))) + (* (x c) (- (y a) (y d))) + (* (x d) (- (y c) (y a))))) + (num-r (* -1 + (+ (* (x a) (- (y c) (y b))) + (* (x b) (- (y a) (y c))) + (* (x c) (- (y b) (y a)))))) + (s (/ num-s denom)) + (r (/ num-r denom))) + + (values + (make-3d-vector (+ (x a) + (* s + (- (x b) (x a)))) + (+ (y d) + (* s + (- (y b) (y a)))) + 1.0d0) + (and (<= 0.0d0 s 1.0d0) + (<= 0.0d0 r 1.0d0)))))))) + ) diff --git a/cram_common/cram_manipulation_interfaces/cram-manipulation-interfaces.asd b/cram_common/cram_manipulation_interfaces/cram-manipulation-interfaces.asd index 75f07006bb..823192a675 100644 --- a/cram_common/cram_manipulation_interfaces/cram-manipulation-interfaces.asd +++ b/cram_common/cram_manipulation_interfaces/cram-manipulation-interfaces.asd @@ -39,7 +39,7 @@ cl-transforms-stamped cram-robot-interfaces ; for gripper transform calculations cram-plan-occasions-events ; for robot-free-arm - cram-utilities ; for working with prolog lazy lists + cram-designator-specification ; for location desig resolution ) :components ((:module "src" @@ -47,14 +47,26 @@ ((:file "package") (:file "object-designator-interfaces" :depends-on ("package")) - (:file "prolog" :depends-on ("package" "object-designator-interfaces")) - - (:file "object-hierarchy" :depends-on ("package" "prolog")) (:file "manipulation-interfaces" :depends-on ("package")) - (:file "gripper" :depends-on ("package" "manipulation-interfaces" "object-hierarchy")) + (:file "prolog" :depends-on ("package" + "object-designator-interfaces" + "manipulation-interfaces")) + (:file "object-hierarchy" :depends-on ("package" "prolog")) + + (:file "gripper" :depends-on ("package" + "manipulation-interfaces" + "object-hierarchy")) + (:file "carry" :depends-on ("package" + "manipulation-interfaces" + "object-hierarchy")) + (:file "likely-locations" :depends-on ("package" + "manipulation-interfaces" + "object-hierarchy")) (:file "grasps" :depends-on ("package" "manipulation-interfaces")) (:file "trajectories" :depends-on ("package" - "prolog" "manipulation-interfaces" "object-hierarchy")) + "prolog" + "manipulation-interfaces" + "object-hierarchy")) (:file "standard-grasps" :depends-on ("package")) (:file "standard-rotations" :depends-on ("package")) diff --git a/cram_common/cram_manipulation_interfaces/package.xml b/cram_common/cram_manipulation_interfaces/package.xml index 8ecf815887..e754b544cf 100644 --- a/cram_common/cram_manipulation_interfaces/package.xml +++ b/cram_common/cram_manipulation_interfaces/package.xml @@ -22,4 +22,5 @@ cl_transforms_stamped cram_robot_interfaces cram_plan_occasions_events + cram_designator_specification diff --git a/cram_common/cram_manipulation_interfaces/src/carry.lisp b/cram_common/cram_manipulation_interfaces/src/carry.lisp new file mode 100644 index 0000000000..088fdd2ac9 --- /dev/null +++ b/cram_common/cram_manipulation_interfaces/src/carry.lisp @@ -0,0 +1,33 @@ +;;; +;;; Copyright (c) 2020, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :cram-manipulation-interfaces) + +(defmethod get-object-type-carry-config :heuristics 20 (object-type grasp) + (call-with-specific-type #'get-object-type-carry-config object-type grasp)) diff --git a/cram_common/cram_manipulation_interfaces/src/likely-locations.lisp b/cram_common/cram_manipulation_interfaces/src/likely-locations.lisp new file mode 100644 index 0000000000..f98eb7b491 --- /dev/null +++ b/cram_common/cram_manipulation_interfaces/src/likely-locations.lisp @@ -0,0 +1,44 @@ +;;; +;;; Copyright (c) 2020, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :cram-manipulation-interfaces) + +(defmethod get-object-likely-location :heuristics 20 (object-type + environment-name + human-name + context) + (call-with-specific-type #'get-object-likely-location + object-type environment-name human-name context)) + +(defmethod get-object-destination :heuristics 20 (object-type + environment-name + human-name + context) + (call-with-specific-type #'get-object-destination + object-type environment-name human-name context)) diff --git a/cram_common/cram_manipulation_interfaces/src/manipulation-interfaces.lisp b/cram_common/cram_manipulation_interfaces/src/manipulation-interfaces.lisp index 76ead3b846..ce58dbdc47 100644 --- a/cram_common/cram_manipulation_interfaces/src/manipulation-interfaces.lisp +++ b/cram_common/cram_manipulation_interfaces/src/manipulation-interfaces.lisp @@ -42,7 +42,13 @@ (:documentation "Returns a (lazy) list of keywords that represent the possible grasp orientations for `object-type' given `arm' and `object-transform-in-base'.")) -(defgeneric get-action-trajectory (action-type arm grasp objects-acted-on +(defgeneric get-object-type-carry-config (object-type grasp) + (:method-combination cut:first-in-order-and-around) + (:documentation "When carrying an object, which arm configuration to use. +The return value is a symbol (keyword), which associates with a robot-specific +joint state, specified in the robot description.")) + +(defgeneric get-action-trajectory (action-type arm grasp location objects-acted-on &key &allow-other-keys) (:method-combination cut:first-in-order-and-around) (:documentation "Returns a list of TRAJ-SEGMENTs. @@ -50,6 +56,7 @@ grasp orientations for `object-type' given `arm' and `object-transform-in-base'. `action-type' describes for which type of action the trajectory will be, `arm' a single keyword eg. :left, `grasp' describes grasp orientation to use, e.g., :top, :left-side, +`location' is the location type of the action, e.g., counter-top or shelf `objects-acted-on' are designators describing the objects used by the action.")) (defgeneric get-location-poses (location-designator) @@ -57,7 +64,8 @@ grasp orientations for `object-type' given `arm' and `object-transform-in-base'. (:documentation "Returns a (lazy) list of cl-transforms-pose-stamped that, according to the reasoning engine, correspond to the given `location-designator'.") (:method :heuristics 20 (location-designator) - (desig:resolve-location-designator-through-generators-and-validators location-designator))) + (desig:resolve-location-designator-through-generators-and-validators + location-designator))) (defmethod desig:resolve-designator :around ((desig desig:location-designator) role) "We have to hijack DESIG:RESOLVE-DESIGNATOR because otherwise we would have to @@ -66,6 +74,22 @@ and man-int is way too high level to make it a dependency of CRAM_CORE. This hijacking is kind of an ugly hack that Gaya feels bad about :(." (get-location-poses desig)) +(defgeneric get-object-likely-location (object-type environment-name human-name context) + (:method-combination cut:first-in-order-and-around) + (:documentation "Returns a location designator representing the +location, where an object with given type `object-type' can typically be found at. +The likely location can depend on the `environment-name', +the human preferences represented as `human-name' +and `context' representing the name of the action context, e.g. :table-setting.")) + +(defgeneric get-object-destination (object-type environment-name human-name context) + (:method-combination cut:first-in-order-and-around) + (:documentation "Returns a location designator representing the +location, where an object with given type `object-type' usually should be brought to +in the given action context `context', e.g., :table-setting.. +The likely destination can additionally depend on the `environment-name' and +the human preferences represented as `human-name'.")) + (defgeneric get-container-opening-distance (container-name) (:method-combination cut:first-in-order-and-around) (:documentation "Returns a value describing the distance a container can diff --git a/cram_common/cram_manipulation_interfaces/src/object-designator-interfaces.lisp b/cram_common/cram_manipulation_interfaces/src/object-designator-interfaces.lisp index 08b57ea5b0..c3a123f4a9 100644 --- a/cram_common/cram_manipulation_interfaces/src/object-designator-interfaces.lisp +++ b/cram_common/cram_manipulation_interfaces/src/object-designator-interfaces.lisp @@ -49,3 +49,19 @@ (defun get-object-old-pose (object-designator) (car (getassoc :pose (desig:desig-prop-value object-designator :old-pose)))) + +#+a-hack-in-case-we-dont-want-to-use-perception +(defun get-object-transform (object-designator) + (let* ((object-type + (desig:desig-prop-value object-designator :type)) + (object-frame + (concatenate + 'string + (remove #\- (string-capitalize (symbol-name object-type))) + "1"))) + (cl-transforms-stamped:lookup-transform + cram-tf:*transformer* + cram-tf:*robot-base-frame* + object-frame + :time 0.0 + :timeout cram-tf:*tf-default-timeout*))) diff --git a/cram_common/cram_manipulation_interfaces/src/package.lisp b/cram_common/cram_manipulation_interfaces/src/package.lisp index e94841c18f..7df64a39d5 100644 --- a/cram_common/cram_manipulation_interfaces/src/package.lisp +++ b/cram_common/cram_manipulation_interfaces/src/package.lisp @@ -41,18 +41,31 @@ #:get-object-old-transform #:get-object-old-pose ;; prolog - #:object-type-subtype - #:object-type-direct-subtype - #:robot-free-hand + #:object-type-subtype #:object-type-direct-subtype + #:robot-free-hand #:joint-state-for-arm-config + #:object-rotationally-symmetric + #:orientation-matters #:unidirectional-attachment + #:location-always-reachable + #:object-is-a-robot + #:object-is-a-container + #:object-is-a-prismatic-container + #:object-is-a-revolute-container + #:object-or-its-reference-in-hand + #:location-reference-object + #:location-certain + #:location-always-stable ;; utils #:reasoning-engine-for-method ;; manipulation-interfaces #:get-action-gripping-effort #:get-action-gripper-opening - #:get-action-trajectory + #:get-object-type-carry-config #:get-action-grasps + #:get-action-trajectory #:get-location-poses + #:get-object-likely-location + #:get-object-destination #:get-container-opening-distance #:get-container-closing-distance ;; grasps @@ -60,8 +73,6 @@ #:calculate-face-vector #:object-type-grasp->robot-grasp #:robot-grasp->object-type-grasp - #:object-rotationally-symmetric - #:orientation-matters ;; trajectories #:make-traj-segment #:traj-segment-label @@ -72,24 +83,27 @@ #:calculate-gripper-pose-in-map ;; #:get-object-type-to-gripper-transform - #:get-object-type-to-gripper-pregrasp-transform - #:get-object-type-to-gripper-2nd-pregrasp-transform - #:get-object-type-to-gripper-lift-transform - #:get-object-type-to-gripper-2nd-lift-transform + #:get-object-type-to-gripper-pregrasp-transforms + #:get-object-type-wrt-base-frame-lift-transforms #:def-object-type-to-gripper-transforms #:get-object-grasping-poses ;; #:get-object-type-in-other-object-transform + #:get-z-offset-for-placing-with-dropping #:get-object-placement-transform #:def-object-type-in-other-object-transform #:get-object-look-from-pose ;; standard-grasps #:*x-across-z-grasp-rotation* + #:*x-across-z-grasp-rotation-2* #:*-x-across-z-grasp-rotation* + #:*-x-across-z-grasp-rotation-2* #:*x-across-y-grasp-rotation* #:*-x-across-y-grasp-rotation* #:*y-across-z-grasp-rotation* #:*-y-across-z-grasp-rotation* + #:*y-across-z-flipped-grasp-rotation* + #:*-y-across-z-flipped-grasp-rotation* #:*y-across-x-grasp-rotation* #:*-y-across-x-grasp-rotation* #:*z-across-x-grasp-rotation* diff --git a/cram_common/cram_manipulation_interfaces/src/prolog.lisp b/cram_common/cram_manipulation_interfaces/src/prolog.lisp index 513a0d468d..172a22985f 100644 --- a/cram_common/cram_manipulation_interfaces/src/prolog.lisp +++ b/cram_common/cram_manipulation_interfaces/src/prolog.lisp @@ -29,19 +29,15 @@ (in-package :cram-manipulation-interfaces) -(def-fact-group object-designators (desig:desig-location-prop desig:location-grounding) - - (<- (desig:desig-location-prop ?desig ?loc) - (desig:obj-desig? ?desig) - (lisp-fun get-object-pose-in-map ?desig ?loc) - (lisp-pred identity ?loc)) - - (<- (desig:location-grounding ?designator ?pose-stamped) - (desig:loc-desig? ?designator) - (desig:desig-prop ?designator (:of ?object-designator)) - (lisp-type ?object-designator desig:object-designator) - (desig:current-designator ?object-designator ?current-object-designator) - (desig:desig-location-prop ?current-object-designator ?pose-stamped))) +(defun symbol-to-prolog-rule (the-symbol &rest parameters) + (let ((interned-symbol + (find-symbol (string-upcase the-symbol) + (find-package :rob-int)))) + (if interned-symbol + (cram-utilities:var-value + '?result + (car (prolog `(,interned-symbol ,@parameters ?result)))) + the-symbol))) (def-fact-group object-type-hierarchy (object-type-direct-subtype) (<- (object-type-direct-subtype ?type ?direct-subtype) @@ -67,7 +63,7 @@ ;; knives, forks, etc, the orientation is important while for plates ;; the orientation doesn't matter at all. (<- (orientation-matters ?object-type-symbol) - (fail)) + (fail)) ;; The predicate UNIDIRECTIONAL-ATTACHMENTS holds attachments which ;; are only used for unidirectional/loose attachments. @@ -78,9 +74,242 @@ (fail))) -(def-fact-group manipulation-knowledge (robot-free-hand) +(def-fact-group manipulation-knowledge () + ;; most symbolic locations have a reference object + ;; this predicate finds the reference object of the given location desig + (<- (location-reference-object ?location-designator ?current-object-designator) + (desig:loc-desig? ?location-designator) + (desig:current-designator ?location-designator ?current-location-designator) + (or (spec:property ?current-location-designator (:in ?object-designator)) + (spec:property ?current-location-designator (:on ?object-designator)) + (spec:property ?current-location-designator (:above ?object-designator)) + (spec:property ?current-location-designator (:left-of ?object-designator)) + (spec:property ?current-location-designator (:right-of ?object-designator)) + (spec:property ?current-location-designator (:in-front-of ?object-designator)) + (spec:property ?current-location-designator (:behind ?object-designator)) + (spec:property ?current-location-designator (:near ?object-designator)) + (spec:property ?current-location-designator (:far-from ?object-designator)) + (spec:property ?current-location-designator (:of ?object-designator))) + (desig:current-designator ?object-designator ?current-object-designator)) + ;; gives one of robot's hands that is not holding anything (<- (robot-free-hand ?robot ?arm) (rob-int:robot ?robot) (rob-int:arm ?robot ?arm) - (not (cpoe:object-in-hand ?_ ?arm)))) + (not (cpoe:object-in-hand ?_ ?arm))) + + ;; says if the object or an object to which this object is attached, are in hand + (<- (object-or-its-reference-in-hand ?some-object-designator ?object-hand) + (desig:current-designator ?some-object-designator ?object-designator) + (or (cpoe:object-in-hand ?object-designator ?object-hand) + (and (spec:property ?object-designator (:location ?object-location)) + (man-int:location-reference-object ?object-location ?reference-obj) + (cpoe:object-in-hand ?reference-obj ?object-hand)))) + + ;; gives the joint state numbers for the given config, + ;; taking into consideration if there is an object in hand or not + (<- (joint-state-for-arm-config ?robot ?config ?arm ?joint-state) + (once + (or (-> (and (equal ?config :park) + (cpoe:object-in-hand ?object-designator ?arm ?grasp)) + (and (desig:current-designator ?object-designator ?current-object-desig) + (spec:property ?current-object-desig (:type ?object-type)) + (lisp-fun get-object-type-carry-config ?object-type ?grasp + ?carry-config) + (-> (lisp-pred identity ?carry-config) + (rob-int:robot-joint-states ?robot :arm ?arm ?carry-config + ?joint-state) + (rob-int:robot-joint-states ?robot :arm ?arm :carry + ?joint-state))) + (rob-int:robot-joint-states ?robot :arm ?arm ?config ?joint-state)) + (equal ?joint-state NIL)))) + + (<- (object-is-a-robot ?some-object-designator) + (desig:current-designator ?some-object-designator ?object-designator) + (or (desig:desig-prop ?object-designator (:type :robot)) + (desig:desig-prop ?object-designator (:type :environment)) + (and (rob-int:robot ?robot) + (desig:desig-prop ?object-designator (:part-of ?robot))) + (and (rob-int:environment-name ?environment) + (desig:desig-prop ?object-designator (:part-of ?environment))))) + + (<- (object-is-of-type ?some-object-designator ?type-to-assert) + (desig:current-designator ?some-object-designator ?object-designator) + (desig:desig-prop ?object-designator (:type ?object-type)) + (object-type-subtype ?type-to-assert ?object-type)) + + (<- (object-is-a-container ?some-object-designator) + (object-is-of-type ?some-object-designator :container)) + + (<- (object-is-a-prismatic-container ?some-object-designator) + (object-is-of-type ?some-object-designator :container-prismatic)) + + (<- (object-is-a-revolute-container ?some-object-designator) + (object-is-of-type ?some-object-designator :container-revolute)) + + ;; A location on/in the robot is always reachable + (<- (location-always-reachable ?location-designator) + (desig:loc-desig? ?location-designator) + (desig:current-designator ?location-designator ?current-location-designator) + (or (desig:desig-prop ?current-location-designator (:on ?object-designator)) + (desig:desig-prop ?current-location-designator (:in ?object-designator))) + (desig:current-designator ?object-designator ?current-object-designator) + (desig:desig-prop ?current-object-designator (:type :robot))) + ;; Also, a location on an item that is held by the robot is also always reachable + (<- (location-always-reachable ?location-designator) + (desig:loc-desig? ?location-designator) + (desig:current-designator ?location-designator ?current-location-designator) + (desig:desig-prop ?current-location-designator (:on ?object-designator)) + (desig:current-designator ?object-designator ?current-object-designator) + (cpoe:object-in-hand ?current-object-designator)) + ;; Also, a location of an object at a location that is always reachable + ;; is also always reachable + (<- (location-always-reachable ?location-designator) + (desig:loc-desig? ?location-designator) + (desig:current-designator ?location-designator ?current-location-designator) + (spec:property ?current-location-designator (:of ?object-designator)) + (desig:current-designator ?object-designator ?current-object-designator) + (spec:property ?current-object-designator (:location ?object-location)) + (man-int:location-always-reachable ?object-location)) + + (<- (location-certain ?some-location-designator) + (desig:loc-desig? ?some-location-designator) + (desig:current-designator ?some-location-designator ?location-designator) + (or (and (location-reference-object ?location-designator ?reference-object) + (or (object-is-a-robot ?reference-object) + (cpoe:object-in-hand ?reference-object))) + (spec:property ?location-designator (:pose ?_)) + (spec:property ?location-designator (:poses ?_)))) + + (<- (location-always-stable ?some-location-designator) + (desig:loc-desig? ?some-location-designator) + (desig:current-designator ?some-location-designator ?location-designator) + (or (spec:property ?location-designator (:attachment ?_)) + (spec:property ?location-designator (:attachments ?_)) + (spec:property ?location-designator (:above ?_))))) + + + +;; TODO: move to pick and place heuristics package, when it is created +(def-fact-group location-designator-stuff (desig:location-grounding + desig:desig-location-prop) + (<- (desig:desig-location-prop ?desig ?loc) + (desig:obj-desig? ?desig) + (lisp-fun get-object-pose-in-map ?desig ?loc) + (lisp-pred identity ?loc)) + + ;; Resolving (a location (of ?some-object)) + (<- (desig:location-grounding ?designator ?pose-stamped) + (desig:loc-desig? ?designator) + (desig:desig-prop ?designator (:of ?object-designator)) + (lisp-type ?object-designator desig:object-designator) + (desig:current-designator ?object-designator ?current-object-designator) + (desig:desig-location-prop ?current-object-designator ?pose-stamped)) + + ;; Resolving (a location + ;; (of (desig:an object + ;; (part-of ?robot) + ;; (link end-effector-link) + ;; (which-link left)))) + (<- (desig:desig-location-prop ?object-designator ?pose-stamped) + (desig:obj-desig? ?object-designator) + (desig:desig-prop ?object-designator (:part-of ?robot)) + (rob-int:robot ?robot) + (desig:desig-prop ?object-designator (:link ?link)) + (-> (desig:desig-prop ?object-designator (:which-link ?params)) + (lisp-fun symbol-to-prolog-rule ?link ?robot ?params ?link-name) + (lisp-fun symbol-to-prolog-rule ?link ?robot ?link-name)) + (lisp-fun cram-tf:frame-to-pose-in-fixed-frame ?link-name ?pose-stamped)) + + ;; Resolving (a location + ;; (for ?object) + ;; (on ?other-object) + ;; (attachment object-to-other-object)) + (<- (desig:location-grounding ?location-designator ?pose-stamped) + (desig:current-designator ?location-designator ?current-loc-desig) + (desig:desig-prop ?current-loc-desig (:for ?object-designator)) + (once + (or (desig:desig-prop ?current-loc-desig (:on ?other-object-designator)) + (desig:desig-prop ?current-loc-desig (:in ?other-object-designator)) + (desig:desig-prop ?current-loc-desig (:above ?other-object-designator)))) + (-> (desig:desig-prop ?current-loc-desig (:attachments ?attachments)) + (member ?attachment-type ?attachments) + (desig:desig-prop ?current-loc-desig (:attachment ?attachment-type))) + (desig:current-designator ?object-designator ?current-object-designator) + (spec:property ?current-object-designator (:type ?object-type)) + (spec:property ?current-object-designator (:name ?object-name)) + (desig:current-designator ?other-object-designator ?current-other-obj-desig) + (spec:property ?current-other-obj-desig (:type ?other-object-type)) + ;; + (-> (spec:property ?current-other-obj-desig (:urdf-name ?other-object-name)) + (and (lisp-fun roslisp-utilities:rosify-underscores-lisp-name + ?other-object-name ?link-name) + (symbol-value cram-tf:*fixed-frame* ?parent-frame) + (lisp-fun cram-tf:frame-to-transform-in-fixed-frame + ?link-name ?parent-frame + ?other-object-transform)) + (and (spec:property ?current-other-obj-desig (:name ?other-object-name)) + (-> (cpoe:object-in-hand ?current-other-obj-desig ?hand ?grasp ?link) + (and (rob-int:robot ?robot) + (-> (rob-int:end-effector-link ?robot ?arm ?link) + (and (rob-int:robot-tool-frame ?robot ?arm ?tool-frame) + (symbol-value cram-tf:*fixed-frame* ?parent-frame) + (lisp-fun cram-tf:frame-to-transform-in-fixed-frame + ?tool-frame ?parent-frame + ?map-t-gripper) + (lisp-fun get-object-type-to-gripper-transform + ?other-object-type ?other-object-name + ?arm ?grasp + ?object-t-std-gripper) + (lisp-fun cram-tf:transform-stamped-inv + ?object-t-std-gripper + ?std-gripper-t-object) + (rob-int:standard<-particular-gripper-transform + ?robot + ?std-gripper-t-gripper-not-stamped) + (lisp-fun + cl-transforms-stamped:transform->transform-stamped + ?tool-frame ?tool-frame 0.0 + ?std-gripper-t-gripper-not-stamped + ?std-gripper-t-gripper) + (lisp-fun cram-tf:transform-stamped-inv + ?std-gripper-t-gripper + ?gripper-t-std-gripper) + (lisp-fun cram-tf:apply-transform + ?gripper-t-std-gripper ?std-gripper-t-object + ?gripper-t-object) + (lisp-fun cram-tf:apply-transform + ?map-t-gripper ?gripper-t-object + ?other-object-transform)) + (lisp-fun get-object-transform-in-map + ?current-other-obj-desig + ?other-object-transform))) + (lisp-fun get-object-transform-in-map ?current-other-obj-desig + ?other-object-transform)))) + ;; + (lisp-fun get-object-placement-transform + ?object-name ?object-type + ?other-object-name ?other-object-type ?other-object-transform + ?attachment-type + ?attachment-transform-in-map) + (lisp-fun cram-tf:strip-transform-stamped ?attachment-transform-in-map + ?pose-stamped)) + + ;; Resolving (a location + ;; (reachable-for pr2) + ;; (location (on/in (an object + ;; (type robot + (<- (desig:location-grounding ?location-designator ?pose-stamped) + (desig:current-designator ?location-designator ?current-location-designator) + (or (rob-int:reachability-designator ?current-location-designator) + (rob-int:visibility-designator ?current-location-designator)) + (or (and (desig:desig-prop ?current-location-designator (:object ?some-object)) + (desig:current-designator ?some-object ?object) + (lisp-fun man-int:get-object-pose-in-map ?object ?to-reach-pose) + (lisp-pred identity ?to-reach-pose) + (desig:desig-prop ?object (:location ?some-location))) + (desig:desig-prop ?current-location-designator (:location ?some-location))) + (desig:current-designator ?some-location ?location) + ;; if the location is on the robot itself, use the current robot pose + (location-always-reachable ?location) + (lisp-fun cram-tf:robot-current-pose ?pose-stamped))) diff --git a/cram_common/cram_manipulation_interfaces/src/standard-grasps.lisp b/cram_common/cram_manipulation_interfaces/src/standard-grasps.lisp index 974b494ea5..12064df871 100644 --- a/cram_common/cram_manipulation_interfaces/src/standard-grasps.lisp +++ b/cram_common/cram_manipulation_interfaces/src/standard-grasps.lisp @@ -37,10 +37,18 @@ '(( 0 0 -1) (-1 0 0) ( 0 1 0))) +(defparameter *x-across-z-grasp-rotation-2* + '((0 0 -1) + (1 0 0) + (0 -1 0))) (defparameter *-x-across-z-grasp-rotation* '((0 0 1) (1 0 0) (0 1 0))) +(defparameter *-x-across-z-grasp-rotation-2* + '(( 0 0 1) + (-1 0 0) + ( 0 -1 0))) (defparameter *x-across-y-grasp-rotation* '(( 0 0 -1) ( 0 -1 0) @@ -63,6 +71,14 @@ '((-1 0 0) ( 0 0 1) ( 0 1 0))) +(defparameter *y-across-z-flipped-grasp-rotation* + '((-1 0 0) + ( 0 0 -1) + ( 0 -1 0))) +(defparameter *-y-across-z-flipped-grasp-rotation* + '((1 0 0) + (0 0 1) + (0 -1 0))) (defparameter *y-across-x-grasp-rotation* '((0 1 0) (0 0 -1) diff --git a/cram_common/cram_manipulation_interfaces/src/trajectories.lisp b/cram_common/cram_manipulation_interfaces/src/trajectories.lisp index 20dfb87106..8f8e5eac84 100644 --- a/cram_common/cram_manipulation_interfaces/src/trajectories.lisp +++ b/cram_common/cram_manipulation_interfaces/src/trajectories.lisp @@ -1,6 +1,7 @@ ;;; ;;; Copyright (c) 2018, Gayane Kazhoyan ;;; Christopher Pollok +;;; Thomas Lipps ;;; All rights reserved. ;;; ;;; Redistribution and use in source and binary forms, with or without @@ -55,7 +56,7 @@ (ecase arm (:left cram-tf:*robot-left-tool-frame*) (:right cram-tf:*robot-right-tool-frame*))) - (standard-to-particular-gripper-transform ; g'Tg + (standard<-particular-gripper-transform ; g'Tg (cl-transforms-stamped:transform->transform-stamped gripper-tool-frame gripper-tool-frame @@ -64,7 +65,7 @@ '?transform (car (prolog:prolog `(and (cram-robot-interfaces:robot ?robot) - (cram-robot-interfaces:standard-to-particular-gripper-transform + (cram-robot-interfaces:standard<-particular-gripper-transform ?robot ?transform))))))) (base-to-standard-gripper-transform ; bTg' (cram-tf:multiply-transform-stampeds @@ -75,7 +76,7 @@ (cram-tf:multiply-transform-stampeds ; bTg' * g'Tg = bTg cram-tf:*robot-base-frame* gripper-tool-frame base-to-standard-gripper-transform ; bTg' - standard-to-particular-gripper-transform ; g'Tg + standard<-particular-gripper-transform ; g'Tg :result-as-pose-or-transform :pose))) (defun calculate-gripper-pose-in-map (base-to-object-transform arm @@ -108,54 +109,69 @@ Gripper is defined by a convention where Z is pointing towards the object.") (call-with-specific-type #'get-object-type-to-gripper-transform object-type object-name arm grasp))) -(defgeneric get-object-type-to-gripper-pregrasp-transform (object-type object-name - arm grasp grasp-transform) - (:documentation "Returns a transform stamped") - (:method (object-type object-name arm grasp grasp-transform) - (call-with-specific-type #'get-object-type-to-gripper-pregrasp-transform - object-type object-name arm grasp grasp-transform))) - -(defgeneric get-object-type-to-gripper-2nd-pregrasp-transform (object-type object-name - arm grasp grasp-transform) - (:documentation "Returns a transform stamped. Default value is NIL.") - (:method (object-type object-name arm grasp grasp-transform) - (call-with-specific-type #'get-object-type-to-gripper-2nd-pregrasp-transform - object-type object-name arm grasp grasp-transform))) - -(defgeneric get-object-type-to-gripper-lift-transform (object-type object-name - arm grasp grasp-transform) - (:documentation "Returns a transform stamped") - (:method (object-type object-name arm grasp grasp-transform) - (call-with-specific-type #'get-object-type-to-gripper-lift-transform - object-type object-name arm grasp grasp-transform))) - -(defgeneric get-object-type-to-gripper-2nd-lift-transform (object-type object-name - arm grasp grasp-transform) - (:documentation "Returns a transform stamped") - (:method (object-type object-name arm grasp grasp-transform) - (call-with-specific-type #'get-object-type-to-gripper-2nd-lift-transform - object-type object-name arm grasp grasp-transform))) +(defgeneric get-object-type-to-gripper-pregrasp-transforms (object-type object-name + arm grasp location + grasp-transform) + (:documentation "Returns a list of transform stampeds") + (:method (object-type object-name arm grasp location grasp-transform) + (call-with-specific-type #'get-object-type-to-gripper-pregrasp-transforms + object-type object-name arm grasp location + grasp-transform))) + +(defgeneric get-object-type-wrt-base-frame-lift-transforms (object-type + arm grasp location) + (:documentation "Returns a list of transform stampeds bTb representing the +lift and 2nd-lift offset of given `object-type' with `arm' and `grasp' +in `cram-tf:*robot-base-frame*'. Therefore, instantiated methods will +specify how much an object with given `object-type' will be lifted +up in meters after grasping it, where the offset is defined w.r.t. base frame. +Depending on the `location', different lifting trajectories can be defined.") + (:method (object-type arm grasp location) + (call-with-specific-type #'get-object-type-wrt-base-frame-lift-transforms + object-type arm grasp location))) + (defmacro def-object-type-to-gripper-transforms (object-type arm grasp-type &key - (grasp-translation ''(0.0 0.0 0.0)) - (grasp-rot-matrix ''((1.0 0.0 0.0) - (0.0 1.0 0.0) - (0.0 0.0 1.0))) - (pregrasp-offsets ''(0.0 0.0 0.0)) - (2nd-pregrasp-offsets ''(0.0 0.0 0.0)) - (lift-offsets ''(0.0 0.0 0.0)) - (2nd-lift-offsets ''(0.0 0.0 0.0))) + location-type + (grasp-translation + ''(0.0 0.0 0.0)) + (grasp-rot-matrix + ''((1.0 0.0 0.0) + (0.0 1.0 0.0) + (0.0 0.0 1.0))) + (pregrasp-offsets + ''(0.0 0.0 0.0)) + (2nd-pregrasp-offsets + ''(0.0 0.0 0.0)) + (lift-translation + ''(0.0 0.0 0.0)) + (lift-rotation + ''(0.0 0.0 0.0 1.0)) + (2nd-lift-translation + ''(0.0 0.0 0.0)) + (2nd-lift-rotation + ''(0.0 0.0 0.0 1.0))) + "`location-type' is the type of the location for the pregrasp and lift trajectories, + `grasp-translation' is the translation part of oTg-std, + `grasp-rot-matrix' is the rotation part, represented as a rotation matrix 2x2 list of lists, + `pregrasp-offsets' is a list of 3 values, which is the offset of the gripper in object frame, + `2nd-pregrasp-offsets' is the same as pregrasp offsets, for picking it goes after pregrasp, + `lift-translation' and `lift-rotation' are the transform of the gripper in robot base frame, + `2nd-lift-translation' and `2nd-lift-rotation' are similar, they go after lift in picking." `(let ((evaled-object-type ,object-type) (evaled-arm ,arm) (evaled-grasp-type ,grasp-type) + (evaled-location-type ,location-type) (evaled-grasp-translation ,grasp-translation) (evaled-grasp-rot-matrix ,grasp-rot-matrix) (evaled-pregrasp-offsets ,pregrasp-offsets) (evaled-2nd-pregrasp-offsets ,2nd-pregrasp-offsets) - (evaled-lift-offsets ,lift-offsets) - (evaled-2nd-lift-offsets ,2nd-lift-offsets)) + (evaled-lift-translation ,lift-translation) + (evaled-lift-rotation ,lift-rotation) + (evaled-2nd-lift-translation ,2nd-lift-translation) + (evaled-2nd-lift-rotation ,2nd-lift-rotation)) (let ((object-list (if (listp evaled-object-type) evaled-object-type @@ -164,8 +180,10 @@ Gripper is defined by a convention where Z is pointing towards the object.") (if (listp evaled-arm) evaled-arm (list evaled-arm)))) + (mapcar (lambda (object) (mapcar (lambda (arm) + (let ((transform (cl-transforms-stamped:make-transform-stamped (roslisp-utilities:rosify-underscores-lisp-name object) @@ -177,8 +195,31 @@ Gripper is defined by a convention where Z is pointing towards the object.") (third evaled-grasp-translation)) (cl-transforms:matrix->quaternion (make-array '(3 3) - :initial-contents evaled-grasp-rot-matrix))))) - + :initial-contents evaled-grasp-rot-matrix)))) + (lift-transform + (cl-transforms-stamped:make-transform + (cl-transforms:make-3d-vector + (first evaled-lift-translation) + (second evaled-lift-translation) + (third evaled-lift-translation)) + (cl-transforms:make-quaternion + (first evaled-lift-rotation) + (second evaled-lift-rotation) + (third evaled-lift-rotation) + (fourth evaled-lift-rotation)))) + (2nd-lift-transform + (cl-transforms-stamped:make-transform + (cl-transforms:make-3d-vector + (first evaled-2nd-lift-translation) + (second evaled-2nd-lift-translation) + (third evaled-2nd-lift-translation)) + (cl-transforms:make-quaternion + (first evaled-2nd-lift-rotation) + (second evaled-2nd-lift-rotation) + (third evaled-2nd-lift-rotation) + (fourth evaled-2nd-lift-rotation))))) + + evaled-location-type ; just to get rid of unused warning (pushnew evaled-grasp-type *known-grasp-types*) (defmethod get-object-type-to-gripper-transform ((object-type (eql object)) @@ -196,60 +237,49 @@ Gripper is defined by a convention where Z is pointing towards the object.") (error "Grasp transform not defined for object type ~a with arm ~a and grasp ~a~%" object-type arm grasp)))) - (defmethod get-object-type-to-gripper-pregrasp-transform ((object-type (eql object)) - object-name - (arm (eql arm)) - (grasp (eql evaled-grasp-type)) - grasp-transform) - (let ((pregrasp-offsets evaled-pregrasp-offsets)) - (if pregrasp-offsets - (destructuring-bind (x y z) pregrasp-offsets - (cram-tf:translate-transform-stamped - grasp-transform - :x-offset x :y-offset y :z-offset z)) - (error "Pregrasp transform not defined for object type ~a with arm ~a and grasp ~a~%" - object-type arm grasp)))) - - (defmethod get-object-type-to-gripper-2nd-pregrasp-transform ((object-type (eql object)) - object-name - (arm (eql arm)) - (grasp (eql evaled-grasp-type)) - grasp-transform) - (let ((offsets evaled-2nd-pregrasp-offsets)) - (if offsets - (destructuring-bind (x y z) offsets - (cram-tf:translate-transform-stamped - grasp-transform - :x-offset x :y-offset y :z-offset z)) - (error "2nd pregrasp transform not defined for object type ~a with arm ~a and grasp ~a~%" + (defmethod get-object-type-to-gripper-pregrasp-transforms ((object-type (eql object)) + object-name + (arm (eql arm)) + (grasp (eql evaled-grasp-type)) + ,(if location-type + '(location + (eql evaled-location-type)) + 'location) + grasp-transform) + (let ((pregrasp-offsets evaled-pregrasp-offsets) + (2nd-pregrasp-offsets evaled-2nd-pregrasp-offsets)) + (if (and pregrasp-offsets 2nd-pregrasp-offsets) + (list + (destructuring-bind (x y z) pregrasp-offsets + (cram-tf:translate-transform-stamped + grasp-transform + :x-offset x :y-offset y :z-offset z)) + (destructuring-bind (x y z) 2nd-pregrasp-offsets + (cram-tf:translate-transform-stamped + grasp-transform + :x-offset x :y-offset y :z-offset z))) + (error "Pregrasp transforms not defined for object type ~a with arm ~a and grasp ~a~%" object-type arm grasp)))) - (defmethod get-object-type-to-gripper-lift-transform ((object-type (eql object)) - object-name - (arm (eql arm)) - (grasp (eql evaled-grasp-type)) - grasp-transform) - (let ((offsets evaled-lift-offsets)) - (if offsets - (destructuring-bind (x y z) offsets - (cram-tf:translate-transform-stamped - grasp-transform - :x-offset x :y-offset y :z-offset z)) - (error "Lift transform not defined for object type ~a with arm ~a and grasp ~a~%" - object-type arm grasp)))) - - (defmethod get-object-type-to-gripper-2nd-lift-transform ((object-type (eql object)) - object-name - (arm (eql arm)) - (grasp (eql evaled-grasp-type)) - grasp-transform) - (let ((offsets evaled-2nd-lift-offsets)) - (if offsets - (destructuring-bind (x y z) offsets - (cram-tf:translate-transform-stamped - grasp-transform - :x-offset x :y-offset y :z-offset z)) - (error "2nd lift transform not defined for object type ~a with arm ~a and grasp ~a~%" + (defmethod get-object-type-wrt-base-frame-lift-transforms ((object-type (eql object)) + (arm (eql arm)) + (grasp (eql evaled-grasp-type)) + ,(if location-type + '(location + (eql evaled-location-type)) + 'location)) + (let ((this-lift-transform lift-transform) + (this-2nd-lift-transform 2nd-lift-transform)) + (if (and this-lift-transform this-2nd-lift-transform) + (list + (cl-transforms-stamped:transform->transform-stamped + cram-tf:*robot-base-frame* cram-tf:*robot-base-frame* 0.0 + this-lift-transform) + (cl-transforms-stamped:transform->transform-stamped + cram-tf:*robot-base-frame* cram-tf:*robot-base-frame* 0.0 + this-2nd-lift-transform)) + (error "Lift transforms w.r.t. base frame not defined ~ + for object type ~a with arm ~a and grasp ~a~%" object-type arm grasp)))) )) @@ -261,6 +291,7 @@ Gripper is defined by a convention where Z is pointing towards the object.") (defmethod get-action-trajectory :heuristics 20 ((action-type (eql :picking-up)) arm grasp + location objects-acted-on &key) (let* ((object @@ -269,11 +300,25 @@ Gripper is defined by a convention where Z is pointing towards the object.") (desig:desig-prop-value object :name)) (object-type (desig:desig-prop-value object :type)) + (oTg-std + (get-object-type-to-gripper-transform + object-type object-name arm grasp)) (bTo (man-int:get-object-transform object)) - (oTg-std - (man-int:get-object-type-to-gripper-transform - object-type object-name arm grasp))) + (oTb + (cram-tf:transform-stamped-inv bTo)) + (bTb-lifts + (get-object-type-wrt-base-frame-lift-transforms + object-type arm grasp location)) + (oTg-lifts + (mapcar (lambda (btb-lift) + (reduce #'cram-tf:apply-transform + `(,oTb ,bTb-lift ,bTo ,oTg-std) + :from-end T)) + bTb-lifts)) + (oTg-pregrasps + (get-object-type-to-gripper-pregrasp-transforms + object-type object-name arm grasp location oTg-std))) (mapcar (lambda (label transforms) (make-traj-segment @@ -283,30 +328,64 @@ Gripper is defined by a convention where Z is pointing towards the object.") '(:reaching :grasping :lifting) - `((,(man-int:get-object-type-to-gripper-pregrasp-transform - object-type object-name arm grasp oTg-std) - ,(man-int:get-object-type-to-gripper-2nd-pregrasp-transform - object-type object-name arm grasp oTg-std)) + `(,oTg-pregrasps (,oTg-std) - (,(man-int:get-object-type-to-gripper-lift-transform - object-type object-name arm grasp oTg-std) - ,(man-int:get-object-type-to-gripper-2nd-lift-transform - object-type object-name arm grasp oTg-std)))))) + ,oTg-lifts)))) (defmethod get-action-trajectory :heuristics 20 ((action-type (eql :placing)) arm grasp + location objects-acted-on &key target-object-transform-in-base) (let* ((object - (car objects-acted-on)) + (first objects-acted-on)) (object-name (desig:desig-prop-value object :name)) (object-type (desig:desig-prop-value object :type)) - (oTg-std + (other-object + (second objects-acted-on)) + (other-object-type + (desig:desig-prop-value other-object :type)) + (attachment + (third objects-acted-on)) + (bTo + target-object-transform-in-base) + (oTb + (cram-tf:transform-stamped-inv bTo)) + (drop-z-offset + (get-z-offset-for-placing-with-dropping + object-type other-object-type attachment)) + (bTb-drop-z-offset + (cl-transforms-stamped:make-transform-stamped + cram-tf:*robot-base-frame* + cram-tf:*robot-base-frame* + 0.0 + (cl-transforms:make-3d-vector 0 0 drop-z-offset) + (cl-transforms:make-identity-rotation))) + (oTg-std-no-z-offset (get-object-type-to-gripper-transform - object-type object-name arm grasp))) + object-type object-name arm grasp)) + (oTg-std + (reduce #'cram-tf:apply-transform + `(,oTb ,bTb-drop-z-offset ,bTo ,oTg-std-no-z-offset) + :from-end T)) + (bTb-lifts + (get-object-type-wrt-base-frame-lift-transforms + object-type arm grasp location)) + (oTg-lifts + (reverse + (mapcar + (lambda (btb-lift) + (reduce #'cram-tf:apply-transform + `(,oTb ,bTb-lift ,bTo ,oTg-std) + :from-end T)) + bTb-lifts))) + (oTg-pregrasps + (reverse + (get-object-type-to-gripper-pregrasp-transforms + object-type object-name arm grasp location oTg-std)))) (mapcar (lambda (label transforms) (make-traj-segment @@ -317,15 +396,9 @@ Gripper is defined by a convention where Z is pointing towards the object.") '(:reaching :putting :retracting) - `((,(man-int:get-object-type-to-gripper-2nd-lift-transform - object-type object-name arm grasp oTg-std) - ,(man-int:get-object-type-to-gripper-lift-transform - object-type object-name arm grasp oTg-std)) + `(,oTg-lifts (,oTg-std) - (,(man-int:get-object-type-to-gripper-2nd-pregrasp-transform - object-type object-name arm grasp oTg-std) - ,(man-int:get-object-type-to-gripper-pregrasp-transform - object-type object-name arm grasp oTg-std)))))) + ,oTg-pregrasps)))) @@ -338,22 +411,32 @@ Gripper is defined by a convention where Z is pointing towards the object.") other-object-type other-object-name attachment)) +(defgeneric get-z-offset-for-placing-with-dropping (object-type other-object-type attachment) + (:documentation "Returns a Z offset in the cram-tf:*robot-base-frame* in meters +for dropping given `object-type' on the `other-object-type', with the given +`attachemnt' placement pose type.") + (:method (object-type other-object-type attachment) + "Per default, the robot touches the object with the other object +before opening the gripper, such that no dropping offset is necessary." + 0.0)) + (defun get-object-placement-transform (object-name object-type - other-object-name other-object-type other-object-transform + other-object-name other-object-type + other-object-transform attachment-type) - "Returns a transform in robot base frame where the object named `object-name' should go" - (let* ((base-frame - cram-tf:*robot-base-frame*) + "Returns a transform in fixed frame where the object named `object-name' should go" + (let* ((fixed-frame + cram-tf:*fixed-frame*) (object-frame (roslisp-utilities:rosify-underscores-lisp-name object-name)) - (base-to-object-transform ; bTo = bToo * ooTo + (map-to-object-transform ; mTo = mToo * ooTo (cram-tf:multiply-transform-stampeds - base-frame + fixed-frame object-frame other-object-transform (get-object-type-in-other-object-transform ; ooTo object-type object-name other-object-type other-object-name attachment-type)))) - base-to-object-transform)) + map-to-object-transform)) diff --git a/cram_common/cram_mobile_pick_place_plans/cram-mobile-pick-place-plans.asd b/cram_common/cram_mobile_pick_place_plans/cram-mobile-pick-place-plans.asd index 39374e9286..cddc0a39e7 100644 --- a/cram_common/cram_mobile_pick_place_plans/cram-mobile-pick-place-plans.asd +++ b/cram_common/cram_mobile_pick_place_plans/cram-mobile-pick-place-plans.asd @@ -43,7 +43,7 @@ cram-designators cram-occasions-events cram-executive - cram-utilities ; for cut:var-value of prolog stuff + cram-utilities ; for cut:var-value of prolog stuff and equalize-lists cram-tf cram-plan-occasions-events diff --git a/cram_common/cram_mobile_pick_place_plans/src/atomic-action-designators.lisp b/cram_common/cram_mobile_pick_place_plans/src/atomic-action-designators.lisp index 4802f56cb8..6261b7570e 100644 --- a/cram_common/cram_mobile_pick_place_plans/src/atomic-action-designators.lisp +++ b/cram_common/cram_mobile_pick_place_plans/src/atomic-action-designators.lisp @@ -33,7 +33,8 @@ (<- (desig:action-grounding ?action-designator (go-to-target ?resolved-action-designator)) (spec:property ?action-designator (:type :going)) - (spec:property ?action-designator (:target ?location-designator)) + (spec:property ?action-designator (:target ?some-location-designator)) + (desig:current-designator ?some-location-designator ?location-designator) (desig:designator-groundings ?location-designator ?poses) (member ?pose-stamped ?poses) (desig:designator :action ((:type :going) @@ -48,6 +49,53 @@ + (<- (infer-prefer-base ?action-designator ?prefer-base) + ;; infer if the robot should prefer to move the base more than arms + ;; prefer-base is only true when we're opening prismatic containers + (-> (and (spec:property ?action-designator (:type :pulling)) + (spec:property ?action-designator (:container-object ?container-designator)) + (spec:property ?container-designator (:type ?container-type)) + (man-int:object-type-subtype :container-prismatic ?container-type)) + (equal ?prefer-base t) + (equal ?prefer-base nil))) + + (<- (infer-move-base ?action-designator ?move-base) + ;; infer if we should move the base at all or not + ;; we shouldn't move the base if we're getting something of our own back + (-> (and (or (spec:property ?action-designator (:type :reaching)) + (spec:property ?action-designator (:type :grasping))) + (or (and (spec:property ?action-designator + (:object ?some-object-designator)) + (desig:current-designator ?some-object-designator + ?object-designator) + (spec:property ?object-designator + (:location ?some-location-designator))) + (spec:property ?action-designator + (:location ?some-location-designator))) + (desig:current-designator ?some-location-designator ?location-designator) + (spec:property ?location-designator (:on ?on-object-designator)) + (spec:property ?on-object-designator (:name ?robot-name)) + (rob-int:robot ?robot-name)) + (equal ?move-base nil) + (equal ?move-base t))) + + (<- (infer-align-planes ?action-designator ?align-planes-left ?align-planes-right) + ;; infer if we should keep the object in hand upright + ;; that should currently always happen if we have an object in hand + (-> (cpoe:object-in-hand ?_ :left) + (equal ?align-planes-left t) + (equal ?align-planes-left nil)) + (-> (cpoe:object-in-hand ?_ :right) + (equal ?align-planes-right t) + (equal ?align-planes-right nil))) + + (<- (infer-motion-flags ?action-designator + ?prefer-base ?move-base + ?align-planes-left ?align-planes-right) + (infer-prefer-base ?action-designator ?prefer-base) + (infer-move-base ?action-designator ?move-base) + (infer-align-planes ?action-designator ?align-planes-left ?align-planes-right)) + (<- (desig:action-grounding ?action-designator (move-arms-in-sequence ?resolved-action-designator)) (or (spec:property ?action-designator (:type :reaching)) @@ -58,53 +106,48 @@ (equal ?left-poses nil))) (once (or (spec:property ?action-designator (:right-poses ?right-poses)) (equal ?right-poses nil))) + (infer-motion-flags ?action-designator + ?_ ?move-base ?align-planes-left ?align-planes-right) (desig:designator :action ((:type ?action-type) (:left-poses ?left-poses) (:right-poses ?right-poses) - (:collision-mode :avoid-all)) + (:collision-mode :avoid-all) + (:move-base ?move-base) + (:align-planes-left ?align-planes-left) + (:align-planes-right ?align-planes-right)) ?resolved-action-designator)) (<- (desig:action-grounding ?action-designator (move-arms-in-sequence ?resolved-action-designator)) - (or (spec:property ?action-designator (:type :grasping)) - (spec:property ?action-designator (:type :pulling))) + (spec:property ?action-designator (:type :grasping)) (spec:property ?action-designator (:type ?action-type)) (spec:property ?action-designator (:object ?object-designator)) (spec:property ?object-designator (:name ?object-name)) - (or (spec:property ?action-designator (:link ?object-link)) - (equal ?object-link nil)) (once (or (spec:property ?action-designator (:left-poses ?left-poses)) (equal ?left-poses nil))) (once (or (spec:property ?action-designator (:right-poses ?right-poses)) (equal ?right-poses nil))) - (or (and (spec:property ?action-designator (:type :grasping)) - (desig:designator :action ((:type ?action-type) - (:left-poses ?left-poses) - (:right-poses ?right-poses) - (:collision-mode :allow-hand) - (:collision-object-b ?object-name) - (:collision-object-b-link ?object-link)) - ?resolved-action-designator)) - (and (spec:property ?action-designator (:type :pulling)) - (spec:property ?action-designator (:container-object ?container-designator)) - (spec:property ?container-designator (:type ?container-type)) - (or (and (man-int:object-type-subtype :container-prismatic ?container-type) - (desig:designator :action ((:type ?action-type) - (:left-poses ?left-poses) - (:right-poses ?right-poses) - (:collision-mode :allow-hand) - (:collision-object-b ?object-name) - (:collision-object-b-link ?object-link) - (:move-the-ass t)) - ?resolved-action-designator)) - (desig:designator :action ((:type ?action-type) - (:left-poses ?left-poses) - (:right-poses ?right-poses) - (:collision-mode :allow-hand) - (:collision-object-b ?object-name) - (:collision-object-b-link ?object-link) - (:move-the-ass nil)) - ?resolved-action-designator))))) + (infer-motion-flags ?action-designator + ?prefer-base ?move-base + ?align-planes-left ?align-planes-right) + ;; infer collision-object-b and collision-object-b-link + (-> (cpoe:object-in-hand ?object-designator ?_ ?_ ?_) + (and (rob-int:robot ?robot) + (equal ?collision-object-b ?robot) + (equal ?object-link ?object-name)) + (and (equal ?collision-object-b ?object-name) + (equal ?object-link nil))) + (desig:designator :action ((:type ?action-type) + (:left-poses ?left-poses) + (:right-poses ?right-poses) + (:collision-mode :allow-hand) + (:collision-object-b ?collision-object-b) + (:collision-object-b-link ?object-link) + (:prefer-base ?prefer-base) + (:move-base ?move-base) + (:align-planes-left ?align-planes-left) + (:align-planes-right ?align-planes-right)) + ?resolved-action-designator)) (<- (desig:action-grounding ?action-designator (move-arms-in-sequence ?resolved-action-designator)) @@ -123,6 +166,8 @@ (equal ?left-poses nil))) (once (or (spec:property ?action-designator (:right-poses ?right-poses)) (equal ?right-poses nil))) + (infer-motion-flags ?action-designator + ?_ ?move-base ?align-planes-left ?align-planes-right) ;; putting should actually allow hand and attached if grasping allows hand (desig:designator :action ((:type :putting) (:left-poses ?left-poses) @@ -131,20 +176,43 @@ ) (:collision-object-b ?other-object-name) (:collision-object-b-link ?object-link) - (:collision-object-a ?object-name)) + (:collision-object-a ?object-name) + (:move-base ?move-base) + (:align-planes-left ?align-planes-left) + (:align-planes-right ?align-planes-right)) ?resolved-action-designator)) - (<- (desig:action-grounding ?action-designator (move-arms-in-sequence + (<- (desig:action-grounding ?action-designator (manipulate-environment ?resolved-action-designator)) - (or (spec:property ?action-designator (:type :pushing))) - (once (or (spec:property ?action-designator (:left-poses ?left-poses)) - (equal ?left-poses nil))) - (once (or (spec:property ?action-designator (:right-poses ?right-poses)) - (equal ?right-poses nil))) - (desig:designator :action ((:type :pushing) - (:left-poses ?left-poses) - (:right-poses ?right-poses) - (:collision-mode :allow-all)) + (or (and (spec:property ?action-designator (:type :pulling)) + (equal ?collision-mode :allow-hand)) + (and (spec:property ?action-designator (:type :pushing)) + (equal ?collision-mode :allow-arm))) + (or (and (spec:property ?action-designator (:left-poses ?poses)) + (equal ?arm :left)) + (and (spec:property ?action-designator (:right-poses ?poses)) + (equal ?arm :right))) + (spec:property ?action-designator (:type ?action-type)) + (spec:property ?action-designator (:object ?environment-object-designator)) + (spec:property ?environment-object-designator (:name ?environment-name)) + (spec:property ?action-designator (:link ?handle-link)) + (once (or (spec:property ?action-designator (:distance ?joint-angle)) + (equal ?joint-angle NIL))) + ;; infer the missing parameters + (infer-motion-flags ?action-designator + ?prefer-base ?move-base + ?align-planes-left ?align-planes-right) + (desig:designator :action ((:type ?action-type) + (:arm ?arm) + (:poses ?poses) + (:distance ?joint-angle) + (:collision-mode ?collision-mode) + (:collision-object-b ?environment-name) + (:collision-object-b-link ?handle-link) + (:prefer-base ?prefer-base) + (:move-base ?move-base) + (:align-planes-left ?align-planes-left) + (:align-planes-right ?align-planes-right)) ?resolved-action-designator)) (<- (desig:action-grounding ?action-designator (move-arms-into-configuration @@ -152,24 +220,44 @@ (spec:property ?action-designator (:type :positioning-arm)) (rob-int:robot ?robot) (-> (spec:property ?action-designator (:left-configuration ?left-config)) - (-> (equal ?left-config :park) - (-> (cpoe:object-in-hand ?_ :left) - (rob-int:robot-joint-states ?robot :arm :left :carry ?left-joint-states) - (rob-int:robot-joint-states ?robot :arm :left :park ?left-joint-states)) - (rob-int:robot-joint-states ?robot :arm :left ?left-config ?left-joint-states)) + (man-int:joint-state-for-arm-config ?robot ?left-config :left + ?left-joint-states) (equal ?left-joint-states nil)) (-> (spec:property ?action-designator (:right-configuration ?right-config)) - (-> (equal ?right-config :park) - (-> (cpoe:object-in-hand ?_ :right) - (rob-int:robot-joint-states ?robot :arm :right :carry ?right-joint-states) - (rob-int:robot-joint-states ?robot :arm :right :park ?right-joint-states)) - (rob-int:robot-joint-states ?robot :arm :right ?right-config ?right-joint-states)) + (man-int:joint-state-for-arm-config ?robot ?right-config :right + ?right-joint-states) (equal ?right-joint-states nil)) + (infer-align-planes ?action-designator ?align-planes-left ?align-planes-right) (desig:designator :action ((:type :positioning-arm) (:left-joint-states ?left-joint-states) - (:right-joint-states ?right-joint-states)) + (:right-joint-states ?right-joint-states) + (:align-planes-left ?align-planes-left) + (:align-planes-right ?align-planes-right)) ?resolved-action-designator)) + (<- (desig:action-grounding ?action-designator (park-arms ?resolved-action-desig)) + (spec:property ?action-designator (:type :parking-arms)) + ;; get the arms list from the designator or infer it + (once (or (spec:property ?action-designator (:arms ?arms-list)) + (-> (spec:property ?action-designator (:not-neck T)) + (and (rob-int:robot ?robot-name) + (rob-int:arms-that-are-not-neck ?robot-name ?arms-list)) + (and (rob-int:robot ?robot-name) + (rob-int:arms ?robot-name ?arms-list))))) + ;; see if left arm and right arm are present + ;; this is super non-general but has to be like this + ;; because positioning-arm is so non-general + (-> (member :left ?arms-list) + (equal ?left-arm-p T) + (equal ?left-arm-p NIL)) + (-> (member :right ?arms-list) + (equal ?right-arm-p T) + (equal ?right-arm-p NIL)) + (desig:designator :action ((:type :parking-arms) + (:left-arm ?left-arm-p) + (:right-arm ?right-arm-p)) + ?resolved-action-desig)) + (<- (desig:action-grounding ?action-designator (release ?action-designator)) @@ -178,7 +266,14 @@ (once (or (spec:property ?action-designator (:object ?_)) (true)))) - (<- (desig:action-grounding ?action-designator (grip ?augmented-action-designator)) + (<- (desig:action-grounding ?action-designator (grip ?action-designator)) + (spec:property ?action-designator (:type :gripping)) + (spec:property ?action-designator (:gripper ?_)) + (not (spec:property ?action-designator (:object ?_))) + (once (or (spec:property ?action-designator (:effort ?_)) + (true)))) + + (<- (desig:action-grounding ?action-designator (grip ?action-designator)) (spec:property ?action-designator (:type :gripping)) (spec:property ?action-designator (:gripper ?_)) (spec:property ?action-designator (:object ?object-designator)) @@ -188,16 +283,7 @@ (once (or (spec:property ?action-designator (:grasp ?_)) (true))) (once (or (spec:property ?action-designator (:effort ?_)) - (true))) - ;; make a new object designator that will be equated to the old one - ;; after the successful grasp - (desig:current-designator ?object-designator ?current-object-desig) - (lisp-fun desig:rename-designator-property-key ?current-object-desig - :pose :old-pose ?new-object-desig) - ;; extend the old action designator with a new OBJECT property - (equal ?new-description ((:grasped-object ?new-object-desig))) - (lisp-fun desig:copy-designator ?action-designator :new-description ?new-description - ?augmented-action-designator)) + (true)))) (<- (desig:action-grounding ?action-designator (set-gripper-to-position ?action-designator)) (spec:property ?action-designator (:type :setting-gripper)) diff --git a/cram_common/cram_mobile_pick_place_plans/src/atomic-action-plans.lisp b/cram_common/cram_mobile_pick_place_plans/src/atomic-action-plans.lisp index def2343bcb..aa4a24cf62 100644 --- a/cram_common/cram_mobile_pick_place_plans/src/atomic-action-plans.lisp +++ b/cram_common/cram_mobile_pick_place_plans/src/atomic-action-plans.lisp @@ -52,8 +52,8 @@ (defun go-with-torso (&key - ((:joint-angle ?joint-angle)) - &allow-other-keys) + ((:joint-angle ?joint-angle)) + &allow-other-keys) (declare (type (or number keyword) ?joint-angle)) "Go to `?joint-angle' with torso, if a failure happens propagate it up, robot-state-changed event." (unwind-protect @@ -79,12 +79,16 @@ ((:collision-object-b ?collision-object-b)) ((:collision-object-b-link ?collision-object-b-link)) ((:collision-object-a ?collision-object-a)) - ((:move-the-ass ?move-the-ass)) + ((:move-base ?move-base)) + ((:prefer-base ?prefer-base)) + ((:align-planes-left ?align-planes-left)) + ((:align-planes-right ?align-planes-right)) &allow-other-keys) (declare (type (or list cl-transforms-stamped:pose-stamped) left-poses right-poses) (type (or null keyword) ?collision-mode) (type (or null symbol) ?collision-object-b ?collision-object-a) - (type (or null string symbol) ?collision-object-b-link)) + (type (or null string symbol) ?collision-object-b-link) + (type boolean ?move-base ?prefer-base ?align-planes-left ?align-planes-right)) "Move arms through all but last poses of `left-poses' and `right-poses', while ignoring failures; and execute the last pose with propagating the failures." @@ -120,8 +124,14 @@ while ignoring failures; and execute the last pose with propagating the failures (collision-object-b-link ?collision-object-b-link)) (desig:when ?collision-object-a (collision-object-a ?collision-object-a)) - (desig:when ?move-the-ass - (move-the-ass ?move-the-ass)))) + (desig:when ?move-base + (move-base ?move-base)) + (desig:when ?prefer-base + (prefer-base ?prefer-base)) + (desig:when ?align-planes-left + (align-planes-left ?align-planes-left)) + (desig:when ?align-planes-right + (align-planes-right ?align-planes-right)))) (cram-occasions-events:on-event (make-instance 'cram-plan-occasions-events:robot-state-changed)))) @@ -152,16 +162,78 @@ while ignoring failures; and execute the last pose with propagating the failures (collision-object-b-link ?collision-object-b-link)) (desig:when ?collision-object-a (collision-object-a ?collision-object-a)) - (desig:when ?move-the-ass - (move-the-ass ?move-the-ass)))) + (desig:when ?move-base + (move-base ?move-base)) + (desig:when ?prefer-base + (prefer-base ?prefer-base)) + (desig:when ?align-planes-left + (align-planes-left ?align-planes-left)) + (desig:when ?align-planes-right + (align-planes-right ?align-planes-right)))) (cram-occasions-events:on-event (make-instance 'cram-plan-occasions-events:robot-state-changed))))) +(defun manipulate-environment (&key + ((:type ?type)) + ((:arm ?arm)) + ((:poses ?poses)) + ((:distance ?distance)) + ((:collision-mode ?collision-mode)) + ((:collision-object-b ?collision-object-b)) + ((:collision-object-b-link ?collision-object-b-link)) + ((:collision-object-a ?collision-object-a)) + ((:move-base ?move-base)) + ((:prefer-base ?prefer-base)) + ((:align-planes-left ?align-planes-left)) + ((:align-planes-right ?align-planes-right)) + &allow-other-keys) + (declare (type keyword ?type ?arm) + (type list ?poses) + (type (or number null) ?distance) + (type (or keyword null) ?collision-mode) + (type (or symbol null) ?collision-object-b ?collision-object-a) + (type (or string symbol null) ?collision-object-b-link) + (type boolean ?move-base ?prefer-base + ?align-planes-left ?align-planes-right)) + "Execute an environment manipulation trajectory. +In projection it would be executed by following the list of poses in cartesian space. +With a continuous motion planner one could have fluent arch trajectories etc. +`?type' is either :PUSHING or :PULLING." + + (unwind-protect + (exe:perform + (desig:a motion + (type ?type) + (arm ?arm) + (poses ?poses) + (desig:when ?distance + (joint-angle ?distance)) + (desig:when ?collision-mode + (collision-mode ?collision-mode)) + (desig:when ?collision-object-b + (collision-object-b ?collision-object-b)) + (desig:when ?collision-object-b-link + (collision-object-b-link ?collision-object-b-link)) + (desig:when ?collision-object-a + (collision-object-a ?collision-object-a)) + (desig:when ?move-base + (move-base ?move-base)) + (desig:when ?prefer-base + (prefer-base ?prefer-base)) + (desig:when ?align-planes-left + (align-planes-left ?align-planes-left)) + (desig:when ?align-planes-right + (align-planes-right ?align-planes-right)))) + (cram-occasions-events:on-event + (make-instance 'cram-plan-occasions-events:robot-state-changed)))) + (defun move-arms-into-configuration (&key ((:left-joint-states ?left-joint-states)) ((:right-joint-states ?right-joint-states)) + ((:align-planes-left ?align-planes-left)) + ((:align-planes-right ?align-planes-right)) &allow-other-keys) (declare (type list ?left-joint-states ?right-joint-states)) "Calls moving-arm-joints motion, while ignoring failures, and robot-state-changed event." @@ -179,7 +251,11 @@ while ignoring failures; and execute the last pose with propagating the failures (desig:when ?left-joint-states (left-joint-states ?left-joint-states)) (desig:when ?right-joint-states - (right-joint-states ?right-joint-states)))) + (right-joint-states ?right-joint-states)) + (desig:when ?align-planes-left + (align-planes-left ?align-planes-left)) + (desig:when ?align-planes-right + (align-planes-right ?align-planes-right)))) ;; (cpl:seq ;; (exe:perform ;; (desig:a motion @@ -224,7 +300,6 @@ while ignoring failures; and execute the last pose with propagating the failures ((:gripper ?left-or-right)) ((:effort ?effort)) ((:object object-designator)) - ((:grasped-object new-object-designator)) ((:grasp ?grasp)) &allow-other-keys) (declare (type (or keyword list) ?left-or-right) @@ -247,13 +322,14 @@ In any case, issue ROBOT-STATE-CHANGED event." (desig:when ?effort (effort ?effort)))) (roslisp:ros-info (pick-place grip) "Assert grasp into knowledge base") - (cram-occasions-events:on-event - (make-instance 'cpoe:object-attached-robot - :arm ?left-or-right - :object-name (desig:desig-prop-value object-designator :name) - :grasp ?grasp)) - (desig:equate object-designator new-object-designator) - new-object-designator)) + (when object-designator + (cram-occasions-events:on-event + (make-instance 'cpoe:object-attached-robot + :arm ?left-or-right + :object-name (desig:desig-prop-value object-designator :name) + :object-designator object-designator + :grasp ?grasp)) + (desig:current-desig object-designator)))) (cram-occasions-events:on-event (make-instance 'cram-plan-occasions-events:robot-state-changed)))) @@ -337,9 +413,11 @@ In any case, issue ROBOT-STATE-CHANGED event." (declare (type desig:object-designator ?object-designator)) "Call detecting motion on `?object-designator', retry on failure, issue perceived event, equate resulting designator to the original one." - (let ((retries (if (find :cad-model (desig:properties ?object-designator) :key #'car) - 1 - 4))) + (let ((retries 1 + ;; (if (find :cad-model (desig:properties ?object-designator) :key #'car) + ;; 1 + ;; 4) + )) (cpl:with-retry-counters ((perceive-retries retries)) (cpl:with-failure-handling ((common-fail:perception-low-level-failure (e) @@ -355,19 +433,38 @@ equate resulting designator to the original one." (resulting-designator (funcall object-chosing-function resulting-designators))) (if (listp resulting-designators) - (mapcar (lambda (desig) - (cram-occasions-events:on-event - (make-instance 'cram-plan-occasions-events:object-perceived-event - :object-designator desig - :perception-source :whatever)) - ;; doesn't make sense to equate all these desigs together - ;; (desig:equate ?object-designator desig) - ) - resulting-designators) + (mapc (lambda (desig) + (cram-occasions-events:on-event + (make-instance 'cram-plan-occasions-events:object-perceived-event + :object-designator desig + :perception-source :whatever)) + ;; doesn't make sense to equate all these desigs together + ;; (desig:equate ?object-designator desig) + ) + resulting-designators) (progn (cram-occasions-events:on-event (make-instance 'cram-plan-occasions-events:object-perceived-event :object-designator resulting-designators :perception-source :whatever)) (desig:equate ?object-designator resulting-designator))) - resulting-designator))))) + (desig:current-desig resulting-designator)))))) + + +(defun park-arms (&key + ((:left-arm ?left-arm-p)) + ((:right-arm ?right-arm-p)) + &allow-other-keys) + (declare (type boolean ?left-arm-p ?right-arm-p)) + "Puts the arms into a parking configuration" + (let* ((left-config (when ?left-arm-p :park)) + (right-config (when ?right-arm-p :park)) + (?goal `(cpoe:arms-positioned-at ,left-config ,right-config))) + (exe:perform + (desig:an action + (type positioning-arm) + (desig:when ?left-arm-p + (left-configuration park)) + (desig:when ?right-arm-p + (right-configuration park)) + (goal ?goal))))) diff --git a/cram_common/cram_mobile_pick_place_plans/src/high-level-plans.lisp b/cram_common/cram_mobile_pick_place_plans/src/high-level-plans.lisp index 4bdb7c67a5..2e7cec1bf6 100644 --- a/cram_common/cram_mobile_pick_place_plans/src/high-level-plans.lisp +++ b/cram_common/cram_mobile_pick_place_plans/src/high-level-plans.lisp @@ -84,9 +84,7 @@ (defun perceive-and-drive-and-pick-up-plan (?type &key (?arm '(:left :right)) ?color ?cad-model) (exe:perform (desig:an action - (type positioning-arm) - (left-configuration park) - (right-configuration park))) + (type parking-arms))) (let ((object-description `((:type ,?type)))) (when ?color (push `(:color ,?color) object-description)) @@ -133,7 +131,7 @@ ;; cram-tf:*fixed-frame* ;; :use-zero-time t))) ;; -;; (let ((?pose-for-base (cl-tf:pose->pose-stamped +;; (let ((?pose-for-base (cl-transforms:pose->pose-stamped ;; "map" ;; 0.0 ;; (cl-transforms-stamped:make-identity-pose)))) diff --git a/cram_common/cram_mobile_pick_place_plans/src/pick-place-designators.lisp b/cram_common/cram_mobile_pick_place_plans/src/pick-place-designators.lisp index 041891a421..3bf5b0f7c4 100644 --- a/cram_common/cram_mobile_pick_place_plans/src/pick-place-designators.lisp +++ b/cram_common/cram_mobile_pick_place_plans/src/pick-place-designators.lisp @@ -38,11 +38,31 @@ (cram-tf:pose-stamped->transform-stamped target-pose-in-base child-frame-rosy))) +(defun split-attachments-desig (location-designator) + (let ((attachments (desig:desig-prop-value location-designator :attachments))) + (loop for attachment in attachments + collecting (desig:make-designator + :location + ;; cannot equate these guys because they will all end up + ;; being the same location designator + `((:attachment ,attachment) + ,@(remove :attachments (desig:properties location-designator) + :key #'car)))))) + + + (def-fact-group pick-and-place-plans (desig:action-grounding) - (<- (desig:action-grounding ?action-designator (perceive ?action-designator)) + (<- (desig:action-grounding ?action-designator (perceive ?resolved-action-desig)) (spec:property ?action-designator (:type :perceiving)) - (spec:property ?action-designator (:object ?_))) + (spec:property ?action-designator (:object ?object-designator)) + (-> (man-int:object-or-its-reference-in-hand ?object-designator ?object-hand) + (equal ?park-arms NIL) + (equal ?park-arms T)) + (desig:designator :action ((:type :perceiving) + (:object ?object-designator) + (:park-arms ?park-arms)) + ?resolved-action-desig)) (<- (desig:action-grounding ?action-designator (pick-up ?resolved-action-designator)) @@ -69,11 +89,20 @@ (member ?grasp ?grasps))) (lisp-fun man-int:get-action-gripping-effort ?object-type ?effort) (lisp-fun man-int:get-action-gripper-opening ?object-type ?gripper-opening) + ;; get the type of the picking location, because the trajectory + ;; might be different depending on the location type + (once (or (and (spec:property ?current-object-desig (:location ?obj-loc)) + (desig:current-designator ?obj-loc ?curr-obj-loc) + (man-int:location-reference-object ?curr-obj-loc ?obj-loc-obj) + (desig:current-designator ?obj-loc-obj ?curr-obj-loc-obj) + (spec:property ?curr-obj-loc-obj (:type ?location-type))) + (equal ?location-type NIL))) ;; calculate trajectory (equal ?objects (?current-object-desig)) (-> (equal ?arm :left) - (and (lisp-fun man-int:get-action-trajectory :picking-up ?arm ?grasp ?objects + (and (lisp-fun man-int:get-action-trajectory :picking-up + ?arm ?grasp ?location-type ?objects ?left-trajectory) (lisp-fun man-int:get-traj-poses-by-label ?left-trajectory :reaching ?left-reach-poses) @@ -85,7 +114,8 @@ (equal ?left-grasp-poses NIL) (equal ?left-lift-poses NIL))) (-> (equal ?arm :right) - (and (lisp-fun man-int:get-action-trajectory :picking-up ?arm ?grasp ?objects + (and (lisp-fun man-int:get-action-trajectory :picking-up + ?arm ?grasp ?location-type ?objects ?right-trajectory) (lisp-fun man-int:get-traj-poses-by-label ?right-trajectory :reaching ?right-reach-poses) @@ -96,8 +126,12 @@ (and (equal ?right-reach-poses NIL) (equal ?right-grasp-poses NIL) (equal ?right-lift-poses NIL))) - (or (lisp-pred identity ?left-trajectory) - (lisp-pred identity ?right-trajectory)) + (once (or (lisp-pred identity ?left-trajectory) + (lisp-pred identity ?right-trajectory))) + + (-> (lisp-pred identity ?left-grasp-poses) + (equal ?left-grasp-poses (?look-pose . ?_)) + (equal ?right-grasp-poses (?look-pose . ?_))) ;; put together resulting action designator (desig:designator :action ((:type :picking-up) @@ -106,6 +140,8 @@ (:gripper-opening ?gripper-opening) (:effort ?effort) (:grasp ?grasp) + (:location-type ?location-type) + (:look-pose ?look-pose) (:left-reach-poses ?left-reach-poses) (:right-reach-poses ?right-reach-poses) (:left-grasp-poses ?left-grasp-poses) @@ -121,14 +157,16 @@ ;; find in which hand the object is (-> (spec:property ?action-designator (:arm ?arm)) (-> (spec:property ?action-designator (:object ?object-designator)) - (or (cpoe:object-in-hand ?object-designator ?arm) - (format "WARNING: Wanted to place an object ~a with arm ~a, ~ - but it's not in the arm.~%" ?object-designator ?arm)) + (once (or (cpoe:object-in-hand ?object-designator ?arm) + (format "WARNING: Wanted to place an object ~a with arm ~a, ~ + but it's not in the arm.~%" + ?object-designator ?arm))) (cpoe:object-in-hand ?object-designator ?arm)) (-> (spec:property ?action-designator (:object ?object-designator)) - (or (cpoe:object-in-hand ?object-designator ?arm) - (format "WARNING: Wanted to place an object ~a ~ - but it's not in any of the hands.~%" ?object-designator)) + (once (or (cpoe:object-in-hand ?object-designator ?arm) + (format "WARNING: Wanted to place an object ~a ~ + but it's not in any of the hands.~%" + ?object-designator))) (cpoe:object-in-hand ?object-designator ?arm))) ;;; infer missing information @@ -139,7 +177,14 @@ ;; take object-pose from action-designator :target otherwise from object-designator pose (-> (spec:property ?action-designator (:target ?location-designator)) - (and (desig:current-designator ?location-designator ?current-location-designator) + (and (desig:current-designator ?location-designator ?current-loc-desig) + ;; if the location designator has ATTACHMENTS property, + ;; split it into a list of locations with ATTACHMENT property + (-> (desig:desig-prop ?current-loc-desig (:attachments ?_)) + (and (lisp-fun split-attachments-desig ?current-loc-desig + ?list-of-current-loc-desig-split) + (member ?current-location-designator ?list-of-current-loc-desig-split)) + (equal ?current-location-designator ?current-loc-desig)) (desig:designator-groundings ?current-location-designator ?poses) (member ?target-object-pose ?poses) (lisp-fun pose->transform-stamped-in-base ?target-object-pose ?object-name @@ -152,22 +197,35 @@ ?current-location-designator))) ;; placing happens on/in an object - (or (desig:desig-prop ?current-location-designator (:on ?other-object-designator)) - (desig:desig-prop ?current-location-designator (:in ?other-object-designator)) - (equal ?other-object-designator NIL)) - (-> (desig:desig-prop ?current-location-designator (:attachment ?placement-location-name)) - (true) - (equal ?placement-location-name NIL)) - - (-> (spec:property ?action-designator (:grasp ?grasp)) - (true) - (cpoe:object-in-hand ?object-designator ?arm ?grasp)) + (once (or (desig:desig-prop ?current-location-designator + (:on ?other-object-desig)) + (desig:desig-prop ?current-location-designator + (:in ?other-object-desig)) + (equal ?other-object-desig NIL))) + (desig:current-designator ?other-object-desig ?other-object-designator) + ;; and that other object can be a robot or not + (-> (man-int:object-is-a-robot ?other-object-designator) + (equal ?other-object-is-a-robot T) + (equal ?other-object-is-a-robot NIL)) + ;; and the placement can have a specific attachment or not + (once (or (desig:desig-prop ?current-location-designator + (:attachment ?placement-location-name)) + (equal ?placement-location-name NIL))) + ;; get the type of the placement location, because the trajectory + ;; might be different depending on the location type + (once (or (spec:property ?other-object-designator (:type ?location-type)) + (equal ?location-type NIL))) + ;; infer the grasp type + (once (or (spec:property ?action-designator (:grasp ?grasp)) + (cpoe:object-in-hand ?object-designator ?arm ?grasp))) ;; calculate trajectory - (equal ?objects (?current-object-designator)) + (equal ?objects (?current-object-designator + ?other-object-designator + ?placement-location-name)) (-> (equal ?arm :left) - (and (lisp-fun man-int:get-action-trajectory - :placing ?arm ?grasp ?objects + (and (lisp-fun man-int:get-action-trajectory :placing + ?arm ?grasp ?location-type ?objects :target-object-transform-in-base ?target-object-transform ?left-trajectory) (lisp-fun man-int:get-traj-poses-by-label ?left-trajectory :reaching @@ -180,8 +238,8 @@ (equal ?left-put-poses NIL) (equal ?left-retract-poses NIL))) (-> (equal ?arm :right) - (and (lisp-fun man-int:get-action-trajectory - :placing ?arm ?grasp ?objects + (and (lisp-fun man-int:get-action-trajectory :placing + ?arm ?grasp ?location-type ?objects :target-object-transform-in-base ?target-object-transform ?right-trajectory) (lisp-fun man-int:get-traj-poses-by-label ?right-trajectory :reaching @@ -193,17 +251,25 @@ (and (equal ?right-reach-poses NIL) (equal ?right-put-poses NIL) (equal ?right-retract-poses NIL))) - (or (lisp-pred identity ?left-trajectory) - (lisp-pred identity ?right-trajectory)) + (once (or (lisp-pred identity ?left-trajectory) + (lisp-pred identity ?right-trajectory))) + + (-> (lisp-pred identity ?left-put-poses) + (equal ?left-put-poses (?look-pose . ?_)) + (equal ?right-put-poses (?look-pose . ?_))) ;; put together resulting designator (desig:designator :action ((:type :placing) (:object ?current-object-designator) + (:target ?current-location-designator) (:other-object ?other-object-designator) + (:other-object-is-a-robot ?other-object-is-a-robot) (:arm ?arm) + (:grasp ?grasp) + (:location-type ?location-type) (:gripper-opening ?gripper-opening) - (:target ?current-location-designator) (:attachment-type ?placement-location-name) + (:look-pose ?look-pose) (:left-reach-poses ?left-reach-poses) (:right-reach-poses ?right-reach-poses) (:left-put-poses ?left-put-poses) diff --git a/cram_common/cram_mobile_pick_place_plans/src/pick-place-plans.lisp b/cram_common/cram_mobile_pick_place_plans/src/pick-place-plans.lisp index d6a7cce6c7..2333b48240 100644 --- a/cram_common/cram_mobile_pick_place_plans/src/pick-place-plans.lisp +++ b/cram_common/cram_mobile_pick_place_plans/src/pick-place-plans.lisp @@ -35,12 +35,17 @@ ;; As we would really like to have declare statements, our plans are simple defuns. ;; If in the future one would want to use def-cram-function for plan transformations, ;; one can always def-cram-function that calls a normal function. +;; Actually, the main thing we use in the task tree is the PERFORM calls, +;; which are already stored in the task tree. So there is no need for +;; def-cram-function as of now anymore. (defun pick-up (&key ((:object ?object-designator)) ((:arm ?arm)) ((:gripper-opening ?gripper-opening)) ((:effort ?grip-effort)) ((:grasp ?grasp)) + location-type + ((:look-pose ?look-pose)) ((:left-reach-poses ?left-reach-poses)) ((:right-reach-poses ?right-reach-poses)) ((:left-grasp-poses ?left-grasp-poses)) @@ -51,57 +56,76 @@ (declare (type desig:object-designator ?object-designator) (type keyword ?arm ?grasp) (type number ?gripper-opening ?grip-effort) - (type (or null list) ; yes, null is also list, but this is more readable + (type (or null list) ; yes, null is also a list, but this is more readable ?left-reach-poses ?right-reach-poses ?left-grasp-poses ?right-grasp-poses - ?left-lift-poses ?right-lift-poses)) + ?left-lift-poses ?right-lift-poses) + (ignore location-type)) "Open gripper, reach traj, grasp traj, close gripper, issue grasping event, lift." (cram-tf:visualize-marker (man-int:get-object-pose ?object-designator) :r-g-b-list '(1 1 0) :id 300) (cpl:par - (roslisp:ros-info (pick-place pick-up) "Opening gripper") - (exe:perform - (desig:an action - (type setting-gripper) - (gripper ?arm) - (position ?gripper-opening))) - (roslisp:ros-info (pick-place pick-up) "Reaching") + (roslisp:ros-info (pick-place pick-up) + "Looking, opening gripper and reaching") (cpl:with-failure-handling - ((common-fail:manipulation-low-level-failure (e) + ((common-fail:ptu-low-level-failure (e) (roslisp:ros-warn (pp-plans pick-up) - "Manipulation messed up: ~a~%Ignoring." + "Looking-at had a problem: ~a~%Ignoring." e) - ;; (return) - )) + (return))) (exe:perform (desig:an action - (type reaching) - (left-poses ?left-reach-poses) - (right-poses ?right-reach-poses))))) + (type looking) + (target (desig:a location + (pose ?look-pose)))))) + (let ((?goal `(cpoe:gripper-joint-at ,?arm ,?gripper-opening))) + (exe:perform + (desig:an action + (type setting-gripper) + (gripper ?arm) + (position ?gripper-opening) + (goal ?goal)))) + (cpl:with-failure-handling + ((common-fail:manipulation-low-level-failure (e) + (roslisp:ros-warn (pp-plans pick-up) + "Manipulation messed up: ~a~%Ignoring." + e) + (return))) + (let ((?goal `(cpoe:tool-frames-at ,?left-reach-poses ,?right-reach-poses))) + (exe:perform + (desig:an action + (type reaching) + (object ?object-designator) + (left-poses ?left-reach-poses) + (right-poses ?right-reach-poses) + (goal ?goal)))))) (roslisp:ros-info (pick-place pick-up) "Grasping") (cpl:with-failure-handling ((common-fail:manipulation-low-level-failure (e) (roslisp:ros-warn (pp-plans pick-up) "Manipulation messed up: ~a~%Ignoring." e) - (return) - )) + (return))) + (let ((?goal `(cpoe:tool-frames-at ,?left-grasp-poses ,?right-grasp-poses))) + (exe:perform + (desig:an action + (type grasping) + (object ?object-designator) + (left-poses ?left-grasp-poses) + (right-poses ?right-grasp-poses) + (goal ?goal))))) + (roslisp:ros-info (pick-place pick-up) "Gripping") + (let ((?goal `(cpoe:object-in-hand ,?object-designator ,?arm))) (exe:perform (desig:an action - (type grasping) + (type gripping) + (gripper ?arm) + (effort ?grip-effort) (object ?object-designator) - (left-poses ?left-grasp-poses) - (right-poses ?right-grasp-poses)))) - (roslisp:ros-info (pick-place pick-up) "Gripping") - (exe:perform - (desig:an action - (type gripping) - (gripper ?arm) - (effort ?grip-effort) - (object ?object-designator) - (grasp ?grasp))) + (grasp ?grasp) + (goal ?goal)))) (roslisp:ros-info (pick-place pick-up) "Lifting") (cpl:with-failure-handling ((common-fail:manipulation-low-level-failure (e) @@ -109,31 +133,35 @@ "Manipulation messed up: ~a~%Ignoring." e) (return))) - (exe:perform - (desig:an action - (type lifting) - (left-poses ?left-lift-poses) - (right-poses ?right-lift-poses)))) + (let ((?goal `(cpoe:tool-frames-at ,?left-lift-poses ,?right-lift-poses))) + (exe:perform + (desig:an action + (type lifting) + (left-poses ?left-lift-poses) + (right-poses ?right-lift-poses) + (goal ?goal))))) (roslisp:ros-info (pick-place place) "Parking") (exe:perform (desig:an action - (type positioning-arm) + (type parking-arms) ;; TODO: this will not work with dual-arm grasping ;; but as our ?arm is declared as a keyword, ;; for now this code is the right code - (desig:when (eql ?arm :left) - (left-configuration park)) - (desig:when (eql ?arm :right) - (right-configuration park))))) + (arms (?arm))))) (defun place (&key ((:object ?object-designator)) + ((:target ?target-location-designator)) ((:other-object ?other-object-designator)) + other-object-is-a-robot ((:arm ?arm)) + grasp + location-type ((:gripper-opening ?gripper-opening)) ((:attachment-type ?placing-location-name)) + ((:look-pose ?look-pose)) ((:left-reach-poses ?left-reach-poses)) ((:right-reach-poses ?right-reach-poses)) ((:left-put-poses ?left-put-poses)) @@ -146,12 +174,25 @@ (type keyword ?arm) (type (or null keyword) ?placing-location-name) (type number ?gripper-opening) - (type (or null list) ; yes, null is also list, but this is better reachability + (type (or null list) ; yes, null is also list, but this is better readable ?left-reach-poses ?right-reach-poses ?left-put-poses ?right-put-poses - ?left-retract-poses ?right-retract-poses)) + ?left-retract-poses ?right-retract-poses) + (ignore grasp location-type)) "Reach, put, assert assemblage if given, open gripper, retract grasp event, retract arm." + (roslisp:ros-info (pick-place place) "Looking") + (cpl:with-failure-handling + ((common-fail:ptu-low-level-failure (e) + (roslisp:ros-warn (pp-plans place) + "Looking-at had a problem: ~a~%Ignoring." + e) + (return))) + (exe:perform + (desig:an action + (type looking) + (target (desig:a location + (pose ?look-pose)))))) (roslisp:ros-info (pick-place place) "Reaching") (cpl:with-failure-handling ((common-fail:manipulation-low-level-failure (e) @@ -160,11 +201,14 @@ e) ;; (return) )) - (exe:perform - (desig:an action - (type reaching) - (left-poses ?left-reach-poses) - (right-poses ?right-reach-poses)))) + (let ((?goal `(cpoe:tool-frames-at ,?left-reach-poses ,?right-reach-poses))) + (exe:perform + (desig:an action + (type reaching) + (location ?target-location-designator) + (left-poses ?left-reach-poses) + (right-poses ?right-reach-poses) + (goal ?goal))))) (roslisp:ros-info (pick-place place) "Putting") (cpl:with-failure-handling ((common-fail:manipulation-low-level-failure (e) @@ -172,32 +216,50 @@ "Manipulation messed up: ~a~%Ignoring." e) (return))) - (exe:perform - (desig:an action - (type putting) - (object ?object-designator) - (desig:when ?other-object-designator - (supporting-object ?other-object-designator)) - (left-poses ?left-put-poses) - (right-poses ?right-put-poses)))) + (let ((?goal `(cpoe:tool-frames-at ,?left-put-poses ,?right-put-poses))) + (exe:perform + (desig:an action + (type putting) + (object ?object-designator) + (desig:when ?other-object-designator + (supporting-object ?other-object-designator)) + (left-poses ?left-put-poses) + (right-poses ?right-put-poses) + (goal ?goal))))) (when ?placing-location-name (roslisp:ros-info (boxy-plans connect) "Asserting assemblage connection in knowledge base") - (cram-occasions-events:on-event - (make-instance 'cpoe:object-attached-object - :object-name (desig:desig-prop-value ?object-designator :name) - :other-object-name (desig:desig-prop-value ?other-object-designator :name) - :attachment-type ?placing-location-name))) + (if other-object-is-a-robot + (cram-occasions-events:on-event + (make-instance 'cpoe:object-attached-robot + :link (roslisp-utilities:rosify-underscores-lisp-name + (desig:desig-prop-value ?other-object-designator :urdf-name)) + :not-loose t + :object-name (desig:desig-prop-value ?object-designator :name) + :other-object-name (desig:desig-prop-value ?other-object-designator :name) + :grasp ?placing-location-name)) + (cram-occasions-events:on-event + (make-instance 'cpoe:object-attached-object + :object-name (desig:desig-prop-value ?object-designator :name) + :other-object-name (desig:desig-prop-value ?other-object-designator :name) + :attachment-type ?placing-location-name)))) (roslisp:ros-info (pick-place place) "Opening gripper") - (exe:perform - (desig:an action - (type setting-gripper) - (gripper ?arm) - (position ?gripper-opening))) + (let ((?goal `(cpoe:gripper-joint-at ,?arm ,?gripper-opening))) + (exe:perform + (desig:an action + (type setting-gripper) + (gripper ?arm) + (position ?gripper-opening) + (goal ?goal)))) (roslisp:ros-info (pick-place place) "Retract grasp in knowledge base") (cram-occasions-events:on-event (make-instance 'cpoe:object-detached-robot :arm ?arm :object-name (desig:desig-prop-value ?object-designator :name))) + (roslisp:ros-info (pick-place place) "Updating object location in knowledge base") + (cram-occasions-events:on-event + (make-instance 'cpoe:object-location-changed + :object-designator ?object-designator + :location-designator ?target-location-designator)) (roslisp:ros-info (pick-place place) "Retracting") (cpl:with-failure-handling ((common-fail:manipulation-low-level-failure (e) @@ -205,54 +267,57 @@ "Manipulation messed up: ~a~%Ignoring." e) (return))) - (exe:perform - (desig:an action - (type retracting) - (left-poses ?left-retract-poses) - (right-poses ?right-retract-poses)))) + (let ((?goal `(cpoe:tool-frames-at ,?left-retract-poses ,?right-retract-poses))) + (exe:perform + (desig:an action + (type retracting) + (left-poses ?left-retract-poses) + (right-poses ?right-retract-poses) + (goal ?goal))))) (roslisp:ros-info (pick-place place) "Parking") (exe:perform (desig:an action - (type positioning-arm) - (desig:when (eql ?arm :left) - (left-configuration park)) - (desig:when (eql ?arm :right) - (right-configuration park))))) + (type parking-arms) + (arms (?arm))))) (defun perceive (&key ((:object ?object-designator)) + park-arms (object-chosing-function #'identity) &allow-other-keys) - (declare (type desig:object-designator ?object-designator)) + (declare (type desig:object-designator ?object-designator) + (type boolean park-arms) + (ignore object-chosing-function)) "Park arms and call DETECTING action." - (exe:perform - (desig:an action - (type positioning-arm) - (left-configuration park) - (right-configuration park))) + (when park-arms + (exe:perform + (desig:an action + (type parking-arms) + (not-neck T)))) (exe:perform (desig:an action (type detecting) (object ?object-designator)))) -;; (defun perform-phases-in-sequence (action-designator) -;; (declare (type desig:action-designator action-designator)) -;; (let ((phases (desig:desig-prop-value action-designator :phases))) -;; (mapc (lambda (phase) -;; (format t "Executing phase: ~%~a~%~%" phase) -;; (exe:perform phase)) -;; phases))) - -;; (cpl:def-cram-function pick-up (action-designator object arm grasp) -;; (perform-phases-in-sequence action-designator) -;; (cram-occasions-events:on-event -;; (make-instance 'cpoe:object-attached-robot :object object :arm arm :grasp grasp))) - +#+the-stuff-below-with-action-phases-is-a-bit-awkward +( + (defun perform-phases-in-sequence (action-designator) + (declare (type desig:action-designator action-designator)) + (let ((phases (desig:desig-prop-value action-designator :phases))) + (mapc (lambda (phase) + (format t "Executing phase: ~%~a~%~%" phase) + (exe:perform phase)) + phases))) -;; (cpl:def-cram-function place (action-designator object arm) -;; (perform-phases-in-sequence action-designator) -;; (cram-occasions-events:on-event -;; (make-instance 'cpoe:object-detached-robot :arm arm :object object))) + (cpl:def-cram-function pick-up (action-designator object arm grasp) + (perform-phases-in-sequence action-designator) + (cram-occasions-events:on-event + (make-instance 'cpoe:object-attached-robot :object object :arm arm :grasp grasp))) + (cpl:def-cram-function place (action-designator object arm) + (perform-phases-in-sequence action-designator) + (cram-occasions-events:on-event + (make-instance 'cpoe:object-detached-robot :arm arm :object object))) + ) diff --git a/cram_common/cram_object_knowledge/src/household.lisp b/cram_common/cram_object_knowledge/src/household.lisp deleted file mode 100644 index d01e503257..0000000000 --- a/cram_common/cram_object_knowledge/src/household.lisp +++ /dev/null @@ -1,327 +0,0 @@ -;;; -;;; Copyright (c) 2017, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Institute for Artificial Intelligence/ -;;; Universitaet Bremen nor the names of its contributors may be used to -;;; endorse or promote products derived from this software without -;;; specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :objects) - -(defparameter *lift-z-offset* 0.15 "in meters") -(defparameter *lift-offset* `(0.0 0.0 ,*lift-z-offset*)) - -;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(def-fact-group household-object-type-hierarchy (man-int:object-type-direct-subtype) - (<- (man-int:object-type-direct-subtype :household-item :cutlery)) - (<- (man-int:object-type-direct-subtype :household-item :plate)) - (<- (man-int:object-type-direct-subtype :household-item :tray)) - (<- (man-int:object-type-direct-subtype :household-item :bottle)) - (<- (man-int:object-type-direct-subtype :household-item :cup)) - (<- (man-int:object-type-direct-subtype :household-item :milk)) - (<- (man-int:object-type-direct-subtype :household-item :cereal)) - (<- (man-int:object-type-direct-subtype :household-item :bowl)) - - (<- (man-int:object-type-direct-subtype :cutlery :knife)) - (<- (man-int:object-type-direct-subtype :cutlery :fork)) - (<- (man-int:object-type-direct-subtype :cutlery :spoon)) - - (<- (man-int:object-type-direct-subtype :cereal :breakfast-cereal))) - -;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(defmethod man-int:get-action-gripping-effort :heuristics 20 ((object-type (eql :household-item))) - 50) -(defmethod man-int:get-action-gripping-effort :heuristics 20 ((object-type (eql :milk))) - 20) -(defmethod man-int:get-action-gripping-effort :heuristics 20 ((object-type (eql :cereal))) - 30) - -;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(defmethod man-int:get-action-gripper-opening :heuristics 20 ((object-type (eql :household-item))) - 0.10) -(defmethod man-int:get-action-gripper-opening :heuristics 20 ((object-type (eql :cutlery))) - 0.04) -(defmethod man-int:get-action-gripper-opening :heuristics 20 ((object-type (eql :plate))) - 0.02) -(defmethod man-int:get-action-gripper-opening :heuristics 20 ((object-type (eql :tray))) - 0.02) - -;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(def-fact-group pnp-object-knowledge (man-int:object-rotationally-symmetric - man-int:orientation-matters) - - (<- (object-rotationally-symmetric ?object-type) - (member ?object-type (;; :plate :bottle :drink :cup :bowl :milk - ))) - - (<- (orientation-matters ?object-type) - (member ?object-type (:knife :fork :spoon :cutlery :spatula)))) - -;;;;;;;;;;;;;;;;;;;;;;;;;;;; CUTLERY ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(defparameter *cutlery-grasp-z-offset* -0.015 ;; 0.015 - "in meters") ; because TCP is not at the edge -(defparameter *cutlery-pregrasp-z-offset* 0.20 "in meters") -(defparameter *cutlery-pregrasp-xy-offset* 0.10 "in meters") - -;; TOP grasp -(man-int:def-object-type-to-gripper-transforms '(:cutlery :fork :knife :spoon) - '(:left :right) :top - :grasp-translation `(0.0 0.0 ,*cutlery-grasp-z-offset*) - :grasp-rot-matrix man-int:*z-across-x-grasp-rotation* - :pregrasp-offsets `(0.0 0.0 ,*cutlery-pregrasp-z-offset*) - :2nd-pregrasp-offsets `(0.0 0.0 ,*cutlery-pregrasp-z-offset*) - :lift-offsets `(0.0 0.0 ,*cutlery-pregrasp-z-offset*) - :2nd-lift-offsets `(0.0 0.0 ,*cutlery-pregrasp-z-offset*)) - -;; BOTTOM grasp -;; Bottom grasp is commented out because the robot grasps the spoon through the -;; drawer, as in the last part of the grasping trajectory collisions are turned off -;; (man-int:def-object-type-to-gripper-transforms '(:cutlery :fork :knife :spoon) -;; '(:left :right) :bottom -;; :grasp-translation `(0.0 0.0 ,(- *cutlery-grasp-z-offset*)) -;; :grasp-rot-matrix man-int:*-z-across-x-grasp-rotation* -;; :pregrasp-offsets `(0.0 0.0 ,(- *cutlery-pregrasp-z-offset*)) -;; :2nd-pregrasp-offsets `(0.0 0.0 ,(- *cutlery-pregrasp-z-offset*)) -;; :lift-offsets `(0.0 0.0 ,(- *cutlery-pregrasp-z-offset*)) -;; :2nd-lift-offsets `(0.0 0.0 ,(- *cutlery-pregrasp-z-offset*))) - -;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; PLATE ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(defparameter *plate-diameter* 0.26 "in meters") -(defparameter *plate-grasp-y-offset* (- (/ *plate-diameter* 2) 0.015) "in meters") -(defparameter *plate-grasp-z-offset* 0.015 "in meters") -(defparameter *plate-grasp-roll-offset* (/ pi 6)) -(defparameter *plate-pregrasp-y-offset* 0.2 "in meters") -(defparameter *plate-2nd-pregrasp-z-offset* 0.03 "in meters") ; grippers can't go into table - -;; SIDE grasp -(man-int:def-object-type-to-gripper-transforms '(:plate :tray) :left :left-side - :grasp-translation `(0.0 ,*plate-grasp-y-offset* ,*plate-grasp-z-offset*) - :grasp-rot-matrix - `((0 1 0) - (,(sin *plate-grasp-roll-offset*) 0 ,(- (cos *plate-grasp-roll-offset*))) - (,(- (cos *plate-grasp-roll-offset*)) 0 ,(- (sin *plate-grasp-roll-offset*)))) - :pregrasp-offsets `(0.0 ,*plate-pregrasp-y-offset* ,*lift-z-offset*) - :2nd-pregrasp-offsets `(0.0 ,*plate-pregrasp-y-offset* ,*plate-2nd-pregrasp-z-offset*) - :lift-offsets *lift-offset* - :2nd-lift-offsets *lift-offset*) -(man-int:def-object-type-to-gripper-transforms :plate :right :right-side - :grasp-translation `(0.0 ,(- *plate-grasp-y-offset*) ,*plate-grasp-z-offset*) - :grasp-rot-matrix - `((0 -1 0) - (,(- (sin *plate-grasp-roll-offset*)) 0 ,(cos *plate-grasp-roll-offset*)) - (,(- (cos *plate-grasp-roll-offset*)) 0 ,(- (sin *plate-grasp-roll-offset*)))) - :pregrasp-offsets `(0.0 ,(- *plate-pregrasp-y-offset*) ,*lift-z-offset*) - :2nd-pregrasp-offsets `(0.0 ,(- *plate-pregrasp-y-offset*) ,*plate-2nd-pregrasp-z-offset*) - :lift-offsets *lift-offset* - :2nd-lift-offsets *lift-offset*) - -;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; bottle ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(defparameter *bottle-pregrasp-xy-offset* 0.15 "in meters") -(defparameter *bottle-grasp-xy-offset* 0.02 "in meters") -(defparameter *bottle-grasp-z-offset* 0.005 "in meters") - -;; SIDE grasp -(man-int:def-object-type-to-gripper-transforms '(:drink :bottle) '(:left :right) :left-side - :grasp-translation `(0.0d0 ,(- *bottle-grasp-xy-offset*) ,*bottle-grasp-z-offset*) - :grasp-rot-matrix man-int:*y-across-z-grasp-rotation* - :pregrasp-offsets `(0.0 ,*bottle-pregrasp-xy-offset* ,*lift-z-offset*) - :2nd-pregrasp-offsets `(0.0 ,*bottle-pregrasp-xy-offset* 0.0) - :lift-offsets *lift-offset* - :2nd-lift-offsets *lift-offset*) -(man-int:def-object-type-to-gripper-transforms '(:drink :bottle) '(:left :right) :right-side - :grasp-translation `(0.0d0 ,*bottle-grasp-xy-offset* ,*bottle-grasp-z-offset*) - :grasp-rot-matrix man-int:*-y-across-z-grasp-rotation* - :pregrasp-offsets `(0.0 ,(- *bottle-pregrasp-xy-offset*) ,*lift-z-offset*) - :2nd-pregrasp-offsets `(0.0 ,(- *bottle-pregrasp-xy-offset*) 0.0) - :lift-offsets *lift-offset* - :2nd-lift-offsets *lift-offset*) - -;; BACK grasp -(man-int:def-object-type-to-gripper-transforms '(:drink :bottle) '(:left :right) :back - :grasp-translation `(,*bottle-grasp-xy-offset* 0.0d0 ,*bottle-grasp-z-offset*) - :grasp-rot-matrix man-int:*-x-across-z-grasp-rotation* - :pregrasp-offsets `(,(- *bottle-pregrasp-xy-offset*) 0.0 ,*lift-z-offset*) - :2nd-pregrasp-offsets `(,(- *bottle-pregrasp-xy-offset*) 0.0 0.0) - :lift-offsets *lift-offset* - :2nd-lift-offsets *lift-offset*) - -;; FRONT grasp -(man-int:def-object-type-to-gripper-transforms '(:drink :bottle) '(:left :right) :front - :grasp-translation `(,*bottle-grasp-xy-offset* 0.0d0 ,*bottle-grasp-z-offset*) - :grasp-rot-matrix man-int:*x-across-z-grasp-rotation* - :pregrasp-offsets `(,(- *bottle-pregrasp-xy-offset*) 0.0 ,*lift-z-offset*) - :2nd-pregrasp-offsets `(,(- *bottle-pregrasp-xy-offset*) 0.0 0.0) - :lift-offsets *lift-offset* - :2nd-lift-offsets *lift-offset*) - -;;;;;;;;;;;;;;;;;;;;;;;;;;;;; cup ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(defparameter *cup-pregrasp-xy-offset* 0.15 "in meters") -(defparameter *cup-grasp-xy-offset* 0.02 "in meters") -(defparameter *cup-grasp-z-offset* 0.01 "in meters") -(defparameter *cup-top-grasp-x-offset* 0.03 "in meters") -(defparameter *cup-top-grasp-z-offset* 0.02 "in meters") - -;; TOP grasp -(man-int:def-object-type-to-gripper-transforms :cup '(:left :right) :top - :grasp-translation `(,(- *cup-top-grasp-x-offset*) 0.0d0 ,*cup-top-grasp-z-offset*) - :grasp-rot-matrix man-int:*z-across-y-grasp-rotation* - :pregrasp-offsets *lift-offset* - :2nd-pregrasp-offsets *lift-offset* - :lift-offsets *lift-offset* - :2nd-lift-offsets *lift-offset*) - -;; SIDE grasp -(man-int:def-object-type-to-gripper-transforms :cup '(:left :right) :left-side - :grasp-translation `(0.0d0 ,(- *cup-grasp-xy-offset*) ,*cup-grasp-z-offset*) - :grasp-rot-matrix man-int:*y-across-z-grasp-rotation* - :pregrasp-offsets `(0.0 ,*cup-pregrasp-xy-offset* ,*lift-z-offset*) - :2nd-pregrasp-offsets `(0.0 ,*cup-pregrasp-xy-offset* 0.0) - :lift-offsets *lift-offset* - :2nd-lift-offsets *lift-offset*) -(man-int:def-object-type-to-gripper-transforms :cup '(:left :right) :right-side - :grasp-translation `(0.0d0 ,*cup-grasp-xy-offset* ,*cup-grasp-z-offset*) - :grasp-rot-matrix man-int:*-y-across-z-grasp-rotation* - :pregrasp-offsets `(0.0 ,(- *cup-pregrasp-xy-offset*) ,*lift-z-offset*) - :2nd-pregrasp-offsets `(0.0 ,(- *cup-pregrasp-xy-offset*) 0.0) - :lift-offsets *lift-offset* - :2nd-lift-offsets *lift-offset*) - -;; BACK grasp -(man-int:def-object-type-to-gripper-transforms :cup '(:left :right) :back - :grasp-translation `(,*cup-grasp-xy-offset* 0.0d0 ,*cup-grasp-z-offset*) - :grasp-rot-matrix man-int:*-x-across-z-grasp-rotation* - :pregrasp-offsets `(,(- *cup-pregrasp-xy-offset*) 0.0 ,*lift-z-offset*) - :2nd-pregrasp-offsets `(,(- *cup-pregrasp-xy-offset*) 0.0 0.0) - :lift-offsets *lift-offset* - :2nd-lift-offsets *lift-offset*) - -;; FRONT grasp -(man-int:def-object-type-to-gripper-transforms :cup '(:left :right) :front - :grasp-translation `(,(- *cup-grasp-xy-offset*) 0.0d0 ,*cup-grasp-z-offset*) - :grasp-rot-matrix man-int:*x-across-z-grasp-rotation* - :pregrasp-offsets `(,*cup-pregrasp-xy-offset* 0.0 ,*lift-z-offset*) - :2nd-pregrasp-offsets `(,*cup-pregrasp-xy-offset* 0.0 0.0) - :lift-offsets *lift-offset* - :2nd-lift-offsets *lift-offset*) - -;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; milk ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(defparameter *milk-grasp-xy-offset* 0.01 "in meters") -(defparameter *milk-grasp-z-offset* 0.0 "in meters") -(defparameter *milk-pregrasp-xy-offset* 0.15 "in meters") -(defparameter *milk-lift-z-offset* 0.05 "in meters") - -;; BACK grasp -(man-int:def-object-type-to-gripper-transforms :milk '(:left :right) :back - :grasp-translation `(,*milk-grasp-xy-offset* 0.0d0 ,*milk-grasp-z-offset*) - :grasp-rot-matrix man-int:*-x-across-z-grasp-rotation* - :pregrasp-offsets `(,(- *milk-pregrasp-xy-offset*) 0.0 ,*lift-z-offset*) - :2nd-pregrasp-offsets `(,(- *milk-pregrasp-xy-offset*) 0.0 0.0) - :lift-offsets *lift-offset* - :2nd-lift-offsets *lift-offset*) - -;; FRONT grasp -(man-int:def-object-type-to-gripper-transforms :milk '(:left :right) :front - :grasp-translation `(,(- *milk-grasp-xy-offset*) 0.0d0 ,*milk-grasp-z-offset*) - :grasp-rot-matrix man-int:*x-across-z-grasp-rotation* - :pregrasp-offsets `(,*milk-pregrasp-xy-offset* 0.0 ,*lift-z-offset*) - :2nd-pregrasp-offsets `(,*milk-pregrasp-xy-offset* 0.0 0.0) - :lift-offsets *lift-offset* - :2nd-lift-offsets *lift-offset*) - -;; SIDE grasp -(man-int:def-object-type-to-gripper-transforms :milk '(:left :right) :left-side - :grasp-translation `(0.0d0 ,(- *milk-grasp-xy-offset*) ,*milk-grasp-z-offset*) - :grasp-rot-matrix man-int:*y-across-z-grasp-rotation* - :pregrasp-offsets `(0.0 ,*milk-pregrasp-xy-offset* ,*lift-z-offset*) - :2nd-pregrasp-offsets `(0.0 ,*milk-pregrasp-xy-offset* 0.0) - :lift-offsets `(0.0 ,(- *milk-grasp-xy-offset*) ,*milk-lift-z-offset*) - :2nd-lift-offsets `(0.0 ,(- *milk-grasp-xy-offset*) ,*milk-lift-z-offset*)) -(man-int:def-object-type-to-gripper-transforms :milk '(:left :right) :right-side - :grasp-translation `(0.0d0 ,*milk-grasp-xy-offset* ,*milk-grasp-z-offset*) - :grasp-rot-matrix man-int:*-y-across-z-grasp-rotation* - :pregrasp-offsets `(0.0 ,(- *milk-pregrasp-xy-offset*) ,*lift-z-offset*) - :2nd-pregrasp-offsets `(0.0 ,(- *milk-pregrasp-xy-offset*) 0.0) - :lift-offsets `(0.0 ,*milk-grasp-xy-offset* ,*milk-lift-z-offset*) - :2nd-lift-offsets `(0.0 ,*milk-grasp-xy-offset* ,*milk-lift-z-offset*)) - -;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; cereal ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(defparameter *cereal-grasp-z-offset* 0.04 "in meters") -(defparameter *cereal-grasp-xy-offset* 0.03 "in meters") -(defparameter *cereal-pregrasp-z-offset* 0.05 "in meters") -(defparameter *cereal-pregrasp-xy-offset* 0.15 "in meters") -(defparameter *cereal-postgrasp-xy-offset* 0.40 "in meters") -(defparameter *cereal-lift-z-offset* 0.1 "in meters") - -;; FRONT grasp -(man-int:def-object-type-to-gripper-transforms '(:cereal :breakfast-cereal) '(:left :right) :front - :grasp-translation `(,*cereal-grasp-xy-offset* 0.0d0 ,*cereal-grasp-z-offset*) - :grasp-rot-matrix man-int:*x-across-z-grasp-rotation* - :pregrasp-offsets `(,*cereal-pregrasp-xy-offset* 0.0 ,*cereal-pregrasp-z-offset*) - :2nd-pregrasp-offsets `(,*cereal-pregrasp-xy-offset* 0.0 0.0) - :lift-offsets `(,*cereal-grasp-xy-offset* 0.0 ,*cereal-lift-z-offset*) - :2nd-lift-offsets `(,*cereal-postgrasp-xy-offset* 0.0 ,*cereal-lift-z-offset*)) - -;; TOP grasp -(man-int:def-object-type-to-gripper-transforms '(:cereal :breakfast-cereal) '(:left :right) :top - :grasp-translation `(0.0d0 0.0d0 ,*cereal-grasp-z-offset*) - :grasp-rot-matrix man-int:*z-across-x-grasp-rotation* - :pregrasp-offsets *lift-offset* - :2nd-pregrasp-offsets *lift-offset* - :lift-offsets *lift-offset* - :2nd-lift-offsets *lift-offset*) - -;; BACK grasp -(man-int:def-object-type-to-gripper-transforms '(:cereal :breakfast-cereal) '(:left :right) :back - :grasp-translation `(,(- *cereal-grasp-xy-offset*) 0.0d0 ,*cereal-grasp-z-offset*) - :grasp-rot-matrix man-int:*-x-across-z-grasp-rotation* - :pregrasp-offsets `(,(- *cereal-pregrasp-xy-offset*) 0.0 ,*cereal-pregrasp-z-offset*) - :2nd-pregrasp-offsets `(,(- *cereal-pregrasp-xy-offset*) 0.0 0.0) - :lift-offsets `(,(- *cereal-grasp-xy-offset*) 0.0 ,*cereal-lift-z-offset*) - :2nd-lift-offsets `(,(- *cereal-postgrasp-xy-offset*) 0.0 ,*cereal-lift-z-offset*)) - - -;;;;;;;;;;;;;;;;;;;;;;;;;;;;; bowl ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(defparameter *bowl-grasp-x-offset* 0.07 "in meters") -(defparameter *bowl-grasp-z-offset* 0.0 "in meters") -(defparameter *bowl-pregrasp-z-offset* 0.30 "in meters") - -;; TOP grasp -(man-int:def-object-type-to-gripper-transforms :bowl '(:left :right) :top - :grasp-translation `(,(- *bowl-grasp-x-offset*) 0.0d0 ,*bowl-grasp-z-offset*) - :grasp-rot-matrix man-int:*z-across-y-grasp-rotation* - :pregrasp-offsets `(0.0 0.0 ,*bowl-pregrasp-z-offset*) - :2nd-pregrasp-offsets `(0.0 0.0 ,*bowl-pregrasp-z-offset*) - :lift-offsets `(0.0 0.0 ,*bowl-pregrasp-z-offset*) - :2nd-lift-offsets `(0.0 0.0 ,*bowl-pregrasp-z-offset*)) diff --git a/cram_common/cram_occupancy_grid_costmap/src/prolog.lisp b/cram_common/cram_occupancy_grid_costmap/src/prolog.lisp index 8ba0d65d9f..9abf63baa7 100644 --- a/cram_common/cram_occupancy_grid_costmap/src/prolog.lisp +++ b/cram_common/cram_occupancy_grid_costmap/src/prolog.lisp @@ -49,13 +49,23 @@ (true))) (<- (desig-costmap ?desig ?cm) - (cram-robot-interfaces:visibility-designator ?desig) - (costmap ?cm) - (costmap-padding ?padding) - (drivable-location-costmap ?cm ?padding)) - - (<- (desig-costmap ?desig ?cm) - (cram-robot-interfaces:reachability-designator ?desig) - (costmap ?cm) - (costmap-manipulation-padding ?padding) + (or (rob-int:visibility-designator ?desig) + (rob-int:reachability-designator ?desig)) + ;; make sure that the location is not on the robot itself + ;; if it is, don't generate a costmap + (-> (desig:desig-prop ?desig (:object ?some-object)) + (and (desig:current-designator ?some-object ?object) + (-> (desig:desig-prop ?object (:location ?some-loc)) + (not (man-int:location-always-reachable ?some-loc)) + (true))) + (true)) + (-> (desig:desig-prop ?desig (:location ?some-location)) + (and (desig:current-designator ?some-location ?location) + (not (man-int:location-always-reachable ?location))) + (true)) + (costmap:costmap ?cm) + (rob-int:robot ?robot-name) + (-> (rob-int:visibility-designator ?desig) + (costmap:costmap-padding ?robot-name ?padding) + (costmap:costmap-manipulation-padding ?robot-name ?padding)) (drivable-location-costmap ?cm ?padding))) diff --git a/cram_common/cram_plan_occasions_events/src/default-plan-events.lisp b/cram_common/cram_plan_occasions_events/src/default-plan-events.lisp index 6607933a3b..ece9ab9705 100644 --- a/cram_common/cram_plan_occasions_events/src/default-plan-events.lisp +++ b/cram_common/cram_plan_occasions_events/src/default-plan-events.lisp @@ -28,8 +28,10 @@ (in-package :cram-plan-occasions-events) -;;; Note that we do not provide an event for object change. The reason +;;; Note that we do not provide an event for object pose change. The reason ;;; is that object changes are essentially object perception events. +;;; We do, however, provide an object location change, as location change +;;; can be asserted using the knowledge from successful plan execution. (defclass object-perceived-event (event) ((object-designator :initarg :object-designator :reader event-object-designator @@ -47,14 +49,21 @@ contains a symbol indicating the sensor that produces the perception.")) -;; NOTE(winkler): This contradicts the above notice; will be resolved -;; later after everything got cleaned up, as this is a conceptual -;; issue, not a code-one. -;; (defclass object-updated-event (object-perceived-event) ()) - -;; (defclass object-removed-event (event) -;; ((object-name :initarg :object-name :reader event-object-name -;; :initform :object-name))) +(defclass object-location-changed (event) + ((object-designator + :initarg :object-designator :reader event-object-designator + :initform (error + 'simple-error + :format-control "OBJECT-LOCATION-CHANGED requires an object.")) + (location-designator + :initarg :location-designator :reader event-location-designator + :initform (error + 'simple-error + :format-control "OBJECT-LOCATION-CHANGED requires a location."))) + (:documentation "Event that is generated whenever an object general location + is changed. The slot `object-designator' contains a reference to the + designator describing the perceived object and the slot `location-designator' + contains the new location designator, where the object is expected to have moved.")) (defclass robot-state-changed (event) () @@ -75,24 +84,37 @@ ((arm :initarg :arm :reader event-arm - :initform (error - 'simple-error - :format-control "OBJECT-ATTACHED-ROBOT event requires an arm.")) + :initform nil) + (link + :initarg :link + :reader event-link + :initform nil) (grasp :initarg :grasp :reader event-grasp - :initform nil - ;; (error 'simple-error - ;; :format-control "OBJECT-ATTACHED-ROBOT event requires GRASP.") - ))) + :initform nil) + (not-loose + :initarg :not-loose + :reader event-not-loose + :initform nil) + (other-object-name + :initarg :other-object-name + :reader event-other-object-name + :initform nil) + (object-designator + :initarg :object-designator + :reader event-object-designator + :initform nil))) (defclass object-detached-robot (object-connection-event) ((arm :initarg :arm :reader event-arm - :initform (error - 'simple-error - :format-control "OBJECT-DETACHED-ROBOT event requires an arm.")))) + :initform nil) + (link + :initarg :link + :reader event-link + :initform nil))) (defclass object-attached-object (object-connection-event) ((other-object-name @@ -110,18 +132,6 @@ (defclass object-detached-object (object-connection-event) ()) -;; (defclass object-articulation-event (event) -;; ((object-designator -;; :initarg :object-designator :reader event-object-designator -;; :initform (error -;; 'simple-error -;; :format-control "OBJECT-ARTICULATION-EVENT requires an object.")) -;; (opening-distance -;; :initarg :opening-distance :reader opening-distance -;; :initform (error -;; 'simple-error -;; :format-control "OBJECT-ARTICULATION-EVENT requires an opening distance.")))) - (defclass environment-manipulation-event (event) ((joint-name :documentation "The name of the joint that is being manipulated." @@ -153,29 +163,3 @@ (defclass container-opening-event (environment-manipulation-event) ()) (defclass container-closing-event (environment-manipulation-event) ()) - -;; (defclass object-gripped (cram-occasions-events:event) -;; ((arm :initarg :arm -;; :reader event-arm -;; :initform (error 'simple-error -;; :format-control "OBJECT-GRIPPED event requires ARM.")) -;; (object :initarg :object -;; :reader event-object -;; :initform (error 'simple-error -;; :format-control "OBJECT-GRIPPED event requires OBJECT.")) -;; (grasp :initarg :grasp -;; :reader event-grasp -;; :initform (error 'simple-error -;; :format-control "OBJECT-GRIPPED event requires GRASP."))) -;; (:documentation "Event that is generated whenever the robot successfully -;; closed a gripper around an object.")) - -;; (defclass object-released (cram-occasions-events:event) -;; ((arm :initarg :arm -;; :reader event-arm -;; :initform (error 'simple-error -;; :format-control "OBJECT-GRIPPED event requires OBJECT.")) -;; (object :initarg :object ; maybe some epic robots can release only one of two objects they hold -;; :reader event-object -;; :initform (error 'simple-error -;; :format-control "OBJECT-GRIPPED event requires OBJECT.")))) diff --git a/cram_common/cram_plan_occasions_events/src/occasion-declarations.lisp b/cram_common/cram_plan_occasions_events/src/occasion-declarations.lisp index f070bf9553..55a9b33d13 100644 --- a/cram_common/cram_plan_occasions_events/src/occasion-declarations.lisp +++ b/cram_common/cram_plan_occasions_events/src/occasion-declarations.lisp @@ -29,29 +29,67 @@ (in-package :cram-plan-occasions-events) -(def-fact-group occasions (object-in-hand object-placed-at object-picked object-put - loc looking-at arms-parked - container-state) +(def-fact-group occasions (object-in-hand + object-at-location robot-at-location + torso-at gripper-joint-at gripper-opened gripper-closed + arms-positioned-at tool-frames-at + looking-at + container-state + location-reset) + + (<- (object-in-hand ?object ?hand ?grasp ?link) + (fail)) + (<- (object-in-hand ?object ?hand ?grasp) + (fail)) + (<- (object-in-hand ?object ?hand) + (fail)) (<- (object-in-hand ?object) (fail)) - (<- (object-placed-at ?object ?location) + (<- (object-at-location ?object-designator ?location-designator) + (fail)) + (<- (robot-at-location ?location-designator) (fail)) - (<- (object-picked ?object) + (<- (torso-at ?joint-state) + (fail)) + (<- (torso-at ?joint-state ?delta) (fail)) - (<- (object-put ?object) + (<- (gripper-joint-at ?arm ?joint-state) + (fail)) + (<- (gripper-joint-at ?arm ?joint-state ?delta) (fail)) - (<- (loc ?robot-or-object ?location) + (<- (gripper-opened ?gripper) + (fail)) + (<- (gripper-opened ?gripper ?delta) (fail)) - (<- (looking-at ?location) + (<- (gripper-closed ?gripper) + (fail)) + (<- (gripper-closed ?gripper ?delta) (fail)) - (<- (arms-parked) + (<- (arms-positioned-at ?left-configuration ?right-configuration) + (fail)) + (<- (arms-positioned-at ?left-configuration ?right-configuration ?delta) + (fail)) + + (<- (tool-frames-at ?left-poses ?right-poses) + (fail)) + (<- (tool-frames-at ?left-poses ?right-poses ?delta-position ?delta-rotation) + (fail)) + + (<- (looking-at ?location-or-object-or-frame-or-direction-or-pose) + (fail)) + (<- (looking-at ?location-or-object-or-frame-or-direction-or-pose ?delta) + (fail)) + + (<- (container-state ?container-object-designator ?joint-state-or-keyword) + (fail)) + (<- (container-state ?container-object-designator ?joint-state-or-keyword ?delta) (fail)) - (<- (container-state ?container-object-designator ?joint-state) + (<- (location-reset ?location-designator) (fail))) diff --git a/cram_common/cram_plan_occasions_events/src/package.lisp b/cram_common/cram_plan_occasions_events/src/package.lisp index 73457dabbc..0a5b097e22 100644 --- a/cram_common/cram_plan_occasions_events/src/package.lisp +++ b/cram_common/cram_plan_occasions_events/src/package.lisp @@ -34,39 +34,40 @@ (:use #:common-lisp #:cram-occasions-events #:cram-prolog) - (:export #:object-perceived-event - #:event-object-designator - #:perception-source - #:robot-state-changed - #:object-connection-event - ;; #:object-articulation-event - #:object-attached-robot #:object-detached-robot - #:object-attached-object #:object-detached-object - ;; #:object-removed-event - ;; #:object-updated-event - #:event-object-name - #:event-other-object-name - #:event-attachment-type - #:event-arm - #:event-grasp - ;; #:object-designator #:opening-distance + (:export + ;; default-plan-events + #:object-perceived-event + #:object-location-changed + #:robot-state-changed + #:object-connection-event + #:object-attached-robot #:object-detached-robot + #:object-attached-object #:object-detached-object + #:environment-manipulation-event + #:container-opening-event #:container-closing-event - #:environment-manipulation-event - #:environment-event-joint-name - #:environment-event-arm - #:environment-event-object - #:environment-event-distance - ;; #:container-handle-grasping-event - #:container-opening-event - #:container-closing-event + #:perception-source + #:event-location-designator + #:event-object-designator + #:event-object-name + #:event-other-object-name + #:event-attachment-type + #:event-arm + #:event-link + #:event-grasp + #:event-not-loose + #:environment-event-joint-name + #:environment-event-arm + #:environment-event-object + #:environment-event-distance - ;; occasion-declarations - ;; Symbols used in plans and thus the execution trace. - #:object-in-hand - #:object-placed-at - #:object-picked - #:object-put - #:loc - #:looking-at - #:arms-parked - #:container-state)) + ;; occasion-declarations + ;; Symbols used in plans and thus the execution trace. + #:object-in-hand + #:object-at-location #:robot-at-location + #:torso-at #:gripper-joint-at + #:gripper-opened #:gripper-closed + #:arms-positioned-at #:tool-frames-at + #:looking-at + #:container-state + #:location-reset + #:location-accessible)) diff --git a/cram_common/cram_robot_interfaces/cram-robot-interfaces.asd b/cram_common/cram_robot_interfaces/cram-robot-interfaces.asd index 2b83180393..cfba74b66d 100644 --- a/cram_common/cram_robot_interfaces/cram-robot-interfaces.asd +++ b/cram_common/cram_robot_interfaces/cram-robot-interfaces.asd @@ -40,8 +40,8 @@ (:file "grasps" :depends-on ("package")) (:file "trajectories" :depends-on ("package")) (:file "arms" :depends-on ("package")) - (:file "ptu" :depends-on ("package")) + (:file "neck" :depends-on ("package")) (:file "robot" :depends-on ("package")) (:file "designator-utils" :depends-on ("package" "trajectories" "arms")) - (:file "utilities" :depends-on ("package")) - (:file "urdf" :depends-on ("package")))))) + (:file "urdf" :depends-on ("package" "robot")) + (:file "environment" :depends-on ("package")))))) diff --git a/cram_common/cram_robot_interfaces/src/arms.lisp b/cram_common/cram_robot_interfaces/src/arms.lisp index 2fad1528f9..086b120c2f 100644 --- a/cram_common/cram_robot_interfaces/src/arms.lisp +++ b/cram_common/cram_robot_interfaces/src/arms.lisp @@ -30,16 +30,13 @@ (in-package :cram-robot-interfaces) (def-fact-group arms (;; rules describing the robot arms - arm required-arms available-arms - arm-joints arm-links arm-base-joints arm-base-links arm-tool-joints - hand-links end-effector-link robot-tool-frame - gripper-joint gripper-link gripper-meter-to-joint-multiplier - ;; specific configurations - ;; robot-arms-parking-joint-states robot-arms-carrying-joint-states - ;; end-effector-parking-pose - ;; robot-pre-grasp-joint-states - planning-group - standard-to-particular-gripper-transform + arm + required-arms available-arms + arm-joints arm-links + hand-links hand-link hand-finger-link gripper-joint + end-effector-link robot-tool-frame + gripper-meter-to-joint-multiplier + standard<-particular-gripper-transform tcp-in-ee-pose) ;;;;;;;;;;;;;;;;;;;;;;;;; rules describing the robot arms @@ -65,69 +62,44 @@ (<- (arm-links ?robot ?arm ?links) (fail)) - ;; Unifies ?arm with the list of base joints for that arm (e.g., for the PR2 it's the torso). - (<- (arm-base-joints ?robot ?arm ?joints) - (fail)) - - ;; Unifies ?arm with a list of base links for that arm (e.g., for the PR2 it's the torso). - (<- (arm-base-links ?robot ?arm ?links) - (fail)) - - ;; Unifies ?arm with the list of tool joints for that arm - ;; (e.g., for the PR2 it's the palm and tool joints). - (<- (arm-tool-joints ?robot ?arm ?joints) - (fail)) - - ;; Unifies ?arm with a list of links for the hand of that arm. + ;; Unifies ?arm with a list of links for the hand of that arm. (<- (hand-links ?robot ?arm ?links) (fail)) - ;; Defines end-effector links for arms. - (<- (end-effector-link ?robot ?arm ?link-name) + ;; Unifies a ?link, which belongs to the hand of the robot on ?arm arm + (<- (hand-link ?robot ?arm ?link) (fail)) - ;; Defines tool frames for arms. - (<- (robot-tool-frame ?robot ?arm ?frame) + ;; Similar to hand-link but gives only the finger links (not palm etc.) + (<- (hand-finger-link ?robot ?arm ?link) (fail)) ;; Defines joints of robot's grippers (<- (gripper-joint ?robot ?arm ?joint) (fail)) - ;; Defines links of the grippers of the robot - (<- (gripper-link ?robot ?arm ?link) - (fail)) - + ;; Some grippers are commanded in radian, some in CM. + ;; To keep the interfaces consistent, we assume CM and each robot defines + ;; how to convert CM opening distance for the gripper into its own unit. (<- (gripper-meter-to-joint-multiplier ?robot ?multiplier) (fail)) - ;;;;;;;;;;;;;;;;;;;;;;;;; specific configurations - - ;; (<- (robot-arms-parking-joint-states ?robot ?joint-states) - ;; (fail)) - ;; (<- (robot-arms-parking-joint-states ?robot ?joint-states ?arm) - ;; (fail)) - - ;; (<- (robot-arms-carrying-joint-states ?robot ?joint-states) - ;; (fail)) - ;; (<- (robot-arms-carrying-joint-states ?robot ?joint-states ?arm) - ;; (fail)) - - ;; (<- (end-effector-parking-pose ?robot ?pose ?arm) - ;; (fail)) - - ;; (<- (robot-pre-grasp-joint-states ?robot ?joint-states) - ;; (fail)) + ;; Standard gripper has the Z pointing towards the object + ;; and X is aligned with the hand opening. + ;; If the particular robot's gripper is different, + ;; this predicate defines the cl-transforms:transform of + ;; standard-gripper_T_particular-gripper + (<- (standard<-particular-gripper-transform ?robot ?transform) + (fail)) - (<- (planning-group ?robot ?arms ?group-name) + ;; Defines end-effector links for arms. + (<- (end-effector-link ?robot ?arm ?link-name) (fail)) - (<- (standard-to-particular-gripper-transform ?robot ?transform) + ;; Defines tool frames for arms. + (<- (robot-tool-frame ?robot ?arm ?frame) (fail)) + ;; Defines cl-transforms:pose of ee_P_tcp (should be the same for all arms) (<- (tcp-in-ee-pose ?robot ?transform) (fail))) - - - - diff --git a/cram_common/cram_robot_interfaces/src/environment.lisp b/cram_common/cram_robot_interfaces/src/environment.lisp new file mode 100644 index 0000000000..a265e1f3a5 --- /dev/null +++ b/cram_common/cram_robot_interfaces/src/environment.lisp @@ -0,0 +1,56 @@ +;;; +;;; Copyright (c) 2020, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :cram-robot-interfaces) + +(defparameter *environment-description-parameter* "kitchen_description" + "ROS parameter that contains the environment description URDF.") + +(defvar *environment-urdf* nil + "A cl-urdf object corresponding to parsed environment URDF.") + +(defvar *environment-name* nil + "Variable that stores the name of the current environment, +we assume that all the environment furniture is put together into one URDF.") + +(defun set-environment-name (new-name) + (setf *environment-name* new-name)) + +(defun get-environment-name () + (or *environment-name* + (error "[rob-int] Variable *ENVIRONMENT-NAME* is NIL.~%~ + Was it initialized from the URDF on the ROS parameter server?"))) + +(def-fact-group environment (environment-name) + (<- (environment-name ?environment-name) + (symbol-value *environment-name* ?environment-name) + (once (or (lisp-pred identity ?environment-name) + (lisp-pred error "[rob-int] Variable *ENVIRONMENT-NAME* is NIL.~%~ + Was it initialized from the URDF on the ~ + ROS parameter server?"))))) diff --git a/cram_common/cram_robot_interfaces/src/ptu.lisp b/cram_common/cram_robot_interfaces/src/neck.lisp similarity index 59% rename from cram_common/cram_robot_interfaces/src/ptu.lisp rename to cram_common/cram_robot_interfaces/src/neck.lisp index 45a954cd58..ac9f8a1785 100644 --- a/cram_common/cram_robot_interfaces/src/ptu.lisp +++ b/cram_common/cram_robot_interfaces/src/neck.lisp @@ -1,19 +1,19 @@ ;;; Copyright (c) 2015, Gayane Kazhoyan ;;; All rights reserved. -;;; +;;; ;;; Redistribution and use in source and binary forms, with or without ;;; modification, are permitted provided that the following conditions are met: -;;; +;;; ;;; * Redistributions of source code must retain the above copyright ;;; notice, this list of conditions and the following disclaimer. ;;; * Redistributions in binary form must reproduce the above copyright ;;; notice, this list of conditions and the following disclaimer in the ;;; documentation and/or other materials provided with the distribution. ;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software ;;; without specific prior written permission. -;;; +;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" ;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE ;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE @@ -28,9 +28,17 @@ (in-package :cram-robot-interfaces) -(def-fact-group ptu (camera-frame camera-minimal-height camera-maximal-height - robot-neck-links robot-neck-joints robot-neck-base-link - camera-in-neck-ee-pose) +(def-fact-group neck (camera-frame + camera-minimal-height camera-maximal-height + camera-horizontal-angle camera-vertical-angle + neck robot-neck-links robot-neck-joints robot-neck-base-link + camera-in-neck-ee-pose + neck-camera-z-offset + neck-camera-pose-unit-vector-multiplier + neck-camera-resampling-step + neck-camera-x-axis-limit neck-camera-y-axis-limit + neck-camera-z-axis-limit) + ;; Unifies ?frame with the name of the camera frame present on the ?robot (<- (camera-frame ?robot ?frame) (fail)) @@ -47,12 +55,44 @@ (<- (camera-maximal-height ?robot ?max-height) (fail)) + ;; view angle of the camera (assuming a fixed focal length) in horizontal axis + (<- (camera-horizontal-angle ?robot ?angle) + (fail)) + ;; view angle of the camera (assuming a fixed focal length) in vertical axis + (<- (camera-vertical-angle ?robot ?angle) + (fail)) + + ;; Unifies ?neck with the name of a body part that is present on the ?robot. + (<- (neck ?robot ?neck) + (fail)) + + ;; For necks with standard pan-tilt units (2 joints pan and tilt) (<- (robot-neck-links ?robot ?pan-link ?tilt-link) (fail)) (<- (robot-neck-joints ?robot ?pan-joint ?tilt-joint) (fail)) + + ;; For necks with more than 2 joints + (<- (robot-neck-links ?robot . ?neck-links) + (fail)) + (<- (robot-neck-joints ?robot . ?neck-joints) + (fail)) + ;; This link will be used for IK stuff (if IK will be used) (<- (robot-neck-base-link ?robot ?neck-base-link) (fail)) - + ;; neck_P_camera cl-transforms:pose (<- (camera-in-neck-ee-pose ?robot ?pose) + (fail)) + ;; for doing neck IK if the neck has more than 2 joints + (<- (neck-camera-z-offset ?robot ?number) + (fail)) + (<- (neck-camera-pose-unit-vector-multiplier ?robot ?number) + (fail)) + (<- (neck-camera-resampling-step ?robot ?number) + (fail)) + (<- (neck-camera-x-axis-limit ?robot ?number) + (fail)) + (<- (neck-camera-y-axis-limit ?robot ?number) + (fail)) + (<- (neck-camera-z-axis-limit ?robot ?number) (fail))) diff --git a/cram_common/cram_robot_interfaces/src/package.lisp b/cram_common/cram_robot_interfaces/src/package.lisp index 230e2e4310..dd67fd962b 100644 --- a/cram_common/cram_robot_interfaces/src/package.lisp +++ b/cram_common/cram_robot_interfaces/src/package.lisp @@ -1,19 +1,19 @@ ;;; Copyright (c) 2012, Lorenz Moesenlechner ;;; All rights reserved. -;;; +;;; ;;; Redistribution and use in source and binary forms, with or without ;;; modification, are permitted provided that the following conditions are met: -;;; +;;; ;;; * Redistributions of source code must retain the above copyright ;;; notice, this list of conditions and the following disclaimer. ;;; * Redistributions in binary form must reproduce the above copyright ;;; notice, this list of conditions and the following disclaimer in the ;;; documentation and/or other materials provided with the distribution. ;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software ;;; without specific prior written permission. -;;; +;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" ;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE ;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE @@ -32,35 +32,41 @@ (:use #:common-lisp #:cram-prolog #:cram-designators) (:nicknames #:rob-int) (:export + ;; robot + #:*robot-description-parameter* #:*robot-urdf* + #:set-robot-name #:get-robot-name + #:robot #:robot-base-frame #:robot-odom-frame #:robot-torso-link-joint + #:robot-joint-states + #:robot-pose + #:arms #:arms-that-are-not-neck ;; arms #:arm #:required-arms #:available-arms - #:arm-joints #:arm-links #:arm-base-joints #:arm-base-links #:arm-tool-joints - #:hand-links #:end-effector-link #:robot-tool-frame - #:gripper-link #:gripper-joint #:gripper-meter-to-joint-multiplier - #:planning-group - #:standard-to-particular-gripper-transform + #:arm-joints #:arm-links + #:hand-links #:hand-link #:hand-finger-link #:gripper-joint + #:end-effector-link #:robot-tool-frame + #:gripper-meter-to-joint-multiplier + #:standard<-particular-gripper-transform #:tcp-in-ee-pose ;; designator utils #:compute-iks #:reachability-designator #:designator-reach-pose #:visibility-designator #:reachability-designator-p #:visibility-designator-p #:trajectory-desig? #:constraints-desig? - ;; ptu + ;; neck #:camera-frame #:camera-minimal-height #:camera-maximal-height - #:robot-neck-links #:robot-neck-joints #:robot-neck-base-link + #:camera-horizontal-angle #:camera-vertical-angle + #:neck #:robot-neck-links #:robot-neck-joints #:robot-neck-base-link #:camera-in-neck-ee-pose - ;; robot - #:robot #:robot-base-frame #:robot-odom-frame #:robot-torso-link-joint - #:current-robot-symbol #:current-robot-package #:current-robot-name - #:robot-joint-states - #:robot-pose + #:neck-camera-z-offset #:neck-camera-pose-unit-vector-multiplier + #:neck-camera-resampling-step + #:neck-camera-x-axis-limit #:neck-camera-y-axis-limit #:neck-camera-z-axis-limit ;; trajectories #:trajectory-point - ;; utilities - #:symbol-to-prolog-rule ;; urdf - #:*robot-urdf* #:get-joint-type #:get-joint-lower-limit #:get-joint-upper-limit #:get-joint-axis #:get-joint-origin #:get-joint-parent #:get-joint-child #:joint-lower-limit #:joint-upper-limit #:joint-type #:joint-axis #:joint-origin - #:joint-parent-link #:joint-child-link)) + #:joint-parent-link #:joint-child-link + ;; environment + #:*environment-description-parameter* #:*environment-urdf* + #:set-environment-name #:get-environment-name #:environment-name)) diff --git a/cram_common/cram_robot_interfaces/src/robot.lisp b/cram_common/cram_robot_interfaces/src/robot.lisp index 80b9ec7c61..8b8057f9b6 100644 --- a/cram_common/cram_robot_interfaces/src/robot.lisp +++ b/cram_common/cram_robot_interfaces/src/robot.lisp @@ -1,19 +1,19 @@ ;;; Copyright (c) 2015, Gayane Kazhoyan ;;; All rights reserved. -;;; +;;; ;;; Redistribution and use in source and binary forms, with or without ;;; modification, are permitted provided that the following conditions are met: -;;; +;;; ;;; * Redistributions of source code must retain the above copyright ;;; notice, this list of conditions and the following disclaimer. ;;; * Redistributions in binary form must reproduce the above copyright ;;; notice, this list of conditions and the following disclaimer in the ;;; documentation and/or other materials provided with the distribution. ;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software ;;; without specific prior written permission. -;;; +;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" ;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE ;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE @@ -28,11 +28,34 @@ (in-package :cram-robot-interfaces) -(def-fact-group robot (robot robot-base-frame robot-odom-frame - robot-torso-link-joint - robot-joint-states robot-pose) +(defparameter *robot-description-parameter* "robot_description" + "ROS parameter that contains the robot description.") + +(defvar *robot-urdf* nil + "A cl-urdf object corresponding to parsed robot urdf.") + +(defvar *robot-name* nil + "Variable that stores the name of the current robot, +so the robot whose brain this is.") + +(defun set-robot-name (new-name) + (setf *robot-name* new-name)) + +(defun get-robot-name () + (or *robot-name* (error "[rob-int] Variable *ROBOT-NAME* is NIL.~%~ + Have you initialized it from a URDF on the ~ + ROS parameter server?"))) + +(def-fact-group robot (robot + robot-base-frame robot-odom-frame + robot-torso-link-joint + robot-joint-states robot-pose) (<- (robot ?robot-name) - (fail)) + (symbol-value *robot-name* ?robot-name) + (once (or (lisp-pred identity ?robot-name) + (lisp-pred error "[rob-int] Variable *ROBOT-NAME* is NIL.~%~ + Have you initialized it from a URDF on the ~ + ROS parameter server?")))) (<- (robot-base-frame ?robot-name ?base-frame) (fail)) @@ -52,15 +75,13 @@ (fail))) -(defun current-robot-symbol () - (let ((robot-symbol - (cut:var-value '?r (car (prolog:prolog '(robot ?r)))))) - (if (cut:is-var robot-symbol) - NIL - robot-symbol))) - -(defun current-robot-package () - (symbol-package (current-robot-symbol))) +(def-fact-group utils (arms arms-that-are-not-neck) + (<- (arms ?robot-name ?arms) + (once (or (setof ?arm (rob-int:arm ?robot-name ?arm) ?arms) + (equal ?arms NIL)))) -(defun current-robot-name () - (symbol-name (current-robot-symbol))) + (<- (arms-that-are-not-neck ?robot-name ?arms) + (once (or (setof ?arm (and (rob-int:arm ?robot-name ?arm) + (not (rob-int:neck ?robot-name ?arm))) + ?arms) + (equal ?arms NIL))))) diff --git a/cram_common/cram_robot_interfaces/src/urdf.lisp b/cram_common/cram_robot_interfaces/src/urdf.lisp index dc4efeefe2..ac34fd5065 100644 --- a/cram_common/cram_robot_interfaces/src/urdf.lisp +++ b/cram_common/cram_robot_interfaces/src/urdf.lisp @@ -34,9 +34,6 @@ ;; Will need an SRDF parser to extract that information. Until then, a lot ;; of the predicates will be manually filled with data. -(defvar *robot-urdf* nil - "A cl-urdf object corresponding to parsed robot urdf.") - (defun get-joint-description (joint-name) (unless *robot-urdf* (error "[rob-int] ROBOT-URDF variable is not set!")) @@ -49,13 +46,19 @@ (defun get-joint-lower-limit (joint-name) (let* ((joint-description (get-joint-description joint-name))) - (when (and joint-description (not (equal (get-joint-type joint-name) :continuous))) - (cl-urdf:lower (cl-urdf:limits joint-description))))) + (when (and joint-description + (not (equal (get-joint-type joint-name) :continuous))) + (if (slot-boundp joint-description 'cl-urdf:limits) + (cl-urdf:lower (cl-urdf:limits joint-description)) + 0.0)))) (defun get-joint-upper-limit (joint-name) (let* ((joint-description (get-joint-description joint-name))) - (when (and joint-description (not (equal (get-joint-type joint-name) :continuous))) - (cl-urdf:upper (cl-urdf:limits joint-description))))) + (when (and joint-description + (not (equal (get-joint-type joint-name) :continuous))) + (if (slot-boundp joint-description 'cl-urdf:limits) + (cl-urdf:upper (cl-urdf:limits joint-description)) + 0.0)))) (defun get-joint-axis (joint-name) (let* ((joint-description (get-joint-description joint-name))) diff --git a/cram_common/cram_robot_pose_gaussian_costmap/src/current-pose-generator-and-pose-validator.lisp b/cram_common/cram_robot_pose_gaussian_costmap/src/current-pose-generator-and-pose-validator.lisp index d98aacd312..2ffd45f3c6 100644 --- a/cram_common/cram_robot_pose_gaussian_costmap/src/current-pose-generator-and-pose-validator.lisp +++ b/cram_common/cram_robot_pose_gaussian_costmap/src/current-pose-generator-and-pose-validator.lisp @@ -30,6 +30,7 @@ (in-package :gaussian-costmap) (defun robot-current-pose-tf-generator (desig) + (return-from robot-current-pose-tf-generator nil) (when (or (cram-robot-interfaces:reachability-designator-p desig) (cram-robot-interfaces:visibility-designator-p desig)) (when cram-tf:*transformer* @@ -37,6 +38,16 @@ (list (cram-tf:robot-current-pose)) (cl-transforms-stamped:transform-stamped-error () nil))))) +;; (defun robot-current-pose-bullet-generator (desig) +;; (when (or (cram-robot-interfaces:reachability-designator-p desig) +;; (cram-robot-interfaces:visibility-designator-p desig)) +;; (handler-case +;; (cut:var-value '?pose +;; (car (prolog `(and (btr:bullet-world ?w) +;; (cram-robot-interfaces:robot ?robot-name) +;; (btr:object-pose ?w ?robot-name ?pose))))) +;; (error () nil)))) + (desig:register-location-generator 3 robot-current-pose-tf-generator "We should move the robot only if we really need to move. Try the @@ -67,8 +78,10 @@ (defun reachable-location-validator (designator pose) (if (cram-robot-interfaces:reachability-designator-p designator) - (cut:with-vars-bound (?to-reach-pose ?min-distance ?max-distance - ?orientation-samples ?orientation-sample-step) + (cut:with-vars-bound (?to-reach-pose + ?min-distance ?max-distance + ?orientation-samples ?orientation-sample-step + ?orientation-offset) (cut:lazy-car (prolog:prolog `(and @@ -78,16 +91,24 @@ ;; (lisp-fun costmap:2d-pose-covariance ?poses 0.5 (?to-reach-point ?_)) (once (or (and (desig:desig-prop ,designator (:object ?some-object)) (desig:current-designator ?some-object ?object) - (lisp-fun man-int:get-object-pose-in-map ?object ?to-reach-pose) - (lisp-pred identity ?to-reach-pose)) - (and (desig:desig-prop ,designator (:location ?some-location)) + (lisp-fun man-int:get-object-pose-in-map ?object + ?to-reach-pose) + (lisp-pred identity ?to-reach-pose) + (-> (desig:desig-prop ?object (:location ?loc)) + (not (man-int:location-always-reachable ?loc)) + (true))) + (and (desig:desig-prop ,designator + (:location ?some-location)) (desig:current-designator ?some-location ?location) + (not (man-int:location-always-reachable ?location)) (desig:designator-groundings ?location ?to-reach-poses) (member ?to-reach-pose ?to-reach-poses)))) - (costmap:costmap-reach-minimal-distance ?min-distance) - (costmap:costmap-in-reach-distance ?max-distance) - (costmap:orientation-samples ?orientation-samples) - (costmap:orientation-sample-step ?orientation-sample-step)))) + (rob-int:robot ?robot-name) + (costmap:costmap-reach-minimal-distance ?robot-name ?min-distance) + (costmap:costmap-in-reach-distance ?robot-name ?max-distance) + (costmap:orientation-samples ?robot-name ?orientation-samples) + (costmap:orientation-sample-step ?robot-name ?orientation-sample-step) + (costmap:reachability-orientation-offset ?robot-name ?orientation-offset)))) (if (or (cut:is-var ?to-reach-pose) (cut:is-var ?min-distance) (cut:is-var ?max-distance)) @@ -115,7 +136,9 @@ (generated-angle (calculate-z-angle pose))) (if (and (< dist ?max-distance) (> dist ?min-distance) - (<= (abs (- perfect-angle generated-angle)) allowed-range)) + (<= (abs (- (abs (- perfect-angle generated-angle)) + (cl-transforms:normalize-angle ?orientation-offset))) + allowed-range)) :accept :reject)))) :unknown)) @@ -127,24 +150,30 @@ (defun visible-location-validator (designator pose) (if (cram-robot-interfaces:visibility-designator-p designator) - (cut:with-vars-bound (?to-see-pose ?max-distance - ?orientation-samples ?orientation-sample-step) + (cut:with-vars-bound (?to-see-pose + ?max-distance + ?orientation-samples ?orientation-sample-step) (cut:lazy-car (prolog:prolog - `(and (once (or (and (desig:desig-prop ,designator (:object ?some-object)) - (desig:current-designator ?some-object ?object) - ;; (btr-belief:object-designator-name ?object ?object-name) - ;; (btr:bullet-world ?world) - ;; (btr:object-pose ?world ?object-name ?to-see-pose) - (lisp-fun man-int:get-object-pose-in-map ?object ?to-see-pose) - (lisp-pred identity ?to-see-pose)) - (and (desig:desig-prop ,designator (:location ?some-location)) - (desig:current-designator ?some-location ?location) - (desig:designator-groundings ?location ?to-see-poses) - (member ?to-see-pose ?to-see-poses)))) - (costmap:visibility-costmap-size ?max-distance) - (costmap:orientation-samples ?orientation-samples) - (costmap:orientation-sample-step ?orientation-sample-step)))) + `(and (once + (or (and (desig:desig-prop ,designator (:object ?some-object)) + (desig:current-designator ?some-object ?object) + (lisp-fun man-int:get-object-pose-in-map ?object + ?to-see-pose) + (lisp-pred identity ?to-see-pose) + (-> (desig:desig-prop ?object (:location ?loc)) + (not (man-int:location-always-reachable ?loc)) + (true))) + (and (desig:desig-prop ,designator (:location ?some-location)) + (desig:current-designator ?some-location ?location) + (not (man-int:location-always-reachable ?location)) + (desig:designator-groundings ?location ?to-see-poses) + (member ?to-see-pose ?to-see-poses)))) + (rob-int:robot ?robot-name) + (costmap:visibility-costmap-size ?robot-name ?max-distance) + (costmap:orientation-samples ?robot-name ?orientation-samples) + (costmap:orientation-sample-step ?robot-name + ?orientation-sample-step)))) (if (or (cut:is-var ?to-see-pose) (cut:is-var ?max-distance)) :unknown (let (;; DIST ist the distance from the suggested robot pose to to-see-pose @@ -177,13 +206,3 @@ (desig:register-location-validation-function 5 visible-location-validator "Verifies that visible location is indeed in close distance to pose") - -;; (defun robot-current-pose-bullet-generator (desig) -;; (when (or (cram-robot-interfaces:reachability-designator-p desig) -;; (cram-robot-interfaces:visibility-designator-p desig)) -;; (handler-case -;; (cut:var-value '?pose -;; (car (prolog `(and (btr:bullet-world ?w) -;; (cram-robot-interfaces:robot ?robot-name) -;; (btr:object-pose ?w ?robot-name ?pose))))) -;; (error () nil)))) diff --git a/cram_common/cram_robot_pose_gaussian_costmap/src/prolog.lisp b/cram_common/cram_robot_pose_gaussian_costmap/src/prolog.lisp index b3dd70aefc..fe9c9e8cde 100644 --- a/cram_common/cram_robot_pose_gaussian_costmap/src/prolog.lisp +++ b/cram_common/cram_robot_pose_gaussian_costmap/src/prolog.lisp @@ -38,26 +38,27 @@ (defmethod costmap-generator-name->score ((name pose-distribution-range-include-generator)) - 7) + 3) (defmethod costmap-generator-name->score ((name pose-distribution-range-exclude-generator)) - 6) + 4) (def-fact-group robot-pose-gaussian-costmap (desig-costmap) (<- (desig-costmap ?desig ?cm) - (cram-robot-interfaces:visibility-designator ?desig) + (rob-int:visibility-designator ?desig) ;; (bagof ?pose (desig-location-prop ?desig ?pose) ?poses) (once (or (and (desig:desig-prop ?desig (:object ?some-object)) (desig:current-designator ?some-object ?object) - ;; (btr-belief:object-designator-name ?object ?object-name) - ;; (btr:bullet-world ?world) - ;; (btr:object-pose ?world ?object-name ?to-see-pose) (lisp-fun man-int:get-object-pose-in-map ?object ?to-see-pose) - (lisp-pred identity ?to-see-pose)) + (lisp-pred identity ?to-see-pose) + (-> (desig:desig-prop ?object (:location ?loc)) + (not (man-int:location-always-reachable ?loc)) + (true))) (and (desig:desig-prop ?desig (:location ?some-location)) (desig:current-designator ?some-location ?location) + (not (man-int:location-always-reachable ?location)) (desig:designator-groundings ?location ?location-poses) ;; have to take one pose from all possibilities ;; as later we have a FORCE-LL on ?TO-SEE-POSES @@ -65,35 +66,43 @@ (member ?to-see-pose ?location-poses)))) (lisp-fun list ?to-see-pose ?to-see-poses) (lisp-fun 2d-pose-covariance ?to-see-poses 0.5 (?mean ?covariance)) - (costmap ?cm) - (costmap-add-function + (rob-int:robot ?robot-name) + (costmap:costmap ?cm) + (costmap:costmap-add-function pose-distribution - (make-gauss-cost-function ?mean ?covariance) + (costmap:make-gauss-cost-function ?mean ?covariance) ?cm) - (costmap:visibility-costmap-size ?distance) + (costmap:visibility-costmap-size ?robot-name ?distance) (instance-of pose-distribution-range-include-generator ?include-generator-id) - (costmap-add-function + (costmap:costmap-add-function ?include-generator-id - (make-range-cost-function ?mean ?distance) + (costmap:make-range-cost-function ?mean ?distance) ?cm) - (costmap:orientation-samples ?samples) - (costmap:orientation-sample-step ?sample-step) - (costmap-add-orientation-generator - (make-angle-to-point-generator ?mean :samples ?samples :sample-step ?sample-step) + (costmap:orientation-samples ?robot-name ?samples) + (costmap:orientation-sample-step ?robot-name ?sample-step) + (costmap:costmap-add-orientation-generator + (costmap:make-angle-to-point-generator + ?mean :samples ?samples :sample-step ?sample-step) ?cm) - (costmap-add-height-generator - (make-constant-height-function 0.0) + (costmap:costmap-add-height-generator + (costmap:make-constant-height-function 0.0) ?cm)) (<- (desig-costmap ?desig ?cm) - (cram-robot-interfaces:reachability-designator ?desig) + (rob-int:reachability-designator ?desig) ;; (bagof ?pose (cram-robot-interfaces:designator-reach-pose ?desig ?pose ?_) ?poses) (once (or (and (desig:desig-prop ?desig (:object ?some-object)) (desig:current-designator ?some-object ?object) (lisp-fun man-int:get-object-pose-in-map ?object ?to-reach-pose) - (lisp-pred identity ?to-reach-pose)) + (lisp-pred identity ?to-reach-pose) + (-> (desig:desig-prop ?object (:location ?loc)) + (not (man-int:location-always-reachable ?loc)) + (true))) (and (desig:desig-prop ?desig (:location ?some-location)) (desig:current-designator ?some-location ?location) + ;; if the location is on the robot itself, + ;; don't use the costmap + (not (man-int:location-always-reachable ?location)) (desig:designator-groundings ?location ?location-poses) ;; have to take one pose from all possibilities ;; as later we have a FORCE-LL on ?TO-REACH-POSES @@ -101,37 +110,40 @@ (member ?to-reach-pose ?location-poses)))) (lisp-fun list ?to-reach-pose ?to-reach-poses) (lisp-fun cut:force-ll ?to-reach-poses ?poses-list) - (lisp-fun 2d-pose-covariance ?to-reach-poses 0.5 (?mean ?covariance)) - (costmap-in-reach-distance ?distance) - (costmap-reach-minimal-distance ?minimal-distance) - (costmap ?cm) - (forall - (member ?pose ?to-reach-poses) - (and - (instance-of pose-distribution-range-include-generator - ?include-generator-id) - (costmap-add-function - ?include-generator-id - (make-range-cost-function ?pose ?distance) ?cm) - (instance-of pose-distribution-range-exclude-generator - ?exclude-generator-id) - (costmap-add-function - ?exclude-generator-id - (make-range-cost-function ?pose ?minimal-distance :invert t) - ?cm))) - (costmap:orientation-samples ?samples) - (costmap:orientation-sample-step ?sample-step) - (costmap-add-orientation-generator - (make-angle-to-point-generator ?mean :samples ?samples :sample-step ?sample-step) + (lisp-fun costmap:2d-pose-covariance ?to-reach-poses 0.5 (?mean ?covariance)) + (costmap:costmap-in-reach-distance ?robot-name ?distance) + (costmap:costmap-reach-minimal-distance ?robot-name ?minimal-distance) + (costmap:costmap ?cm) + (forall (member ?pose ?to-reach-poses) + (and (instance-of pose-distribution-range-include-generator + ?include-generator-id) + (costmap:costmap-add-function + ?include-generator-id + (costmap:make-range-cost-function ?pose ?distance) ?cm) + (instance-of pose-distribution-range-exclude-generator + ?exclude-generator-id) + (costmap:costmap-add-function + ?exclude-generator-id + (costmap:make-range-cost-function + ?pose ?minimal-distance :invert t) + ?cm))) + (rob-int:robot ?robot-name) + (costmap:orientation-samples ?robot-name ?samples) + (costmap:orientation-sample-step ?robot-name ?sample-step) + (once (or (costmap:reachability-orientation-offset ?robot-name ?offset) + (equal ?offset 0.0))) + (costmap:costmap-add-orientation-generator + (costmap:make-angle-to-point-generator + ?mean :samples ?samples :sample-step ?sample-step :sample-offset ?offset) ?cm) - (costmap-add-height-generator + (costmap:costmap-add-height-generator (make-constant-height-function 0.0) ?cm)) ;; poses reachable-from ?pose for the robot ;; ?pose should usually be robot's current pose I suppose - (<- (desig-costmap ?desig ?cm) - (costmap ?cm) + (<- (costmap:desig-costmap ?desig ?cm) + (costmap:costmap ?cm) (desig-prop ?desig (:reachable-from ?from-what)) (or (and (lisp-type ?from-what symbol) ;; (cram-robot-interfaces:robot ?from-what) @@ -139,10 +151,13 @@ (and (lisp-type ?from-what cl-transforms:pose) (equal ?pose ?from-what))) (lisp-fun cl-transforms:origin ?pose ?point) - (costmap-in-reach-distance ?distance) - (costmap-add-function reachable-from-space - (make-range-cost-function ?point ?distance) - ?cm) - (costmap-add-function reachable-from-weighted - (make-location-cost-function ?pose ?distance) - ?cm))) + (rob-int:robot ?robot-name) + (costmap:costmap-in-reach-distance ?robot-name ?distance) + (costmap:costmap-add-function + reachable-from-space + (costmap:make-range-cost-function ?point ?distance) + ?cm) + (costmap:costmap-add-function + reachable-from-weighted + (costmap:make-location-cost-function ?pose ?distance) + ?cm))) diff --git a/cram_common/cram_simple_actionlib_client/package.xml b/cram_common/cram_simple_actionlib_client/package.xml index 6535945633..df4a93fc77 100644 --- a/cram_common/cram_simple_actionlib_client/package.xml +++ b/cram_common/cram_simple_actionlib_client/package.xml @@ -11,7 +11,7 @@ catkin roslisp - actionlib + actionlib_lisp roslisp_utilities cram_language diff --git a/cram_common/cram_simple_actionlib_client/src/simple-actionlib-client.lisp b/cram_common/cram_simple_actionlib_client/src/simple-actionlib-client.lisp index fb4b7b25db..8dd3e75dbf 100644 --- a/cram_common/cram_simple_actionlib_client/src/simple-actionlib-client.lisp +++ b/cram_common/cram_simple_actionlib_client/src/simple-actionlib-client.lisp @@ -109,9 +109,9 @@ do their magic invisibly in the background. (setf action-timeout (gethash name *action-timeouts*))) (cpl:with-failure-handling ((simple-error (e) - (format t "Actionlib error occured!~%~a~%Reinitializing...~%~%" e) - (init-simple-action-client name) - (cpl:retry))) + (format t "Actionlib error occured!~%~a~%Reinitializing...~%~%" e) + (init-simple-action-client name) + (cpl:retry))) (let ((actionlib:*action-server-timeout* 10.0) (client (get-simple-action-client name))) (if client diff --git a/cram_common/cram_tf/src/facts.lisp b/cram_common/cram_tf/src/facts.lisp index 82c3dcea31..bcdca7970a 100644 --- a/cram_common/cram_tf/src/facts.lisp +++ b/cram_common/cram_tf/src/facts.lisp @@ -102,18 +102,3 @@ (member ?pose ?poses)) (or (pose ?pose ?location) (equal ?location ?pose))))) - - -;; todo(@gaya): ugliest piece of code ever... -;; spent 2 years cleaning up cram, now spend another 2 messing it up again... -(def-fact-group robot-parts-location (desig-location-prop) - (<- (desig-location-prop ?object-designator ?pose-stamped) - (obj-desig? ?object-designator) - (desig-prop ?object-designator (:part-of ?robot)) - (cram-robot-interfaces:robot ?robot) - (desig-prop ?object-designator (:link ?link)) - (-> (desig-prop ?object-designator (:which-link ?params)) - (lisp-fun symbol-to-prolog-rule ?link ?robot-name ?params ?link-name) - (lisp-fun symbol-to-prolog-rule ?link ?robot-name ?link-name)) - (lisp-fun frame-to-pose-in-fixed-frame ?link-name ?pose-stamped))) - diff --git a/cram_common/cram_tf/src/package.lisp b/cram_common/cram_tf/src/package.lisp index fc8951e93c..60f4d72551 100644 --- a/cram_common/cram_tf/src/package.lisp +++ b/cram_common/cram_tf/src/package.lisp @@ -42,29 +42,31 @@ #:start-publishing-transforms #:stop-publishing-transforms ;; utilities #:poses-equal-p - #:frame-to-pose-in-fixed-frame + #:frame-to-pose-in-fixed-frame #:frame-to-transform-in-fixed-frame + #:3d-vector->list #:list->3d-vector #:pose->flat-list #:pose->flat-list-w-first #:pose->list #:flat-list->pose #:flat-list->transform #:flat-list-w-first->pose #:list->pose #:list->transform - #:ensure-pose-in-frame #:ensure-point-in-frame + #:ensure-pose-in-frame #:ensure-point-in-frame #:ensure-transform-in-frame #:translate-pose #:rotate-pose #:rotate-pose-in-own-frame #:rotate-transform-in-own-frame - #:tf-frame-converged #:pose->transform-stamped #:transform->pose-stamped #:transform-stamped-inv #:multiply-transform-stampeds #:strip-transform-stamped #:copy-transform-stamped #:translate-transform-stamped - #:pose-stamped->transform-stamped + #:pose-stamped->transform-stamped #:pose-stamped->point-stamped #:apply-transform - #:values-converged + #:values-converged #:tf-frame-converged #:pose-stampeds-converged + #:normalize-joint-angles + #:map-axis-aligned-axis #:map-axis-aligned-orientation #:angle-around-map-z ;; prolog facts #:pose #:pose-stamped #:position #:orientation #:poses-equal #:location-pose ;; robot current pose - #:robot-current-pose + #:robot-current-pose #:robot-current-transform ;; setup #:*transformer* #:*tf-default-timeout* diff --git a/cram_common/cram_tf/src/robot-current-pose.lisp b/cram_common/cram_tf/src/robot-current-pose.lisp index d160bab9dd..9e963cb592 100644 --- a/cram_common/cram_tf/src/robot-current-pose.lisp +++ b/cram_common/cram_tf/src/robot-current-pose.lisp @@ -55,3 +55,8 @@ :z 0.0))) (error 'transform-stamped-error :description "*transformer* is NIL. Have you called STARTUP-ROS?"))) + +(defun robot-current-transform (&key use-current-time-p) + (cram-tf:pose-stamped->transform-stamped + (robot-current-pose :use-current-time-p use-current-time-p) + cram-tf:*robot-base-frame*)) diff --git a/cram_common/cram_tf/src/setup.lisp b/cram_common/cram_tf/src/setup.lisp index be5eeb466d..b02b93a543 100644 --- a/cram_common/cram_tf/src/setup.lisp +++ b/cram_common/cram_tf/src/setup.lisp @@ -65,13 +65,13 @@ or in general at compile-time.") (defvar *robot-right-tool-frame* nil "Tool frame of the right arm. Initialized from CRAM robot desciption.") - (defun init-tf () (macrolet ((initialize-var (dynamic-var prolog-var) (let ((var-name (symbol-name dynamic-var))) `(if (is-var ,prolog-var) (roslisp:ros-info (cram-tf init-tf) - "~a is unknown. Did you load a robot description package?" + "~a is unknown. Did you load a ~ + robot description package?" ,var-name) (progn (setf ,dynamic-var ,prolog-var) @@ -79,18 +79,44 @@ or in general at compile-time.") "Set ~a to ~s." ,var-name ,prolog-var)))))) + ;; set *FIXED-FRAME* (setf *fixed-frame* "map") (roslisp:ros-info (cram-tf init-tf) "Set *fixed-frame* to ~s." *fixed-frame*) + ;; set the environment name based on the name in the urdf + (let ((environment-name + (roslisp-utilities:lispify-ros-underscore-name + (cl-urdf:name + (cl-urdf:parse-urdf + (roslisp:get-param rob-int:*environment-description-parameter*))) + :keyword))) + (rob-int:set-environment-name environment-name) + (roslisp:ros-info (cram-tf init-tf) "Environment name is ~a." environment-name)) + + ;; initialize *TRANSFORMER* (setf *transformer* (make-instance 'cl-tf:transform-listener)) (roslisp:ros-info (cram-tf init-tf) "Initialized *transformer* to a ~a." (type-of *transformer*)) + ;; set the TF-DEFAULT-TIMEOUT (when (roslisp:get-param "use_sim_time" nil) (setf *tf-default-timeout* 10.0)) (roslisp:ros-info (cram-tf init-tf) "*tf-default-timeout* is ~a." *tf-default-timeout*) + ;; set the robot name based on the name in the urdf + (let ((robot-name + (roslisp-utilities:lispify-ros-underscore-name + (cl-urdf:name + (cl-urdf:parse-urdf + (cut:replace-all ; our pr2 urdf has some garbage inside :( + (roslisp:get-param rob-int:*robot-description-parameter*) + "\\" " "))) + :keyword))) + (rob-int:set-robot-name robot-name) + (roslisp:ros-info (cram-tf init-tf) "Robot name is ~a." robot-name)) + + ;; set variables based on robot knowledge (ROB-INT package) (with-vars-bound (?odom-frame) (lazy-car (prolog `(and (robot ?robot) (robot-odom-frame ?robot ?odom-frame)))) @@ -103,15 +129,18 @@ or in general at compile-time.") (with-vars-bound (?torso-frame ?torso-joint) (lazy-car (prolog `(and (robot ?robot) - (robot-torso-link-joint ?robot ?torso-frame ?torso-joint)))) + (robot-torso-link-joint ?robot + ?torso-frame ?torso-joint)))) (initialize-var *robot-torso-frame* ?torso-frame) (initialize-var *robot-torso-joint* ?torso-joint)) - (with-vars-bound (?left-tool-frame ?right-tool-frame) + (with-vars-bound (?left-tool-frame) + (lazy-car (prolog `(and (robot ?robot) + (robot-tool-frame ?robot :left ?left-tool-frame)))) + (initialize-var *robot-left-tool-frame* ?left-tool-frame)) + (with-vars-bound (?right-tool-frame) (lazy-car (prolog `(and (robot ?robot) - (robot-tool-frame ?robot :left ?left-tool-frame) (robot-tool-frame ?robot :right ?right-tool-frame)))) - (initialize-var *robot-left-tool-frame* ?left-tool-frame) (initialize-var *robot-right-tool-frame* ?right-tool-frame)))) (defun destroy-tf () diff --git a/cram_common/cram_tf/src/utilities.lisp b/cram_common/cram_tf/src/utilities.lisp index 0cc733453d..700c55d4c0 100644 --- a/cram_common/cram_tf/src/utilities.lisp +++ b/cram_common/cram_tf/src/utilities.lisp @@ -38,7 +38,7 @@ (cl-transforms:orientation pose-2)) ang-sigma))) -(defun frame-to-pose-in-fixed-frame (frame-name) +(defun frame-to-pose-in-fixed-frame (frame-name &optional parent-frame) (when *transformer* (transform-pose-stamped *transformer* @@ -46,7 +46,26 @@ :pose (make-pose-stamped frame-name 0.0 (make-identity-vector) (make-identity-rotation)) - :target-frame *fixed-frame*))) + :target-frame (or parent-frame *fixed-frame*)))) + +(defun frame-to-transform-in-fixed-frame (frame-name &optional parent-frame) + (when *transformer* + (cl-transforms-stamped:lookup-transform + *transformer* + parent-frame frame-name + :timeout *tf-default-timeout* + :time 0.0))) + +(defun 3d-vector->list (3d-vector) + (let ((x (cl-transforms:x 3d-vector)) + (y (cl-transforms:y 3d-vector)) + (z (cl-transforms:z 3d-vector))) + (list x y z))) + +(defun list->3d-vector (position-list) + (destructuring-bind (x y z) + position-list + (cl-transforms:make-3d-vector x y z))) (defun pose->flat-list (pose) (let* ((xyz (cl-transforms:origin pose)) @@ -148,18 +167,31 @@ :timeout *tf-default-timeout* :use-current-ros-time use-current-ros-time)) -(defun translate-pose (pose &key (x-offset 0.0) (y-offset 0.0) (z-offset 0.0)) +(defun ensure-transform-in-frame (transform frame + &key use-current-ros-time use-zero-time) + (declare (type (or null cl-transforms-stamped:transform-stamped))) + (when transform + (let* ((child-frame + (cl-transforms-stamped:child-frame-id transform)) + (new-pose-stamped + (ensure-pose-in-frame (strip-transform-stamped transform) + frame + :use-current-ros-time use-current-ros-time + :use-zero-time use-zero-time))) + (pose-stamped->transform-stamped new-pose-stamped child-frame)))) + +(defun translate-pose (pose &key (x 0.0) (y 0.0) (z 0.0)) (let* ((pose-origin (cl-transforms:origin pose)) (new-origin (cl-transforms:copy-3d-vector pose-origin :x (let ((x-pose-origin (cl-transforms:x pose-origin))) - (+ x-pose-origin x-offset)) + (+ x-pose-origin x)) :y (let ((y-pose-origin (cl-transforms:y pose-origin))) - (+ y-pose-origin y-offset)) + (+ y-pose-origin y)) :z (let ((z-pose-origin (cl-transforms:z pose-origin))) - (+ z-pose-origin z-offset))))) + (+ z-pose-origin z))))) (etypecase pose (cl-transforms-stamped:pose-stamped (cl-transforms-stamped:copy-pose-stamped pose :origin new-origin)) @@ -223,20 +255,6 @@ (cl-transforms:transform (cl-transforms:copy-transform transform :rotation new-rotation))))) -(defun tf-frame-converged (goal-frame goal-pose-stamped delta-xy delta-theta) - (let* ((pose-in-frame - (cram-tf:ensure-pose-in-frame - goal-pose-stamped - goal-frame - :use-zero-time t)) - (goal-dist (max (abs (cl-transforms:x (cl-transforms:origin pose-in-frame))) - (abs (cl-transforms:y (cl-transforms:origin pose-in-frame))))) - (goal-angle (cl-transforms:normalize-angle - (cl-transforms:get-yaw - (cl-transforms:orientation pose-in-frame))))) - (and (<= goal-dist delta-xy) - (<= (abs goal-angle) delta-theta)))) - (defun pose->transform-stamped (parent-frame child-frame stamp pose) (let ((translation (cl-transforms:origin pose)) (rotation (cl-transforms:orientation pose))) @@ -271,37 +289,40 @@ Take xTy, ensure it's from x-frame. Multiply from the right with the yTz transform -- xTy * yTz == xTz." - (unless (string-equal (cl-transforms-stamped:frame-id x-y-transform) x-frame) - (warn "~%~%~%~%!!!!!~%~%~%In multiply-transform-stampeds X-Y-TRANSFORM did not have ~ - correct parent frame: ~a and ~a" - (cl-transforms-stamped:frame-id x-y-transform) x-frame)) - - (unless (string-equal (cl-transforms-stamped:child-frame-id y-z-transform) z-frame) - (warn "~%~%~%~%!!!!!~%~%~%In multiply-transform-stampeds Y-Z-TRANSFORM did not have ~ - correct child frame: ~a and ~a" - (cl-transforms-stamped:child-frame-id y-z-transform) z-frame)) - - (unless (string-equal (cl-transforms-stamped:child-frame-id x-y-transform) - (cl-transforms-stamped:frame-id y-z-transform)) - (warn "~%~%~%~%!!!!!~%~%~%In multiply-transform-stampeds X-Y-TRANSFORM and ~ - Y-Z-TRANSFORM did not have equal corresponding frames: ~a and ~a" - (cl-transforms-stamped:child-frame-id x-y-transform) - (cl-transforms-stamped:frame-id y-z-transform))) + (when (string-not-equal (cl-transforms-stamped:frame-id x-y-transform) + x-frame) + (warn "~%~%~%~%!!!!!~%~%~%In multiply-transform-stampeds X-Y-TRANSFORM~%~ + did not have correct parent frame: ~a and ~a" + (cl-transforms-stamped:frame-id x-y-transform) x-frame)) + + (when (string-not-equal (cl-transforms-stamped:child-frame-id y-z-transform) + z-frame) + (warn "~%~%~%~%!!!!!~%~%~%In multiply-transform-stampeds Y-Z-TRANSFORM~%~ + did not have correct child frame: ~a and ~a" + (cl-transforms-stamped:child-frame-id y-z-transform) z-frame)) + + (when (string-not-equal (cl-transforms-stamped:child-frame-id x-y-transform) + (cl-transforms-stamped:frame-id y-z-transform)) + (warn "~%~%~%~%!!!!!~%~%~%In multiply-transform-stampeds X-Y-TRANSFORM and~%~ + Y-Z-TRANSFORM did not have equal corresponding frames: ~a and ~a" + (cl-transforms-stamped:child-frame-id x-y-transform) + (cl-transforms-stamped:frame-id y-z-transform))) (let ((multiplied-transforms (cl-transforms:transform* x-y-transform y-z-transform)) - (timestamp (min (cl-transforms-stamped:stamp x-y-transform) - (cl-transforms-stamped:stamp y-z-transform)))) + (timestamp + (min (cl-transforms-stamped:stamp x-y-transform) + (cl-transforms-stamped:stamp y-z-transform)))) (ecase result-as-pose-or-transform (:pose (cl-transforms-stamped:pose->pose-stamped - x-frame + (cl-transforms-stamped:frame-id x-y-transform) timestamp (cl-transforms:transform->pose multiplied-transforms))) (:transform (cl-transforms-stamped:transform->transform-stamped - x-frame - z-frame + (cl-transforms-stamped:frame-id x-y-transform) + (cl-transforms-stamped:child-frame-id y-z-transform) timestamp multiplied-transforms))))) @@ -321,18 +342,20 @@ Multiply from the right with the yTz transform -- xTy * yTz == xTz." (or translation (cl-transforms-stamped:translation transform-stamped)) (or rotation (cl-transforms-stamped:rotation transform-stamped)))) -(defun translate-transform-stamped (transform &key (x-offset 0.0) (y-offset 0.0) (z-offset 0.0)) +(defun translate-transform-stamped (transform + &key (x-offset 0.0) (y-offset 0.0) (z-offset 0.0)) (copy-transform-stamped transform - :translation (let ((transform-translation (cl-transforms:translation transform))) - (cl-transforms:copy-3d-vector - transform-translation - :x (let ((x-transform-translation (cl-transforms:x transform-translation))) - (+ x-transform-translation x-offset)) - :y (let ((y-transform-translation (cl-transforms:y transform-translation))) - (+ y-transform-translation y-offset)) - :z (let ((z-transform-translation (cl-transforms:z transform-translation))) - (+ z-transform-translation z-offset)))))) + :translation + (let ((transform-translation (cl-transforms:translation transform))) + (cl-transforms:copy-3d-vector + transform-translation + :x (let ((x-transform-translation (cl-transforms:x transform-translation))) + (+ x-transform-translation x-offset)) + :y (let ((y-transform-translation (cl-transforms:y transform-translation))) + (+ y-transform-translation y-offset)) + :z (let ((z-transform-translation (cl-transforms:z transform-translation))) + (+ z-transform-translation z-offset)))))) (defun pose-stamped->transform-stamped (pose-stamped child-frame-id) (cl-transforms-stamped:make-transform-stamped @@ -342,6 +365,12 @@ Multiply from the right with the yTz transform -- xTy * yTz == xTz." (cl-transforms-stamped:origin pose-stamped) (cl-transforms-stamped:orientation pose-stamped))) +(defun pose-stamped->point-stamped (pose-stamped) + (cl-transforms-stamped:make-point-stamped + (cl-transforms-stamped:frame-id pose-stamped) + (cl-transforms-stamped:stamp pose-stamped) + (cl-transforms-stamped:origin pose-stamped))) + (defun apply-transform (left-hand-side-transform right-hand-side-transform) (cram-tf:multiply-transform-stampeds (cl-transforms-stamped:frame-id left-hand-side-transform) @@ -371,3 +400,157 @@ Multiply from the right with the yTz transform -- xTy * yTz == xTz." deltas (list deltas)))) ;; actually compare (every #'value-converged values goal-values deltas))) + +(defun tf-frame-converged (goal-frame goal-pose-stamped delta-xy delta-theta) + (let* ((pose-in-frame + (cram-tf:ensure-pose-in-frame + goal-pose-stamped + goal-frame + :use-zero-time t)) + (goal-dist (max (abs (cl-transforms:x (cl-transforms:origin pose-in-frame))) + (abs (cl-transforms:y (cl-transforms:origin pose-in-frame))) + (abs (cl-transforms:z (cl-transforms:origin pose-in-frame))))) + (goal-angle (cl-transforms:normalize-angle + (cl-transforms:get-yaw + (cl-transforms:orientation pose-in-frame))))) + (and (<= goal-dist delta-xy) + (<= (abs goal-angle) delta-theta)))) + +(defun pose-stampeds-converged (pose other-pose delta-position delta-rotation) + (declare (type (or null cl-transforms-stamped:pose-stamped) pose other-pose)) + (when (and pose other-pose) + (if (string-not-equal (cl-transforms-stamped:frame-id pose) + (cl-transforms-stamped:frame-id other-pose)) + (warn "[CRAM-TF:POSE-STAMPEDS-CONVERGED]: frames were not equal: ~a vs. ~a" + (cl-transforms-stamped:frame-id pose) + (cl-transforms-stamped:frame-id other-pose)) + (and (< (cl-transforms:v-norm + (cl-transforms:v- + (cl-transforms:origin pose) + (cl-transforms:origin other-pose))) + delta-position) + (< (abs + (cl-transforms:normalize-angle + (cl-transforms:angle-between-quaternions + (cl-transforms:orientation pose) + (cl-transforms:orientation other-pose)))) + delta-rotation))))) + + +(defun normalize-joint-angles (list-of-angles) + (mapcar #'cl-transforms:normalize-angle list-of-angles)) + + +(defun map-axis-aligned-axis (input-quaternion &optional (map-axis 2)) + (declare (type cl-transforms:quaternion input-quaternion)) + "Returns a list with (axis-index projection-positive), +where axis-index is a number 0, 1 or 2 (for x, y or z correspondingly), +depending on which axis is aligned with the given fixed frame `map-axis', +and projection-positive is T if the axis-index axis is pointing in the direction +of the `map-axis' or NIL if it looks in the opposite direction. +For example, if `map-axis' is 2, then we want to find which axis of +`input-quaternion' is aligned with map Z +and the projection-positive will T if axis-index looks up and NIL if it looks down. +projection-on-axis is a number between [-1; -0.57) V (0.57; 1], +which is the length of the projection of the `map-axis' +onto the correspondingly aligned object axis, +projection-positive is calculated based on the sing of projection-on-axis." + (let* ((rotation-matrix + (cl-transforms:quaternion->matrix input-quaternion)) + (map-axis-in-input-frame + `(,(aref rotation-matrix map-axis 0) + ,(aref rotation-matrix map-axis 1) + ,(aref rotation-matrix map-axis 2))) + (axis-index + 0) + (projection-on-axis-abs + (abs (nth axis-index map-axis-in-input-frame))) + (projection-on-axis + (nth axis-index map-axis-in-input-frame))) + (loop for i from 1 to 2 + do (when (> (abs (nth i map-axis-in-input-frame)) + projection-on-axis-abs) + (setf projection-on-axis-abs + (abs (nth i map-axis-in-input-frame)) + projection-on-axis + (nth i map-axis-in-input-frame) + axis-index + i))) + (list axis-index (> projection-on-axis 0)))) + +(defun map-axis-aligned-orientation (input-quaternion) + (declare (type cl-transforms:quaternion input-quaternion)) + "The returned orientation is of type cl-transforms:quaternion +and has its axes aligned with the identity axes of map (Z up, X forward, Y left), +i.e. the rotation matrix is a permutation and possibly negation of the identity. +For example, if the object is not flatly lying on the horizontal plane, +the axis-aligned orientation will put it on the plane and also correct +the angle around the map Z axis, such that the other two axes are aligned +with the X and Y of the map" + (destructuring-bind (axis-facing-up-index axis-positive-p) + (map-axis-aligned-axis input-quaternion) + (if axis-positive-p + (ecase axis-facing-up-index + (0 + ;; x is up, so align with y, i.e. y of object looks to the left + (cl-transforms:axis-angle->quaternion + (cl-transforms:make-3d-vector 0 1 0) (/ pi -2))) + (1 + ;; y is up, so align with x, i.e. x of object looks forward + (cl-transforms:axis-angle->quaternion + (cl-transforms:make-3d-vector 1 0 0) (/ pi 2))) + (2 + ;; z is up, so align with x and y + (cl-transforms:make-identity-rotation))) + (ecase axis-facing-up-index + (0 + ;; x is down, so align with y, i.e. y of object looks to the left + (cl-transforms:axis-angle->quaternion + (cl-transforms:make-3d-vector 0 1 0) (/ pi 2))) + (1 + ;; y is down, so align with x, i.e. x of object looks forward + (cl-transforms:axis-angle->quaternion + (cl-transforms:make-3d-vector 1 0 0) (/ pi -2))) + (2 + ;; z is down, so align with x and y + (cl-transforms:axis-angle->quaternion + (cl-transforms:make-3d-vector 0 1 0) pi)))))) + +(defun angle-around-map-z (input-quaternion) + (declare (type cl-transforms:quaternion input-quaternion)) + "Calculates the angle between `input-quaternion' and +the corresponding axis-aligned orientation as per MAP-AXIS-ALIGNED-ORIENTATION, +assuming that the object is flatly lying on a horizontal plane, +i.e. that the angles around X and Y are 0." + ;; find out which axis in the `input-quaternion' is aligned with map Z + (destructuring-bind (axis-facing-up-index axis-positive-p) + (map-axis-aligned-axis input-quaternion) + ;; find the map axis-aligned orientation for `input-quaternion' + (let ((map-axis-aligned-quaternion + (map-axis-aligned-orientation input-quaternion))) + ;; find the angle between `input-quaternion' and map-axis-aligned-quaternion + ;; this angle is the orientation of input frame in axis-aligned frame + (multiple-value-bind (axis-aligned-R-input-angle axis-aligned-R-input-axis) + (cl-transforms:angle-between-quaternions + map-axis-aligned-quaternion + input-quaternion) + ;; angle-between-quaternions returns an angle and an axis, + ;; around which to rotate with the angle. + ;; the axis is going to be in axis-aligned coordinate frame + ;; and the angle might be clockwise or counterclockwise around that axis, + ;; so normalize it according to the right-hand rule + (let* ((axis-aligned-R-input-angle-normalized + (if (> (nth axis-facing-up-index + (3d-vector->list axis-aligned-R-input-axis)) + 0) + axis-aligned-R-input-angle + (* -1 axis-aligned-R-input-angle))) + ;; now that we know the angle between axis-aligned and input, + ;; we need to put that angle around map's Z axis. + ;; for that, we need to know if the vertical axis of `input-quaternion' + ;; is pointing up or down, if it points down we need to go clockwise + (angle-around-map-positive-Z + (if axis-positive-p + axis-aligned-R-input-angle-normalized + (* -1 axis-aligned-R-input-angle-normalized)))) + angle-around-map-positive-Z))))) diff --git a/cram_common/cram_tf/src/visualization.lisp b/cram_common/cram_tf/src/visualization.lisp index bd0ec96559..ce14517fcf 100644 --- a/cram_common/cram_tf/src/visualization.lisp +++ b/cram_common/cram_tf/src/visualization.lisp @@ -55,7 +55,7 @@ (cl-transforms-stamped:pose-stamped (cl-transforms-stamped:frame-id pose)) (t (or in-frame cram-tf:*fixed-frame*))) - ns "goal_locations" + ns "cram_goal_locations" id id type (roslisp:symbol-code 'visualization_msgs-msg: diff --git a/cram_core/cram_designators/src/cram-designators/package.lisp b/cram_core/cram_designators/src/cram-designators/package.lisp index 4ec477b1af..eee812fd5b 100644 --- a/cram_core/cram_designators/src/cram-designators/package.lisp +++ b/cram_core/cram_designators/src/cram-designators/package.lisp @@ -72,6 +72,7 @@ #:motion-designator #:motion-grounding #:location-designator #:*location-generator-max-retries* + #:*print-location-validation-function-results* #:register-location-generator #:register-location-validation-function #:list-location-generators diff --git a/cram_core/cram_executive/src/perform.lisp b/cram_core/cram_executive/src/perform.lisp index 916e64682b..8c556dd611 100644 --- a/cram_core/cram_executive/src/perform.lisp +++ b/cram_core/cram_executive/src/perform.lisp @@ -36,37 +36,45 @@ ((result :initarg :result :reader result :initform nil)) (:default-initargs :format-control "designator-goal-parsing-failure")) -(defun try-reference-designator (designator &optional (error-message "")) - (handler-case (reference designator) - (desig:designator-error () - (cpl:fail 'designator-reference-failure - :format-control "Designator ~a could not be resolved.~%~a" - :format-arguments (list designator error-message))))) +(defgeneric try-reference-designator (designator &optional error-message) + (:method (designator &optional (error-message "")) + (handler-case (reference designator) + (desig:designator-error () + (cpl:fail 'designator-reference-failure + :format-control "Designator ~a could not be resolved.~%~a" + :format-arguments (list designator error-message)))))) (defun convert-desig-goal-to-occasion (keyword-expression) - (handler-case (destructuring-bind (occasion &rest params) - keyword-expression - (cons ;; (intern (string-upcase occasion) :keyword) - occasion - params)) + (handler-case + (destructuring-bind (occasion &rest params) + keyword-expression + ;; (intern (string-upcase occasion) :keyword) + (cons occasion params)) (error (error-message) (cpl:fail 'designator-goal-parsing-failure :format-control "Designator goal ~a could not be parsed.~%~a" :format-arguments (list keyword-expression error-message))))) -(defun call-plan-with-designator-properties (plan-function action-designator) +(defun call-action-designator-plan (action-designator) (declare (type desig:action-designator action-designator)) "Returns the result of executing the plan function and the action-designator that was used as the parameter of the plan as multiple values." - (let ((designator-props-as-key-lambda-list - (let (plist) - (dolist (pair (desig:properties action-designator)) - (push (first pair) plist) - (push (second pair) plist)) - (nreverse plist)))) - (roslisp:ros-info (perform resolved) "~%~A~%~%" action-designator) - (values (apply plan-function designator-props-as-key-lambda-list) - action-designator))) + (destructuring-bind (plan-function referenced-action-designator) + (try-reference-designator action-designator) + (if (fboundp plan-function) + (let ((designator-props-as-key-lambda-list + (let (plist) + (dolist (pair (desig:properties referenced-action-designator)) + (push (first pair) plist) + (push (second pair) plist)) + (nreverse plist)))) + (roslisp:ros-info (perform resolved) "~%~A~%~%" + referenced-action-designator) + (values (apply plan-function designator-props-as-key-lambda-list) + referenced-action-designator)) + (cpl:fail "Action designator `~a' resolved to cram function `~a', ~ + but it isn't defined. Cannot perform action." + action-designator plan-function)))) (cpl:declare-goal perform (designator) (declare (ignore designator)) @@ -94,20 +102,16 @@ similar to what we have for locations.") (:method ((designator action-designator)) (roslisp:ros-info (perform action) "~%~A~%~%" designator) - (destructuring-bind (plan referenced-action-designator) - (try-reference-designator designator) - (if (fboundp plan) - (let ((desig-goal (desig-prop-value designator :goal))) + (let ((desig-goal (desig-prop-value designator :goal))) (if desig-goal (let ((occasion (convert-desig-goal-to-occasion desig-goal))) - (if (cram-occasions-events:holds occasion) - (warn 'simple-warning - :format-control "Action goal `~a' already achieved." - :format-arguments (list occasion)) - (call-plan-with-designator-properties plan referenced-action-designator)) - (unless (cram-occasions-events:holds occasion) - (cpl:fail "Goal `~a' of action `~a' was not achieved." - occasion designator))) - (call-plan-with-designator-properties plan referenced-action-designator))) - (cpl:fail "Action designator `~a' resolved to cram function `~a', ~ - but it isn't defined. Cannot perform action." designator plan))))) + (prog1 + (if (cram-occasions-events:holds occasion) + (roslisp:ros-info (perform action) + "Action goal `~a' already achieved." + (list occasion)) + (call-action-designator-plan designator)) + (unless (cram-occasions-events:holds occasion) + (warn "Goal `~a' of action `~a' was not achieved." + occasion designator)))) + (call-action-designator-plan designator))))) diff --git a/cram_core/cram_utilities/src/package.lisp b/cram_core/cram_utilities/src/package.lisp index a405f72cb4..a1fa081292 100644 --- a/cram_core/cram_utilities/src/package.lisp +++ b/cram_core/cram_utilities/src/package.lisp @@ -120,6 +120,7 @@ #:compare #:choose #:equalize-two-list-lengths #:equalize-lists-of-lists-lengths + #:recursive-alist-hash-table ;; time #:current-timestamp #:set-default-timestamp-function @@ -161,7 +162,7 @@ #:with-hash-table-locked ;; utils #:minimum #:maximum #:compare - #:execute-string + #:execute-string #:replace-all ;; semaphores, reexported from sb-thread ,@+semaphore-symbols+ ;; mailboxes, reexported from sb-concurrency diff --git a/cram_core/cram_utilities/src/utils.lisp b/cram_core/cram_utilities/src/utils.lisp index a6f6196b86..61df5c0136 100644 --- a/cram_core/cram_utilities/src/utils.lisp +++ b/cram_core/cram_utilities/src/utils.lisp @@ -165,19 +165,30 @@ removes deletes the file and the compiled file after loading it." -(defun equalize-two-list-lengths (first-list second-list) +(defun equalize-two-list-lengths (first-list second-list &key return-as-list) "Returns two lists of equal length as VALUES. To achieve equal length appends NILs at the end of the shorter of `first-list' and `second-list'." - (let* ((first-length (length first-list)) - (second-length (length second-list)) - (max-length (max first-length second-length))) - (values - (if (> max-length first-length) - (append first-list (make-list (- max-length first-length))) - first-list) - (if (> max-length second-length) - (append second-list (make-list (- max-length second-length))) - second-list)))) + (unless (listp first-list) + (setf first-list (list first-list))) + (unless (listp second-list) + (setf second-list (list second-list))) + (let* ((first-length + (length first-list)) + (second-length + (length second-list)) + (max-length + (max first-length second-length)) + (first-list-equalized + (if (> max-length first-length) + (append first-list (make-list (- max-length first-length))) + first-list)) + (second-list-equalized + (if (> max-length second-length) + (append second-list (make-list (- max-length second-length))) + second-list))) + (if return-as-list + (list first-list-equalized second-list-equalized) + (values first-list-equalized second-list-equalized)))) (defun equalize-lists-of-lists-lengths (first-list-of-lists second-list-of-lists) "Equalizes the length of lists inside of lists. E.g.: @@ -198,3 +209,35 @@ To achieve equal length appends NILs at the end of the shorter of `first-list' a (values first-result-l-of-ls second-result-l-of-ls))) + + +(defun recursive-alist-hash-table (alist &rest hash-table-initargs) + "Returns a hash table containing the keys and values of the association list +ALIST. Hash table is initialized using the HASH-TABLE-INITARGS. +This is a recursive version of alexandria:alist-hash-table." + (let ((table (apply #'make-hash-table hash-table-initargs))) + (dolist (cons alist) + (alexandria:ensure-gethash + (car cons) + table + (if (listp (cdr cons)) + (apply #'recursive-alist-hash-table (cdr cons) hash-table-initargs) + (cdr cons)))) + table)) + + +(defun replace-all (string part replacement &key (test #'char=)) + "Returns a new string in which all the occurences of the part +is replaced with replacement. + Taken from Common Lisp Cookbook." + (with-output-to-string (out) + (loop with part-length = (length part) + for old-pos = 0 then (+ pos part-length) + for pos = (search part string + :start2 old-pos + :test test) + do (write-string string out + :start old-pos + :end (or pos (length string))) + when pos do (write-string replacement out) + while pos))) diff --git a/cram_boxy/cram_boxy_assembly_demo/CMakeLists.txt b/cram_demos/cram_boxy_assembly_demo/CMakeLists.txt similarity index 100% rename from cram_boxy/cram_boxy_assembly_demo/CMakeLists.txt rename to cram_demos/cram_boxy_assembly_demo/CMakeLists.txt diff --git a/cram_boxy/cram_boxy_assembly_demo/cram-boxy-assembly-demo.asd b/cram_demos/cram_boxy_assembly_demo/cram-boxy-assembly-demo.asd similarity index 94% rename from cram_boxy/cram_boxy_assembly_demo/cram-boxy-assembly-demo.asd rename to cram_demos/cram_boxy_assembly_demo/cram-boxy-assembly-demo.asd index 5bf05bbeab..7d74455499 100644 --- a/cram_boxy/cram_boxy_assembly_demo/cram-boxy-assembly-demo.asd +++ b/cram_demos/cram_boxy_assembly_demo/cram-boxy-assembly-demo.asd @@ -46,33 +46,36 @@ cram-projection cram-occasions-events cram-utilities ; for EQUALIZE-LISTS-OF-LISTS-LENGTHS + cram-process-modules cram-common-failures cram-mobile-pick-place-plans cram-robot-interfaces ; for *robot-urdf* cram-object-knowledge - ;; cram-robosherlock + cram-manipulation-interfaces ; for standard rotations + - cram-physics-utils ; for reading "package://" paths + cram-physics-utils ; for reading "package://" paths cl-bullet ; for handling BOUNDING-BOX datastructures cram-bullet-reasoning cram-bullet-reasoning-belief-state cram-bullet-reasoning-utilities - cram-btr-visibility-costmap + cram-location-costmap cram-robot-pose-gaussian-costmap cram-occupancy-grid-costmap - cram-location-costmap - cram-manipulation-interfaces ; for standard rotations + cram-btr-visibility-costmap + cram-btr-spatial-relations-costmap + + cram-fetch-deliver-plans cram-urdf-projection ; for with-simulated-robot cram-boxy-description - ;; cram-boxy-low-level - cram-process-modules - ;; cram-boxy-process-modules - cram-boxy-plans ; for (a location (on ?obj) (attachment ?att) ...) ;; real robot + ;; cram-boxy-low-level + ;; cram-boxy-process-modules + ;; cram-robosherlock ) :components @@ -80,5 +83,6 @@ :components ((:file "package") (:file "setup" :depends-on ("package")) + (:file "costmaps" :depends-on ("package")) (:file "projection-demo" :depends-on ("package")) (:file "demo" :depends-on ("package" "projection-demo")))))) diff --git a/cram_boxy/cram_boxy_assembly_demo/launch/sandbox.launch b/cram_demos/cram_boxy_assembly_demo/launch/sandbox.launch similarity index 100% rename from cram_boxy/cram_boxy_assembly_demo/launch/sandbox.launch rename to cram_demos/cram_boxy_assembly_demo/launch/sandbox.launch diff --git a/cram_boxy/cram_boxy_assembly_demo/package.xml b/cram_demos/cram_boxy_assembly_demo/package.xml similarity index 93% rename from cram_boxy/cram_boxy_assembly_demo/package.xml rename to cram_demos/cram_boxy_assembly_demo/package.xml index f157768f89..109f72466e 100644 --- a/cram_boxy/cram_boxy_assembly_demo/package.xml +++ b/cram_demos/cram_boxy_assembly_demo/package.xml @@ -26,12 +26,13 @@ cram_projection cram_occasions_events cram_utilities + cram_process_modules cram_common_failures cram_mobile_pick_place_plans cram_robot_interfaces cram_object_knowledge - + cram_manipulation_interfaces cram_physics_utils cl_bullet @@ -39,17 +40,19 @@ cram_bullet_reasoning_belief_state cram_bullet_reasoning_utilities + cram_location_costmap cram_robot_pose_gaussian_costmap cram_occupancy_grid_costmap - cram_location_costmap - cram_manipulation_interfaces + cram_btr_visibility_costmap + cram_btr_spatial_relations_costmap + + cram_fetch_deliver_plans cram_urdf_projection cram_boxy_description - cram_process_modules - cram_boxy_plans + iai_maps diff --git a/cram_pr2/cram_pr2_pick_place_demo/src/costmaps.lisp b/cram_demos/cram_boxy_assembly_demo/src/costmaps.lisp similarity index 67% rename from cram_pr2/cram_pr2_pick_place_demo/src/costmaps.lisp rename to cram_demos/cram_boxy_assembly_demo/src/costmaps.lisp index 003cfe7fcf..ba98bbb600 100644 --- a/cram_pr2/cram_pr2_pick_place_demo/src/costmaps.lisp +++ b/cram_demos/cram_boxy_assembly_demo/src/costmaps.lisp @@ -31,22 +31,31 @@ (defun make-restricted-area-cost-function () (lambda (x y) - (if (> x 1.2) + (declare (ignore y)) + (if (> x -1.2) 0.0 - (if (and (> x 0.5) (> y -1.5) (< y 2.0)) - 1.0 - (if (and (> x 0.0) (> y -1.5) (< y 1.0)) - 1.0 - (if (and (< x 0.0) (> x -1.5) (> y -1.5) (< y 2.5)) - 1.0 - 0.0)))))) + 1.0))) (defmethod location-costmap:costmap-generator-name->score ((name (eql 'restricted-area))) 5) (def-fact-group demo-costmap (location-costmap:desig-costmap) (<- (location-costmap:desig-costmap ?designator ?costmap) - (or (cram-robot-interfaces:visibility-designator ?designator) - (cram-robot-interfaces:reachability-designator ?designator)) + (or (rob-int:visibility-designator ?designator) + (rob-int:reachability-designator ?designator)) + ;; make sure that the location is not on the robot itself + ;; if it is, don't generate a costmap + (once (or (and (desig:desig-prop ?designator (:object ?some-object)) + (desig:current-designator ?some-object ?object) + (lisp-fun man-int:get-object-pose-in-map ?object ?to-reach-pose) + (lisp-pred identity ?to-reach-pose) + (-> (desig:desig-prop ?object (:location ?loc)) + (not (man-int:location-always-reachable ?loc)) + (true))) + (and (desig:desig-prop ?designator (:location ?some-location)) + (desig:current-designator ?some-location ?location) + ;; if the location is on the robot itself, + ;; don't use the costmap + (not (man-int:location-always-reachable ?location))))) (location-costmap:costmap ?costmap) (location-costmap:costmap-add-function restricted-area diff --git a/cram_boxy/cram_boxy_projection/src/tf.lisp b/cram_demos/cram_boxy_assembly_demo/src/demo.lisp similarity index 79% rename from cram_boxy/cram_boxy_projection/src/tf.lisp rename to cram_demos/cram_boxy_assembly_demo/src/demo.lisp index 870675b0d2..b39ba012e7 100644 --- a/cram_boxy/cram_boxy_projection/src/tf.lisp +++ b/cram_demos/cram_boxy_assembly_demo/src/demo.lisp @@ -1,4 +1,5 @@ -;;; Copyright (c) 2012, Lorenz Moesenlechner +;;; +;;; Copyright (c) 2018, Gayane Kazhoyan ;;; All rights reserved. ;;; ;;; Redistribution and use in source and binary forms, with or without @@ -10,8 +11,8 @@ ;;; notice, this list of conditions and the following disclaimer in the ;;; documentation and/or other materials provided with the distribution. ;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software ;;; without specific prior written permission. ;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" @@ -26,10 +27,4 @@ ;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE ;;; POSSIBILITY OF SUCH DAMAGE. -(in-package :boxy-proj) - -(defmethod cram-occasions-events:on-event - update-tf ((event cram-plan-occasions-events:robot-state-changed)) - (when (eql cram-projection:*projection-environment* - 'cram-boxy-projection::boxy-bullet-projection-environment) - (cram-bullet-reasoning-belief-state:set-tf-from-bullet))) +(in-package :demo) diff --git a/cram_boxy/cram_boxy_assembly_demo/src/package.lisp b/cram_demos/cram_boxy_assembly_demo/src/package.lisp similarity index 100% rename from cram_boxy/cram_boxy_assembly_demo/src/package.lisp rename to cram_demos/cram_boxy_assembly_demo/src/package.lisp diff --git a/cram_demos/cram_boxy_assembly_demo/src/projection-demo.lisp b/cram_demos/cram_boxy_assembly_demo/src/projection-demo.lisp new file mode 100644 index 0000000000..d0711ccdf8 --- /dev/null +++ b/cram_demos/cram_boxy_assembly_demo/src/projection-demo.lisp @@ -0,0 +1,546 @@ +;;; +;;; Copyright (c) 2018, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Intelligent Autonomous Systems Group/ +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software +;;; without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :demo) + +(defparameter *plate-x* -1.1115) +(defparameter *plate-y* 1.6) +(defparameter *plate-z* 0.8626) + +(defparameter *plate-rad-x* 0.36) +(defparameter *plate-rad-y* 0.60) +(defparameter *plate-rad-z* 0.008) +(defparameter *holder-bolt-rad-x* 0.05) +(defparameter *holder-bolt-rad-y* 0.025) +(defparameter *holder-bolt-rad-z* 0.0125) +(defparameter *bolt-rad-x* 0.01) +(defparameter *bolt-rad-y* 0.01) +(defparameter *bolt-rad-z* 0.0225) +(defparameter *holder-upperbody-rad-x* 0.085) +(defparameter *holder-upperbody-rad-y* 0.025) +(defparameter *holder-upperbody-rad-z* 0.021) +(defparameter *holder-bottom-wing-rad-x* 0.035) +(defparameter *holder-bottom-wing-rad-y* 0.045) +(defparameter *holder-bottom-wing-rad-z* 0.045) +(defparameter *holder-underbody-rad-x* 0.0925) +(defparameter *holder-underbody-rad-y* 0.025) +(defparameter *holder-underbody-rad-z* 0.024) +(defparameter *holder-plane-horizontal-rad-x* 0.1015) +(defparameter *holder-plane-horizontal-rad-y* 0.05) +(defparameter *holder-plane-horizontal-rad-z* 0.0335) +(defparameter *holder-window-rad-x* 0.026) +(defparameter *holder-window-rad-y* 0.025) +(defparameter *holder-window-rad-z* 0.017) +(defparameter *front-wheel-rad-z* 0.015) +(defparameter *nut-rad-z* 0.0075) +(defparameter *chassis-rad-z* 0.0515) +(defparameter *holder-plane-vertical-rad-x* 0.065) +(defparameter *holder-plane-vertical-rad-y* 0.06) +(defparameter *holder-plane-vertical-rad-z* 0.0175) +(defparameter *holder-top-wing-rad-x* 0.035) +(defparameter *holder-top-wing-rad-y* 0.0415) +(defparameter *holder-top-wing-rad-z* 0.045) + +(defparameter *yellow-plastic* '(0.949 0.807 0.082)) +(defparameter *gray-plastic* '(0.568 0.592 0.584)) +(defparameter *red-plane* '(0.878 0.376 0.243)) +(defparameter *cyan-plane* '(0.078 0.513 0.541)) +(defparameter *yellow-plane* '(0.964 0.847 0.584)) +(defparameter *transparent-plane* '(1 1 1)) +(defparameter *black-plane* '(0.184 0.152 0.121)) +(defparameter *gray-plane* '(0.482 0.537 0.549)) + +(defparameter *object-spawning-data* + `((big-wooden-plate :big-wooden-plate (0.823 0.698 0.513) + ((,*plate-rad-x* ,*plate-rad-y* ,(- *plate-rad-z*)) (0 0 0 1))) + (holder-bolt :holder-bolt ,*yellow-plastic* + ((,*holder-bolt-rad-x* ,*holder-bolt-rad-y* ,*holder-bolt-rad-z*) (0 0 0 1))) + (holder-upper-body :holder-upper-body ,*yellow-plastic* + ((,(+ 0.05 *holder-upperbody-rad-x*) 0.10 ,*holder-upperbody-rad-z*) + (0 0 0 1))) + (holder-bottom-wing :holder-bottom-wing ,*gray-plastic* + ((,(+ 0.1 *holder-bottom-wing-rad-x*) + ,(- 0.3 *holder-bottom-wing-rad-y*) + ,*holder-bottom-wing-rad-z*) + ,man-int:*rotation-around-z-90-list*)) + (holder-underbody :holder-underbody ,*yellow-plastic* + ((,(+ 0.05 *holder-underbody-rad-x*) 0.4 ,*holder-underbody-rad-z*) + (0 0 0 1))) + (holder-plane-horizontal :holder-plane-horizontal ,*yellow-plastic* + ((,(+ 0.05 *holder-plane-horizontal-rad-x*) + 0.6 + ,*holder-plane-horizontal-rad-z*) + (0 0 0 1))) + (holder-window :holder-window ,*gray-plastic* + ((,*holder-window-rad-x* + ,(+ 0.75 *holder-window-rad-y*) + ,*holder-window-rad-z*) + (0 0 0 1))) + (holder-plane-vertical :holder-plane-vertical ,*yellow-plastic* + ((,*holder-plane-vertical-rad-x* + ,(- 1.0 *holder-plane-vertical-rad-y*) + ,*holder-plane-vertical-rad-z*) + (0 0 0 1))) + (holder-top-wing :holder-top-wing ,*yellow-plastic* + ((,(+ 0.15 *holder-top-wing-rad-x*) + ,(- 1.15 *holder-top-wing-rad-y*) + ,*holder-top-wing-rad-z*) + ,man-int:*rotation-around-z-90-list*)) + + ;; rear wing is already well positioned + (rear-wing :rear-wing ,*yellow-plane* + ((0.079 0.599 0.056) + ,man-int:*rotation-around-z+90-list*)) + + ;; bolts are used intermediately + (bolt-1 :bolt ,*gray-plane* + ((0.015 0.0125 ,*bolt-rad-z*) (0 0 0 1))) + (bolt-2 :bolt ,*gray-plane* + ((0.0325 0.0375 ,*bolt-rad-z*) (0 0 0 1))) + (bolt-3 :bolt ,*gray-plane* + ((0.05 0.0125 ,*bolt-rad-z*) (0 0 0 1))) + (bolt-4 :bolt ,*gray-plane* + ((0.0675 0.0375 ,*bolt-rad-z*) (0 0 0 1))) + (bolt-5 :bolt ,*gray-plane* + ((0.085 0.0125 ,*bolt-rad-z*) (0 0 0 1))) + + ;; first part of scenario on horizontal holder + (chassis :chassis ,*yellow-plane* + ((0.2 0.9 ,*chassis-rad-z*) ,man-int:*rotation-around-z-90-list*)) + (bottom-wing :bottom-wing ,*cyan-plane* + ((0.134 0.25 0.093) (0 0 0 1))) + (underbody :underbody ,*red-plane* + ((0.145 0.399 0.024) (0 0 0 1))) + (motor-grill :motor-grill ,*black-plane* + ((0.238 0.399 0.039) ,man-int:*rotation-around-y+90-list*)) + (upper-body :upper-body ,*red-plane* + ((0.119 0.1003 0.0482) (0 0 0 1))) + (top-wing :top-wing ,*cyan-plane* + ((0.18522 1.11423 0.08852) (0 0 0 1))) + (window :window ,*transparent-plane* + ((0.024 0.775 0.01962) (0 0 0 1))) + + ;; second part of scenario on vertical holder + (propeller :propeller ,*yellow-plane* + ((0.075 1.10 0) (0 0 0 1))) + (front-wheel-1 :front-wheel ,*black-plane* + ((0.15 0.775 ,*front-wheel-rad-z*) (0 0 0 1))) + (front-wheel-2 :front-wheel ,*black-plane* + ((0.215 0.775 ,*front-wheel-rad-z*) (0 0 0 1))) + (nut-1 :nut ,*gray-plane* + ((0.15 0.725 ,*nut-rad-z*) (0 0 0 1))) + (nut-2 :nut ,*gray-plane* + ((0.215 0.725 ,*nut-rad-z*) (0 0 0 1))))) + + +(defun spawn-objects-on-plate (&optional (spawning-data *object-spawning-data*)) + ;; (btr-utils:kill-all-objects) + ;; detach all objects from robot and environment + (btr:detach-all-objects (btr:get-robot-object)) + (btr:detach-all-objects (btr:get-environment-object)) + ;; detach all items from each other + (mapcar #'btr:detach-all-objects + (remove-if-not (lambda (obj) (typep obj 'btr:item)) + (btr:objects btr:*current-bullet-world*))) + ;; spawn objects at default poses + (let ((objects + (mapcar (lambda (object-name-type-pose-list) + (destructuring-bind (object-name object-type object-color + object-pose-list) + object-name-type-pose-list + (let ((object-relative-pose + (cram-tf:list->pose object-pose-list))) + (btr-utils:spawn-object + object-name + object-type + :mass 0.0 + :color object-color + :pose (cram-tf:pose->list + (cl-transforms:make-pose + (cl-transforms:v+ + (cl-transforms:make-3d-vector + (- *plate-x* *plate-rad-x*) + (- *plate-y* *plate-rad-y*) + (+ *plate-z* *plate-rad-z*)) + (cl-transforms:origin + object-relative-pose)) + (cl-transforms:orientation + object-relative-pose))))))) + spawning-data))) + + (btr:attach-object 'motor-grill 'underbody) + + objects)) + + +(defmethod exe:generic-perform :before (designator) + (format t "~%PERFORMING~%~A~%~%" designator)) + + +;;; ASSEMBLY STEPS: +;;; (1) put chassis on holder (bump inwards) +;;; (2) put bottom wing on chassis +;;; * maybe: dont hit the top-wing with the arm +;;; (3) put underbody on bottom wing +;;; (4) put upperbody on underbody +;;; (5) screw rear hole +;;; (6) put top wing on body +;;; (7) screw top wing +;;; (8) put window on body +;;; (9) screw window +;;; (10) put plane on vertical holder +;;; (11) put propeller on grill +;;; (12) screw propeller +;;; * put wheel on +;;; * screw nut onto wheel +;;; * put other wheel on +;;; * screw nut onto wheel +;;; * screw bottom body +(defun demo () + ;;(setf cram-robosherlock::*no-robosherlock-mode* t) + (spawn-objects-on-plate) + (setf btr:*visibility-threshold* 0.6) + + (urdf-proj:with-projected-robot + + (let ((wooden-plate + (desig:an object + (type big-wooden-plate) + (location (desig:a location + (on (desig:an object + (type counter-top) + (urdf-name + kitchen-island-surface) + (part-of iai-kitchen))) + (side back) + (range 0.5)))))) + ;; 1 + (go-transport :chassis '(:side :left) :holder-plane-horizontal '(:range 0.3) + :horizontal-attachment + wooden-plate) + ;; 2 + (go-transport :bottom-wing '(:side :right) :chassis '(:range 0.3) + :wing-attachment + wooden-plate) + ;; 3 + (go-transport :underbody '(:side :right) :bottom-wing '(:range 0.3) + :body-attachment + wooden-plate) + + ;; we put the underbody on the bottom-wing but by doing that + ;; we also put it on the rear-wing. + ;; as there is no explicit placing action, the two will not be + ;; attached automatically. + ;; so we have to attach them manually unfortunately. + ;; this is required for later moving the whole plane onto another holder + (btr:attach-object 'underbody 'rear-wing) + + ;; 4 + (go-transport :upper-body '(:side :right) :underbody '(:range 0.3) + :body-on-body + wooden-plate) + ;; 5 + (go-transport :bolt '(:side :right) :upper-body '(:range 0.3) + :rear-thread + wooden-plate) + ;; 6 + (go-transport :top-wing '(:side :left) :upper-body '(:range 0.3) + :wing-attachment + wooden-plate) + ;; 7 + (go-transport :bolt :bolt :top-wing '(:range 0.3) + :middle-thread + wooden-plate) + ;; 8 + (go-transport :window '(:side :left) :top-wing '(:range 0.3) + :window-attachment + wooden-plate) + ;; 9 + (go-transport :bolt :bolt :window '(:range 0.3) + :window-thread + wooden-plate) + + ;; 10 + (go-transport :top-wing '(:range 0.3) :holder-plane-vertical '(:side :left) + ;; or `((,(- *base-x* 0.00) 1.45 0) (0 0 0 1)) + :vertical-attachment + wooden-plate) + + ;; 11 + (go-transport :propeller '(:side :left) :motor-grill '(:side :left) + ;; or `((,(- *base-x* 0.15) 1.8 0) (0 0 0 1)) + :propeller-attachment + wooden-plate) + + ;; 12 + (go-transport :bolt :bolt :propeller '(:side :left) + ;; or `((,*base-x* 1.85 0) (0 0 0 1)) + :propeller-thread + wooden-plate)))) + + +(defun go-transport (?object-type ?object-location-property + ?other-object-type ?other-object-location-property + ?attachment-type + ?wooden-plate) + (let* ((?object-location + (if (eq ?object-location-property :bolt) + (desig:a location + (on (desig:an object + (type counter-top) + (urdf-name + kitchen-island-surface) + (part-of iai-kitchen))) + (side right) + (range-invert 0.9) + (side front)) + (desig:a location + (on ?wooden-plate) + ?object-location-property + (side front)))) + (?other-object-location + (desig:a location + (on ?wooden-plate) + ?other-object-location-property + (side front))) + (?object + (desig:an object + (type ?object-type) + (location ?object-location))) + (?other-object + (desig:an object + (type ?other-object-type) + (location ?other-object-location)))) + (exe:perform + (desig:an action + (type transporting) + (object ?object) + (arms (left)) + (target (desig:a location + (on ?other-object) + (for ?object) + (attachments (?attachment-type)))))))) + + + + +;;; ASSEMBLY STEPS: +;;; (1) put chassis on holder (bump inwards) +;;; (2) put bottom wing on chassis +;;; * maybe: dont hit the top-wing with the arm +;;; (3) put underbody on bottom wing +;;; (4) put upperbody on underbody +;;; (5) screw rear hole +;;; (6) put top wing on body +;;; (7) screw top wing +;;; (8) put window on body +;;; (9) screw window +;;; (10) put plane on vertical holder +;;; (11) put propeller on grill +;;; (12) screw propeller +;;; * put wheel on +;;; * screw nut onto wheel +;;; * put other wheel on +;;; * screw nut onto wheel +;;; * screw bottom body +(defun demo-hardcoded () + ;;(setf cram-robosherlock::*no-robosherlock-mode* t) + (spawn-objects-on-plate) + + (let* ((base-x + -2.4) + (base-very-left-side-left-hand-pose + `((,base-x 1.8 0) (0 0 0 1))) + (base-left-side-left-hand-pose + `((,base-x 1.5 0) (0 0 0 1))) + (base-somewhat-left-side-left-hand-pose + `((,base-x 1.3 0) (0 0 0 1))) + (base-middle-side-left-hand-pose + `((,base-x 1.1 0) (0 0 0 1))) + (base-right-side-left-hand-pose + `((,base-x 0.7 0) (0 0 0 1))) + (base-very-right-side-left-hand-pose + `((,(- base-x 0.2) 0.65 0) (0 0 0 1)))) + + (urdf-proj:with-projected-robot + ;; 1 + (go-connect :chassis base-very-left-side-left-hand-pose + :holder-plane-horizontal base-middle-side-left-hand-pose + :horizontal-attachment) + ;; 2 + (go-connect :bottom-wing base-very-right-side-left-hand-pose + :chassis base-left-side-left-hand-pose + :wing-attachment) + ;; 3 + (go-connect :underbody base-middle-side-left-hand-pose + :bottom-wing base-middle-side-left-hand-pose + :body-attachment) + + ;; we put the underbody on the bottom-wing but by doing that + ;; we also put it on the rear-wing. + ;; as there is no explicit placing action, the two will not be + ;; attached automatically. + ;; so we have to attach them manually unfortunately. + ;; this is required for later moving the whole plane onto another holder + (btr:attach-object 'underbody 'rear-wing) + + ;; 4 + (go-connect :upper-body base-right-side-left-hand-pose + :underbody base-left-side-left-hand-pose + :body-on-body) + ;; 5 + (go-connect :bolt base-right-side-left-hand-pose + :upper-body base-left-side-left-hand-pose + :rear-thread) + ;; 6 + (go-connect :top-wing base-left-side-left-hand-pose + :upper-body base-left-side-left-hand-pose + :wing-attachment) + ;; 7 + (go-connect :bolt base-right-side-left-hand-pose + :top-wing base-left-side-left-hand-pose + :middle-thread) + ;; 8 + (go-connect :window base-somewhat-left-side-left-hand-pose + :top-wing base-left-side-left-hand-pose + :window-attachment) + ;; 9 + (go-connect :bolt base-right-side-left-hand-pose + :window base-left-side-left-hand-pose + :window-thread) + + ;; 10 + (go-connect :top-wing base-somewhat-left-side-left-hand-pose + :holder-plane-vertical base-left-side-left-hand-pose + ;; or `((,(- *base-x* 0.00) 1.45 0) (0 0 0 1)) + :vertical-attachment) + + ;; 11 + (go-connect :propeller `((,(- base-x 0.15) 2 0) (0 0 0 1)) + :motor-grill base-left-side-left-hand-pose + ;; or `((,(- *base-x* 0.15) 1.8 0) (0 0 0 1)) + :propeller-attachment) + + ;; 12 + (go-connect :bolt base-right-side-left-hand-pose + :propeller base-left-side-left-hand-pose + ;; or `((,*base-x* 1.85 0) (0 0 0 1)) + :propeller-thread) + + ;;(go-connect :top-wing base-left-side-left-hand-pose + ;; :holder-plane-horizontal base-middle-side-left-hand-pose + ;; :horizontal-attachment) + + (exe:perform + (desig:an action + (type parking-arms)))))) + + +(defun go-connect (?object-type ?nav-goal ?other-object-type ?other-nav-goal + ?attachment-type) + (flet ((go-perceive (?object-type ?nav-goal) + ;; drive to right location + (let ((?pose (cl-transforms-stamped:pose->pose-stamped + cram-tf:*fixed-frame* + 0.0 + (btr:ensure-pose ?nav-goal)))) + (exe:perform + (desig:an action + (type navigating) + (location (desig:a location + (pose ?pose)))))) + ;; look down + (exe:perform + (desig:an action + (type looking) + (direction down-left))) + ;; perceive object + (let ((?object + (exe:perform + (desig:an action + (type detecting) + (object (desig:an object (type ?object-type))))))) + ;; look away + (exe:perform + (desig:an action + (type looking) + (direction away))) + ?object))) + + ;; go and perceive object to pick + (let ((?object + (go-perceive ?object-type ?nav-goal))) + ;; pick it up + (exe:perform + (desig:an action + (type picking-up) + (arm left) + (object ?object))) + ;; go and perceive other object + (let ((?other-object + (go-perceive ?other-object-type ?other-nav-goal))) + ;; place + (exe:perform + (desig:an action + (type placing) + (arm left) + (object ?object) + (target (desig:a location + (on ?other-object) + (for ?object) + (attachment ?attachment-type))))) + ;; return object and other object + (values ?object ?other-object))))) + +#+examples +( + (boxy-proj:with-projected-robot + (cram-executive:perform + (desig:an action + (type looking) + (direction down)))) + + (boxy-proj:with-projected-robot + (cram-executive:perform + (desig:an action + (type detecting) + (object (desig:an object (type chassis)))))) + + (boxy-proj:with-simulated-robot + (exe:perform + (desig:an action + (type opening-gripper) + (gripper left)))) + + (boxy-proj:with-projected-robot + (cram-executive:perform + (desig:an action + (type placing) + (arm left)))) + ) diff --git a/cram_demos/cram_boxy_assembly_demo/src/setup.lisp b/cram_demos/cram_boxy_assembly_demo/src/setup.lisp new file mode 100644 index 0000000000..2af1253239 --- /dev/null +++ b/cram_demos/cram_boxy_assembly_demo/src/setup.lisp @@ -0,0 +1,48 @@ +;;; +;;; Copyright (c) 2018, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Intelligent Autonomous Systems Group/ +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software +;;; without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :demo) + +;; roslaunch cram_boxy_assembly_demo sandbox.launch + +(defun init-projection () + ;; (setf cram-tf:*transformer* (make-instance 'cl-tf2:buffer-client)) + + (btr-belief:setup-world-database) + + (setf cram-tf:*tf-default-timeout* 2.0) + + (setf prolog:*break-on-lisp-errors* t) + + (cram-bullet-reasoning:clear-costmap-vis-object) + + (btr:add-objects-to-mesh-list "assembly_models" :directory "fixtures" :extension "stl") + (btr:add-objects-to-mesh-list "assembly_models" :directory "battat/convention" :extension "stl")) + +(roslisp-utilities:register-ros-init-function init-projection) diff --git a/cram_demos/cram_donbot_retail_demo/CMakeLists.txt b/cram_demos/cram_donbot_retail_demo/CMakeLists.txt new file mode 100644 index 0000000000..3e42586b32 --- /dev/null +++ b/cram_demos/cram_donbot_retail_demo/CMakeLists.txt @@ -0,0 +1,4 @@ +cmake_minimum_required(VERSION 2.8.3) +project(cram_donbot_retail_demo) +find_package(catkin REQUIRED) +catkin_package() diff --git a/cram_pr2/cram_pr2_projection/cram-pr2-projection.asd b/cram_demos/cram_donbot_retail_demo/cram-donbot-retail-demo.asd similarity index 56% rename from cram_pr2/cram_pr2_projection/cram-pr2-projection.asd rename to cram_demos/cram_donbot_retail_demo/cram-donbot-retail-demo.asd index 0d4c57939a..7d54c8676b 100644 --- a/cram_pr2/cram_pr2_projection/cram-pr2-projection.asd +++ b/cram_demos/cram_donbot_retail_demo/cram-donbot-retail-demo.asd @@ -1,4 +1,5 @@ -;;; Copyright (c) 2017, Gayane Kazhoyan +;;; +;;; Copyright (c) 2019, Gayane Kazhoyan ;;; All rights reserved. ;;; ;;; Redistribution and use in source and binary forms, with or without @@ -26,39 +27,61 @@ ;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE ;;; POSSIBILITY OF SUCH DAMAGE. -(defsystem cram-pr2-projection - :author "Gayane Kazhoyan" +(defsystem cram-donbot-retail-demo + :author "gaya" :license "BSD" - :depends-on (cram-projection - cram-prolog - cram-designators - cram-utilities - cram-bullet-reasoning - cram-bullet-reasoning-belief-state ; for event updating before ik requests - cram-tf - cram-robot-interfaces ; for ROBOT predicate and COMPUTE-IKS + :depends-on (roslisp-utilities ; for ros-init-function + cl-transforms cl-transforms-stamped - cl-tf + ;; cl-tf + ;; cl-tf2 + cram-tf + + cram-language + cram-executive + cram-designators + cram-prolog + cram-projection cram-occasions-events - cram-plan-occasions-events - cram-pr2-description ; to get kinematic structure names - cram-common-designators - cram-common-failures + cram-utilities ; for EQUALIZE-LISTS-OF-LISTS-LENGTHS cram-process-modules - alexandria ; for CURRY in low-level perception - roslisp-utilities ; for rosify-lisp-name - moveit_msgs-msg - moveit_msgs-srv) + + cram-common-failures + cram-mobile-pick-place-plans + cram-robot-interfaces ; for *robot-urdf* + cram-object-knowledge + cram-manipulation-interfaces ; for standard rotations + + cram-physics-utils ; for reading "package://" paths + cl-bullet ; for handling BOUNDING-BOX datastructures + cram-bullet-reasoning + cram-bullet-reasoning-belief-state + cram-bullet-reasoning-utilities + cram-urdf-projection ; for with-simulated-robot + cram-urdf-projection-reasoning + + cram-location-costmap + cram-btr-visibility-costmap + cram-robot-pose-gaussian-costmap + cram-btr-spatial-relations-costmap + ;; cram-occupancy-grid-costmap + + cram-fetch-deliver-plans + + cram-donbot-description + + ;; real robot + ;; cram-robosherlock + ;; cram-giskard + ;; cram-donbot-process-modules + ) + :components ((:module "src" :components ((:file "package") - (:file "projection-clock" :depends-on ("package")) - (:file "tf" :depends-on ("package")) - (:file "ik" :depends-on ("package")) - (:file "low-level" :depends-on ("package" "tf" "ik")) - (:file "process-modules" :depends-on ("package" "low-level")) - (:file "projection-environment" :depends-on ("package" "projection-clock" "tf" - "process-modules")))))) + (:file "costmaps" :depends-on ("package")) + (:file "setup" :depends-on ("package")) + (:file "demo" :depends-on ("package")))))) diff --git a/cram_demos/cram_donbot_retail_demo/launch/sandbox.launch b/cram_demos/cram_donbot_retail_demo/launch/sandbox.launch new file mode 100644 index 0000000000..4e2689c506 --- /dev/null +++ b/cram_demos/cram_donbot_retail_demo/launch/sandbox.launch @@ -0,0 +1,57 @@ + + + + + + + + + + + + + + + + + + + + - /kitchen/cram_joint_states + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/cram_demos/cram_donbot_retail_demo/package.xml b/cram_demos/cram_donbot_retail_demo/package.xml new file mode 100644 index 0000000000..19641d821d --- /dev/null +++ b/cram_demos/cram_donbot_retail_demo/package.xml @@ -0,0 +1,62 @@ + + cram_donbot_retail_demo + 0.7.0 + Demo code for shelf replenishment with Donbot + Gayane Kazhoyan + Gayane Kazhoyan + BSD + + http://cram-system.org + http://github.com/cram2/cram + + catkin + + roslisp_utilities + + cl_transforms + cl_transforms_stamped + + + cram_tf + + cram_language + cram_executive + cram_designators + cram_prolog + cram_projection + cram_occasions_events + cram_utilities + cram_process_modules + + cram_common_failures + cram_mobile_pick_place_plans + cram_robot_interfaces + cram_object_knowledge + cram_manipulation_interfaces + + cram_physics_utils + cl_bullet + cram_bullet_reasoning + cram_bullet_reasoning_belief_state + cram_bullet_reasoning_utilities + cram_urdf_projection + + cram_location_costmap + cram_btr_visibility_costmap + cram_robot_pose_gaussian_costmap + cram_btr_spatial_relations_costmap + + cram_donbot_description + + + + + + + + + + + + + diff --git a/cram_demos/cram_donbot_retail_demo/resource/balea-bottle.stl b/cram_demos/cram_donbot_retail_demo/resource/balea-bottle.stl new file mode 100644 index 0000000000..36f3f3b51a Binary files /dev/null and b/cram_demos/cram_donbot_retail_demo/resource/balea-bottle.stl differ diff --git a/cram_demos/cram_donbot_retail_demo/resource/dish-washer-tabs.stl b/cram_demos/cram_donbot_retail_demo/resource/dish-washer-tabs.stl new file mode 100644 index 0000000000..615ec62e5c Binary files /dev/null and b/cram_demos/cram_donbot_retail_demo/resource/dish-washer-tabs.stl differ diff --git a/cram_demos/cram_donbot_retail_demo/src/costmaps.lisp b/cram_demos/cram_donbot_retail_demo/src/costmaps.lisp new file mode 100644 index 0000000000..e42af32342 --- /dev/null +++ b/cram_demos/cram_donbot_retail_demo/src/costmaps.lisp @@ -0,0 +1,68 @@ +;;; +;;; Copyright (c) 2017, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Intelligent Autonomous Systems Group/ +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software +;;; without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :cram-donbot-retail-demo) + +(defun make-restricted-area-cost-function () + (lambda (x y) + (if (> x 4.0) + 0.0 + (if (< x 0.0) + 0.0 + (if (> y 1.0) + 0.0 + (if (< y -1.0) + 0.0 + 1.0)))))) + +(defmethod location-costmap:costmap-generator-name->score ((name (eql 'restricted-area))) 5) + +(def-fact-group demo-costmap (location-costmap:desig-costmap) + (<- (location-costmap:desig-costmap ?designator ?costmap) + (or (rob-int:visibility-designator ?designator) + (rob-int:reachability-designator ?designator)) + ;; make sure that the location is not on the robot itself + ;; if it is, don't generate a costmap + (once (or (and (desig:desig-prop ?designator (:object ?some-object)) + (desig:current-designator ?some-object ?object) + (lisp-fun man-int:get-object-pose-in-map ?object ?to-reach-pose) + (lisp-pred identity ?to-reach-pose) + (-> (desig:desig-prop ?object (:location ?loc)) + (not (man-int:location-always-reachable ?loc)) + (true))) + (and (desig:desig-prop ?designator (:location ?some-location)) + (desig:current-designator ?some-location ?location) + ;; if the location is on the robot itself, + ;; don't use the costmap + (not (man-int:location-always-reachable ?location))))) + (location-costmap:costmap ?costmap) + (location-costmap:costmap-add-function + restricted-area + (make-restricted-area-cost-function) + ?costmap))) diff --git a/cram_demos/cram_donbot_retail_demo/src/demo.lisp b/cram_demos/cram_donbot_retail_demo/src/demo.lisp new file mode 100644 index 0000000000..cde119aa04 --- /dev/null +++ b/cram_demos/cram_donbot_retail_demo/src/demo.lisp @@ -0,0 +1,626 @@ +;;; +;;; Copyright (c) 2018, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Intelligent Autonomous Systems Group/ +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software +;;; without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :cram-donbot-retail-demo) + +(defun spawn-objects-on-small-shelf (&optional (spawn? t)) + (sb-ext:gc :full t) + (setf desig::*designators* (tg:make-weak-hash-table :weakness :key)) + (btr:clear-costmap-vis-object) + (btr-utils:kill-all-objects) + (btr:detach-all-objects (btr:get-robot-object)) + (btr:detach-all-objects (btr:get-environment-object)) + #+only-for-the-real-robot-so-commenting-out-for-now + (unless cram-projection:*projection-environment* + (giskard::call-giskard-environment-service + :remove-all) + (when (btr:get-environment-object) + (giskard::call-giskard-environment-service + :add-environment + :name (roslisp-utilities:rosify-underscores-lisp-name + (rob-int:get-environment-name)) + :pose (cl-transforms-stamped:pose->pose-stamped + cram-tf:*fixed-frame* 0.0 (btr:pose (btr:get-environment-object))) + :joint-state-topic "kitchen/joint_states"))) + + (when (and spawn? cram-projection:*projection-environment*) + (btr-utils:spawn-object :balea-bottle-1 :balea-bottle :pose + '((1.9 -1.42 1.05) (0 0 0.7 0.7)) + :color '(1 1 1)) + (btr:add-object btr:*current-bullet-world* :box-item + :denkmitgeschirrreinigernature-1 + '((1.75 -1.45 1.06) (0 0 0.7 0.7)) + :mass 0.2 + :color '(0 1 0 1.0) + :size '(0.057 0.018 0.074) + :item-type :dish-washer-tabs) + ;; (btr:simulate btr:*current-bullet-world* 50) + (btr-utils:move-robot '((1.0 0 0) (0 0 0 1))))) + +(defun demo () + (spawn-objects-on-small-shelf) + + (let* ((?environment-name + (rob-int:get-environment-name)) + (?search-location + (desig:a location + (on (desig:an object + (type shelf) + (urdf-name shelf-2-base) + (owl-name "shelf_system_verhuetung") + (part-of ?environment-name) + (level 4))) + (side left) + (range 0.2))) + (?object + (an object + (type dish-washer-tabs) + (location ?search-location))) + (?target-location-shelf + (desig:a location + (on (desig:an object + (type environment) + (name ?environment-name) + (part-of ?environment-name) + (urdf-name shelf-1-level-2-link))) + (for ?object) + (attachments (dish-washer-tabs-shelf-1-front + dish-washer-tabs-shelf-1-back)))) + (?robot-name (rob-int:get-robot-name)) + (?intermediate-locaiton-robot + (desig:a location + (on (desig:an object + (type robot) + (name ?robot-name) + (part-of ?environment-name) + ;; (owl-name "donbot_tray") + (urdf-name plate))) + (for ?object) + (attachments (donbot-tray-front donbot-tray-back))))) + + (exe:perform + (desig:an action + (type transporting) + (object ?object) + (target ?intermediate-locaiton-robot) + ;; (target ?target-location-shelf) + )) + + (exe:perform + (desig:an action + (type transporting) + (object ?object) + (target ?target-location-shelf))) + + ;; (setf ?object + ;; (desig:copy-designator + ;; (perform (a motion + ;; (type :world-state-detecting) + ;; (object (an object + ;; (name denkmitgeschirrreinigernature-1))))) + ;; :new-description + ;; `((:location ,(a location + ;; (on (an object + ;; (type robot) + ;; (name ?robot-name) + ;; (urdf-name plate) + ;; (owl-name "donbot_tray")))))))) + + ;; look at separators + ;; (exe:perform + ;; (desig:an action + ;; (type looking) + ;; (direction right-separators))) + ;; (cpl:sleep 5.0) +)) + + + + + + + + + + + + + + + + + + + +(defun demo-hardcoded (&optional (?item-type :dish-washer-tabs) + (park-drive-look? t)) + + (spawn-objects-on-small-shelf) + + (let ((?object + (an object + (type ?item-type) + (location (a location + (on (an object + (type shelf) + (urdf-name shelf-2-level-3-link) + (owl-name "shelf_system_verhuetung"))))))) + + (?target-pose-front + (cl-transforms-stamped:make-pose-stamped + cram-tf:*fixed-frame* + 0.0 + (cl-transforms:make-3d-vector 4.06 -0.64 1.05) + (cl-transforms:make-quaternion 0 0 1 0))) + + (?target-pose-back + (cl-transforms-stamped:make-pose-stamped + cram-tf:*fixed-frame* + 0.0 + (cl-transforms:make-3d-vector 4.06 -0.64 1.05) + (cl-transforms:make-quaternion 0 0 0 1)))) + + (when park-drive-look? + ;; park arm + (exe:perform + (desig:an action + (type parking-arms) + (arms (left)))) + + ;; drive to pick up + (let ((?pose (cl-transforms-stamped:make-pose-stamped + "map" 0.0 + (cl-transforms-stamped:make-3d-vector + 2.2660367329915365d0 + ;; -0.16621163686116536d0 + -0.26 + 0.0) + (cl-transforms:make-quaternion + 0.0d0 0.0d0 -0.020739689469337463d0 0.9997849464416504d0)))) + (exe:perform + (desig:an action + (type going) + (target (desig:a location (pose ?pose)))))) + + ;; look at the shelf + (exe:perform + (desig:an action + (type looking) + (direction right)))) + + ;; perceive + ;; TODO: make this using WITH-FAILURE-HANDLING and write about + ;; that in deliverable + (let (percept-believable + (?grasp :back)) + (loop until percept-believable + do (let* ((perceived-object + (exe:perform + (desig:an action + (type detecting) + (object ?object)))) + (perceived-object-pose + (btr:object-pose + (desig:desig-prop-value perceived-object :name))) + ;; (perceived-object-pose + ;; (man-int:get-object-pose-in-map perceived-object)) + (perceived-object-pose-z + (cl-transforms:z + (cl-transforms:origin perceived-object-pose))) + (perceived-object-orientation + (cl-transforms:orientation perceived-object-pose)) + (perceived-object-orientation-axis + (cl-transforms:quaternion->axis-angle + perceived-object-orientation)) + (perceived-object-orientation-angle + (* (nth-value + 1 + (cl-transforms:quaternion->axis-angle + perceived-object-orientation)) + (if (> (cl-transforms:z perceived-object-orientation-axis) + 0) + 1 + -1)))) + (if (> (cl-transforms:normalize-angle + perceived-object-orientation-angle) + 0) + (setf ?grasp :front) + (setf ?grasp :back)) + (setf percept-believable + (and (> perceived-object-pose-z 1.02) + (< perceived-object-pose-z 1.2) + (> (abs (cl-transforms:z + perceived-object-orientation-axis)) + (abs (cl-transforms:x + perceived-object-orientation-axis))) + (> (abs (cl-transforms:z + perceived-object-orientation-axis)) + (abs (cl-transforms:y + perceived-object-orientation-axis))) + (> (abs perceived-object-orientation-angle) 1.0) + (< (abs perceived-object-orientation-angle) 2.0))))) + + (let ((picking-up-action + (desig:an action + (type picking-up) + (grasp ?grasp) + (object ?object)))) + ;; (proj-reasoning:check-picking-up-collisions picking-up-action) + ;; picking up + (exe:perform picking-up-action)) + + ;; placing on the back + (let* ((?robot-name (rob-int:get-robot-name)) + (?robot-link-name "plate") + (?pose-in-map (cram-tf:frame-to-pose-in-fixed-frame ?robot-link-name)) + (?transform-in-map (cram-tf:pose-stamped->transform-stamped + ?pose-in-map ?robot-link-name)) + (?pose-in-base (cram-tf:ensure-pose-in-frame + ?pose-in-map cram-tf:*robot-base-frame* + :use-zero-time t)) + (?transform-in-base (cram-tf:pose-stamped->transform-stamped + ?pose-in-base ?robot-link-name)) + (?attachment (ecase ?grasp + (:front :donbot-tray-front) + (:back :donbot-tray-back)))) + (exe:perform + (an action + (type placing) + (object ?object) + (target (a location + (on (an object + (type robot) + (name ?robot-name) + (urdf-name plate) + (owl-name "donbot_tray") + (pose ((pose ?pose-in-base) + (transform ?transform-in-base) + (pose-in-map ?pose-in-map) + (transform-in-map ?transform-in-map))))) + (for ?object) + (attachment ?attachment))))) + + (setf ?object + (desig:copy-designator + (perform (a motion + (type :world-state-detecting) + (object (an object + (name denkmitgeschirrreinigernature-1))))) + :new-description + `((:location ,(a location + (on (an object + (type robot) + (name ?robot-name) + (urdf-name plate) + (owl-name "donbot_tray"))))))))) + + ;; park arm + (exe:perform + (desig:an action + (type parking-arms) + (arms (left)))) + + ;; drive to place + (let ((?pose (cl-transforms-stamped:make-pose-stamped + "map" 0.0 + (cl-transforms-stamped:make-3d-vector + ;; 2.7235169607604437d0 + 3.4 + -0.13619131858235267d0 + 0.0d0) + (cl-transforms:make-quaternion + 0.0d0 + 0.0d0 + 0.6886594891548157d0 + 0.7250849008560181d0)))) + (exe:perform + (desig:an action + (type going) + (target (desig:a location (pose ?pose)))))) + + + ;; look at separators + ;; (exe:perform + ;; (desig:an action + ;; (type looking) + ;; (direction right-separators))) + ;; (cpl:sleep 5.0) + + ;; look at tray + ;; (exe:perform + ;; (desig:an action + ;; (type looking) + ;; (direction down))) + + ;; ;; reperceive object + ;; (let* ((?robot-name + ;; (rob-int:get-robot-name))) + ;; (setf ?object + ;; (perform + ;; (an action + ;; (type detecting) + ;; (object (an object + ;; (type ?item-type) + ;; (location (a location + ;; (on (an object + ;; (type robot) + ;; (name ?robot-name) + ;; (urdf-name plate) + ;; (owl-name "donbot_tray"))))))))))) + + + (exe:perform + (an action + (type picking-up) + (grasp ?grasp) + (object ?object))) + + ;; place on the big shelf + (let ((?target-pose + (ecase ?grasp + (:front ?target-pose-front) + (:back ?target-pose-back)))) + (exe:perform + (an action + (type placing) + (object ?object) + (target (a location + (pose ?target-pose))))))))) + + + + +(defun pick-object-from-small-shelf (&optional (?item-type :dish-washer-tabs) + (park-drive-look? t)) + (spawn-objects-on-small-shelf) + + (let ((?object + (an object + (type ?item-type) + (location (a location + (on (an object + (type shelf) + (urdf-name shelf-2-level-3-link) + (owl-name "shelf_system_verhuetung")))))))) + + (when park-drive-look? + ;; park arm + (exe:perform + (desig:an action + (type parking-arms) + (arms (left)))) + + ;; drive to pick up + (let ((?pose (cl-transforms-stamped:make-pose-stamped + "map" 0.0 + (cl-transforms-stamped:make-3d-vector + 2.2660367329915365d0 -0.16621163686116536d0 0.0) + (cl-transforms:make-quaternion + 0.0d0 0.0d0 -0.020739689469337463d0 0.9997849464416504d0)))) + (exe:perform + (desig:an action + (type going) + (target (desig:a location (pose ?pose)))))) + + ;; look at the shelf + (exe:perform + (desig:an action + (type looking) + (direction right)))) + + ;; perceive + ;; TODO: make this using WITH-FAILURE-HANDLING and write about + ;; that in deliverable + (let (percept-believable + (?grasp :back)) + (loop until percept-believable + do (let* ((perceived-object + (exe:perform + (an action + (type detecting) + (object ?object)))) + (perceived-object-pose + (btr:object-pose + (desig:desig-prop-value perceived-object :name))) + ;; (perceived-object-pose + ;; (man-int:get-object-pose-in-map perceived-object)) + (perceived-object-pose-z + (cl-transforms:z + (cl-transforms:origin perceived-object-pose))) + (perceived-object-orientation + (cl-transforms:orientation perceived-object-pose)) + (perceived-object-orientation-axis + (cl-transforms:quaternion->axis-angle + perceived-object-orientation)) + (perceived-object-orientation-angle + (* (nth-value + 1 + (cl-transforms:quaternion->axis-angle + perceived-object-orientation)) + (if (> (cl-transforms:z perceived-object-orientation-axis) + 0) + (prog1 + 1 + (setf ?grasp :front)) + (prog1 + -1 + (setf ?grasp :back)))))) + (setf percept-believable + (and (> perceived-object-pose-z 1.02) + (< perceived-object-pose-z 1.2) + (> (abs (cl-transforms:z + perceived-object-orientation-axis)) + (abs (cl-transforms:x + perceived-object-orientation-axis))) + (> (abs (cl-transforms:z + perceived-object-orientation-axis)) + (abs (cl-transforms:y + perceived-object-orientation-axis))) + (> (abs perceived-object-orientation-angle) 1.0) + (< (abs perceived-object-orientation-angle) 2.0))))) + + (let ((picking-up-action + (an action + (type picking-up) + (grasp ?grasp) + (object ?object)))) + ;; (proj-reasoning:check-picking-up-collisions picking-up-action) + ;; picking up + (exe:perform picking-up-action))) + + ;; placing on the back + (let* ((?robot-name (rob-int:get-robot-name)) + (?robot-link-name "plate") + (?pose-in-map (cram-tf:frame-to-pose-in-fixed-frame ?robot-link-name)) + (?transform-in-map (cram-tf:pose-stamped->transform-stamped + ?pose-in-map ?robot-link-name)) + (?pose-in-base (cram-tf:ensure-pose-in-frame + ?pose-in-map cram-tf:*robot-base-frame* + :use-zero-time t)) + (?transform-in-base (cram-tf:pose-stamped->transform-stamped + ?pose-in-base ?robot-link-name))) + (exe:perform + (an action + (type placing) + (object ?object) + (target (a location + (on (an object + (type robot) + (name ?robot-name) + (urdf-name plate) + (owl-name "donbot_tray") + (pose ((pose ?pose-in-base) + (transform ?transform-in-base) + (pose-in-map ?pose-in-map) + (transform-in-map ?transform-in-map))))) + (for ?object) + (attachment donbot-tray-left)))))))) + + +(defun place-object-at-big-shelf (&optional (?item-type :dish-washer-tabs) + (park-drive-look? t) + (?target-pose + (cl-transforms-stamped:pose->pose-stamped + cram-tf:*fixed-frame* 0.0 + (cram-tf:list->pose + '((4.048458 -0.64891 1.07) + (-0.7071067811865475d0 + 0.0d0 + 0.7071067811865475d0 + 0.0d0)))))) + ;; (spawn-objects-on-small-shelf nil) + (when park-drive-look? + ;; park arm + (exe:perform + (desig:an action + (type parking-arms) + (arms (left)))) + + ;; drive to place + (let ((?pose (cl-transforms-stamped:make-pose-stamped + "map" 0.0 + (cl-transforms-stamped:make-3d-vector + 2.7235169607604437d0 + -0.13619131858235267d0 + 0.0d0) + (cl-transforms:make-quaternion + 0.0d0 + 0.0d0 + 0.6886594891548157d0 + 0.7250849008560181d0)))) + (exe:perform + (desig:an action + (type going) + (target (desig:a location (pose ?pose)))))) + + ;; look at separators + (exe:perform + (desig:an action + (type looking) + (direction right-separators))) + (cpl:sleep 5.0) + + ;; look at tray + (exe:perform + (desig:an action + (type looking) + (direction down)))) + + ;; pick up from the tray + (let* ((?robot-name + (rob-int:get-robot-name)) + (?obj + (perform + (an action + (type detecting) + (object (an object + (type ?item-type) + (location (a location + (on (an object + (type robot) + (name ?robot-name) + (urdf-name plate) + (owl-name "donbot_tray"))))))))))) + + (exe:perform + (an action + (type picking-up) + (grasp top) + (object ?obj))) + + ;; place on the big shelf + (exe:perform + (an action + (type placing) + (object ?obj) + (target (a location + (pose ?target-pose))))))) + + +#+stuff-to-test-real-robot-interfaces +(defun stuff-that-works () + (cram-process-modules:with-process-modules-running + (giskard:giskard-pm) + (cpl-impl::named-top-level (:name :top-level) + (exe:perform + (let ((?pose (cl-transforms-stamped:make-pose-stamped + "base_footprint" 0.0 + (cl-transforms:make-3d-vector + -0.27012088894844055d0 + 0.5643729567527771d0 + 1.25943687558174133d0) + (cl-transforms:make-quaternion + -0.4310053586959839d0 + 0.24723316729068756d0 + 0.752766489982605d0 + 0.4318017065525055d0 )))) + (desig:a motion + (type moving-tcp) + (left-pose ?pose) + (collision-mode :allow-all))))))) diff --git a/cram_pr2/cram_urdf_bringup/src/package.lisp b/cram_demos/cram_donbot_retail_demo/src/package.lisp similarity index 95% rename from cram_pr2/cram_urdf_bringup/src/package.lisp rename to cram_demos/cram_donbot_retail_demo/src/package.lisp index d571944b81..3476e83093 100644 --- a/cram_pr2/cram_urdf_bringup/src/package.lisp +++ b/cram_demos/cram_donbot_retail_demo/src/package.lisp @@ -11,8 +11,8 @@ ;;; notice, this list of conditions and the following disclaimer in the ;;; documentation and/or other materials provided with the distribution. ;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software ;;; without specific prior written permission. ;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" @@ -29,10 +29,13 @@ (in-package :cl-user) -(defpackage cram-robots-bringup +(defpackage cram-donbot-retail-demo (:nicknames #:demo) (:use #:common-lisp #:cram-prolog #:desig #:exe) (:export ;; setup + ;; #:bla + ;; demo )) + diff --git a/cram_demos/cram_donbot_retail_demo/src/setup.lisp b/cram_demos/cram_donbot_retail_demo/src/setup.lisp new file mode 100644 index 0000000000..cfa40301d6 --- /dev/null +++ b/cram_demos/cram_donbot_retail_demo/src/setup.lisp @@ -0,0 +1,47 @@ +;;; +;;; Copyright (c) 2019, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Intelligent Autonomous Systems Group/ +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software +;;; without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :cram-donbot-retail-demo) + +;; roslaunch cram_donbot_retail_demo sandbox.launch + +(defun init-projection () + ;; (setf cram-tf:*transformer* (make-instance 'cl-tf2:buffer-client)) + + (btr-belief:setup-world-database) + + (setf cram-tf:*tf-default-timeout* 2.0) + + (setf prolog:*break-on-lisp-errors* t) + + (cram-bullet-reasoning:clear-costmap-vis-object) + + (btr:add-objects-to-mesh-list "cram_donbot_retail_demo")) + +(roslisp-utilities:register-ros-init-function init-projection) diff --git a/cram_pr2/cram_pr2_projection/CMakeLists.txt b/cram_demos/cram_hsrb_pick_demo/CMakeLists.txt similarity index 74% rename from cram_pr2/cram_pr2_projection/CMakeLists.txt rename to cram_demos/cram_hsrb_pick_demo/CMakeLists.txt index a183cb39fa..4b5ba0e615 100644 --- a/cram_pr2/cram_pr2_projection/CMakeLists.txt +++ b/cram_demos/cram_hsrb_pick_demo/CMakeLists.txt @@ -1,4 +1,4 @@ cmake_minimum_required(VERSION 2.8.3) -project(cram_pr2_projection) +project(cram_hsrb_pick_demo) find_package(catkin REQUIRED) catkin_package() diff --git a/cram_pr2/cram_urdf_bringup/cram-urdf-bringup.asd b/cram_demos/cram_hsrb_pick_demo/cram-hsrb-pick-demo.asd similarity index 87% rename from cram_pr2/cram_urdf_bringup/cram-urdf-bringup.asd rename to cram_demos/cram_hsrb_pick_demo/cram-hsrb-pick-demo.asd index 2dcdd07f38..ed03f00e95 100644 --- a/cram_pr2/cram_urdf_bringup/cram-urdf-bringup.asd +++ b/cram_demos/cram_hsrb_pick_demo/cram-hsrb-pick-demo.asd @@ -28,8 +28,8 @@ ;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE ;;; POSSIBILITY OF SUCH DAMAGE. -(defsystem cram-urdf-bringup - :author "gaya" +(defsystem cram-hsrb-pick-demo + :author "Vanessa Hassouna" :license "BSD" :depends-on (roslisp-utilities ; for ros-init-function @@ -50,6 +50,7 @@ cram-common-failures cram-mobile-pick-place-plans + cram-object-knowledge ;; cram-robosherlock @@ -64,13 +65,16 @@ cram-robot-pose-gaussian-costmap cram-occupancy-grid-costmap cram-location-costmap - - cram-urdf-projection - ) + cram-math + cram-urdf-projection + cram-hsrb-description) :components ((:module "src" :components ((:file "package") (:file "setup-urdf" :depends-on ("package")) - (:file "setup" :depends-on ("package")))))) + (:file "setup" :depends-on ("package" "setup-urdf")) + (:file "object-knowledge" :depends-on ("package")) + (:file "hsrb-pick-up" :depends-on ("package" "object-knowledge")) + (:file "demo" :depends-on ("package" "hsrb-pick-up")))))) diff --git a/cram_demos/cram_hsrb_pick_demo/launch/sandbox.launch b/cram_demos/cram_hsrb_pick_demo/launch/sandbox.launch new file mode 100644 index 0000000000..423d166fea --- /dev/null +++ b/cram_demos/cram_hsrb_pick_demo/launch/sandbox.launch @@ -0,0 +1,60 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/cram_pr2/cram_urdf_bringup/package.xml b/cram_demos/cram_hsrb_pick_demo/package.xml similarity index 77% rename from cram_pr2/cram_urdf_bringup/package.xml rename to cram_demos/cram_hsrb_pick_demo/package.xml index 7f9f02ac64..ae60dbdce5 100644 --- a/cram_pr2/cram_urdf_bringup/package.xml +++ b/cram_demos/cram_hsrb_pick_demo/package.xml @@ -1,14 +1,11 @@ - cram_urdf_bringup + cram_hsrb_pick_demo 0.7.0 - Demo code for assembly objects with hsrb - Gayane Kazhoyan - Gayane Kazhoyan + Demo code for picking objects with hsrb + Vanessa Hassouna + Gayane Kazhoyan BSD - http://cram-system.org - http://github.com/cram2/cram - catkin roslisp_utilities @@ -28,6 +25,7 @@ cram_utilities cram_common_failures + cram_object_knowledge cram_mobile_pick_place_plans @@ -44,4 +42,5 @@ cram_location_costmap cram_urdf_projection + cram_hsrb_description diff --git a/cram_demos/cram_hsrb_pick_demo/src/demo.lisp b/cram_demos/cram_hsrb_pick_demo/src/demo.lisp new file mode 100644 index 0000000000..7687ffc53a --- /dev/null +++ b/cram_demos/cram_hsrb_pick_demo/src/demo.lisp @@ -0,0 +1,50 @@ +;;; +;;; Copyright (c) 2019, Gayane Kazhoyan +;; Vanessa Hassouna +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Intelligent Autonomous Systems Group/ +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software +;;; without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :demo) + +(defun spawn-pickup-cylinder-table () + "Spawn primitive cylinder as :pringles item and try to pick up from table." + (urdf-proj:with-simulated-robot + (btr:add-object btr:*current-bullet-world* :cylinder-item 'cylinder-1 + '((-0.7 -0.7 0.85) (0 0 1 1)) + :mass 0.2 + :size (cl-transforms:make-3d-vector 0.03 0.03 0.08) + :item-type :pringles) + (pick-up-object 'cylinder-1 :pringles))) + +(defun spawn-pickup-cylinder-air () + "Spawn primitive cylinder as :pringles item and try to pick up." + (urdf-proj:with-simulated-robot + (btr:add-object btr:*current-bullet-world* :cylinder-item 'cylinder-1 + '((0.7 0.0777 0.65) (0 0 1 1)) + :mass 0.2 :size (cl-transforms:make-3d-vector 0.03 0.03 0.08) + :item-type :pringles) + (pick-up-object 'cylinder-1 :pringles))) diff --git a/cram_demos/cram_hsrb_pick_demo/src/hsrb-pick-up.lisp b/cram_demos/cram_hsrb_pick_demo/src/hsrb-pick-up.lisp new file mode 100644 index 0000000000..d3d43f1076 --- /dev/null +++ b/cram_demos/cram_hsrb_pick_demo/src/hsrb-pick-up.lisp @@ -0,0 +1,171 @@ +;;; +;;; Copyright (c) 2020, Vanessa Hassouna +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Intelligent Autonomous Systems Group/ +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software +;;; without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :demo) + +(defun pick-up-object (object-name object-type) + "move hsr and grasp the object" + (mirror-object-pose object-name) + (grasp-object object-name object-type)) + +(defun mirror-object-pose (object-name) + "moves the robot as the object while ignoring the enviroment" + (let* ((?object-pose (btr:object-pose object-name))) + (roslisp:with-fields (x y) (cl-transforms:origin ?object-pose) + ;; TODO This does not work on the real robot + ;; to make it work multiply the transforms instead of teleporting the robot + (btr-utils:move-robot + (cl-transforms:make-pose + (cl-transforms:make-3d-vector x y 0) + (cl-transforms:orientation ?object-pose))))) + ;; update that the robot-state changed otherwise the transformer dosen't update + (coe:on-event (make-instance 'cpoe:robot-state-changed))) + +(defun grasp-object (object-name object-type) + "places the robot in front-/left-/right-/back-side of the object and tries +to grasp the object, if that fails the next position in list will be tried" + (let* ((nav-pose + ;; TODO shuffle the list? + ;; applying append function to the successive subsets of the list + (reduce + #'append + ;; goes through each element in the sequence, and returns a new list + (mapcar + (lambda (list-poses) + (let ((tmp-list nil)) + (loop for a from 0.0 to 0.4 by 0.01 + do + ;; push element to list + (push + (roslisp:with-fields (x y) + (cl-transforms:origin (car list-poses)) + ;; check if the offset needs to be summed or subtracted + (if (or (eq (car (cdr list-poses)) :front) + (eq (car (cdr list-poses)) :back)) + (setf x (+ x + (if (> x 0) + a + (- a)))) + (setf y (+ y + (if (> y 0) + a + (- a))))) + ;; create new list with a stamped-pose and x/y w + ;; with edited offset and the grasping-side + (list + (cl-transforms-stamped:transform-pose-stamped + cram-tf:*transformer* + :pose + (cl-transforms-stamped:make-pose-stamped + "base_footprint" 0 + (cl-transforms:make-3d-vector x y 0) + (cl-transforms:orientation (car list-poses))) + :target-frame "map") + + ;; get grasping-side + (cdr list-poses))) + ;; push to my-list + tmp-list)) + ;; loop done and reverse tmp-list such that the lower value is first + (reverse tmp-list))) + ;;the basic list that goes through the mapcar + (list + (list (cl-transforms:make-pose + (cl-transforms:make-3d-vector 0.40 0.07769999504089356d0 0) + (cl-transforms:euler->quaternion :az pi)) + :front) + (list (cl-transforms:make-pose + (cl-transforms:make-3d-vector -0.40 -0.07769999504089356d0 0) + (cl-transforms:make-identity-rotation)) + :back) + (list (cl-transforms:make-pose + (cl-transforms:make-3d-vector -0.07769999504089356d0 0.40 0) + (cl-transforms:euler->quaternion :az (- (/ pi 2)))) + :left-side) + (list (cl-transforms:make-pose + (cl-transforms:make-3d-vector +0.07769999504089356d0 -0.4 0) + (cl-transforms:euler->quaternion :az (/ pi 2))) + :right-side))))) + ;; sets object-type to prolog variable + (?object-type object-type)) + + (cpl:with-retry-counters ((going-retry 500)) + ;; TODO if it takes to long to go through the whole list implement a stop + (cpl:with-failure-handling + (((or common-fail:low-level-failure + cl::simple-error + cl::simple-type-error) (e) + (roslisp:ros-warn (grasp-object fail) + "~%Failed with given msgs ~a~%" e) + ;; get rid of head of nav-pose by setting only the rest + (unless (eq nil (cdr nav-pose)) + (setf nav-pose (cdr nav-pose)) + + (cpl:do-retry going-retry + (roslisp:ros-warn (grasp-object fail) + "~%Failed with given msgs ~a~%" e) + (cpl:retry))) + (roslisp:ros-warn (grasp-object fail) + "~%No more retries~%"))) + ;; park-robot (percieve pose) + (btr-utils:park-robot) + (let* ((?nav-pose + (car (car nav-pose))) + (?object-pose + (cl-transforms-stamped:pose->pose-stamped + "map" 0 (btr:object-pose object-name)))) + ;; perform a action type going to first pose + (exe:perform + (desig:an action + (type going) + (target (desig:a location (pose ?nav-pose))))) + + ;;perform a action type looking towards the object + (exe:perform + (desig:an action + (type looking) + (target (desig:a location (pose ?object-pose)))))) + + (let* ((?object-desig + (exe:perform (desig:a motion + (type detecting) + (object (desig:an object + (type ?object-type)))))) + (?grasp (caadar nav-pose))) + + ;; perform a action type picking-up with given grasp and object + (exe:perform (desig:an action + (type picking-up) + (arm :left) + (grasp ?grasp) + (object ?object-desig)))))))) + + + + diff --git a/cram_demos/cram_hsrb_pick_demo/src/object-knowledge.lisp b/cram_demos/cram_hsrb_pick_demo/src/object-knowledge.lisp new file mode 100644 index 0000000000..553f7c34c0 --- /dev/null +++ b/cram_demos/cram_hsrb_pick_demo/src/object-knowledge.lisp @@ -0,0 +1,83 @@ +;;; +;;; Copyright (c) 2019, Gayane Kazhoyan +;; Vanessa Hassouna +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Intelligent Autonomous Systems Group/ +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software +;;; without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :demo) + +(defparameter *lift-z-offset* 0.05 "in meters") +(defparameter *lift-offset* `(0.0 0.0 ,*lift-z-offset*)) + +(defmethod man-int:get-action-gripping-effort :heuristics 20 + ((object-type (eql :pringles))) 50) + +(defmethod man-int:get-action-gripper-opening :heuristics 20 + ((object-type (eql :pringles))) 0.10) + + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; pringles ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +;; pregrasp offset for pringles size '((0.7 0.0777 0.65)) +(defparameter *pringles-pregrasp-xy-offset* 0.03) +(defparameter *pringles-grasp-xy-offset* 0.01 "in meters") +(defparameter *pringles-grasp-z-offset* 0.005 "in meters") + +;; SIDE grasp +(man-int:def-object-type-to-gripper-transforms :pringles :left :left-side + :grasp-translation `(0.0d0 ,(- *pringles-grasp-xy-offset*) ,*pringles-grasp-z-offset*) + :grasp-rot-matrix man-int:*y-across-z-grasp-rotation* + :pregrasp-offsets `(0.0 ,*pringles-pregrasp-xy-offset* 0.01) + :2nd-pregrasp-offsets `(0.0 ,*pringles-pregrasp-xy-offset* 0.01) + :lift-translation `(0.0 0.0 ,*lift-z-offset*) + :2nd-lift-translation `(0.0 0.0 ,*lift-z-offset*)) + +(man-int:def-object-type-to-gripper-transforms :pringles :left :right-side + :grasp-translation `(0.0d0 ,*pringles-grasp-xy-offset* ,*pringles-grasp-z-offset*) + :grasp-rot-matrix man-int:*-y-across-z-grasp-rotation* + :pregrasp-offsets `(0.0 ,(- *pringles-pregrasp-xy-offset*) 0.01) + :2nd-pregrasp-offsets `(0.0 ,(- *pringles-pregrasp-xy-offset*) 0.01) + :lift-translation `(0.0 0.0 ,*lift-z-offset*) + :2nd-lift-translation `(0.0 0.0 ,*lift-z-offset*)) + +;; BACK grasp +(man-int:def-object-type-to-gripper-transforms :pringles :left :back + :grasp-translation `(,*pringles-grasp-xy-offset* 0.0d0 ,*pringles-grasp-z-offset*) + :grasp-rot-matrix man-int:*-x-across-z-grasp-rotation* + :pregrasp-offsets `(,(- *pringles-pregrasp-xy-offset*) 0.0 0.01) + :2nd-pregrasp-offsets `(,(- *pringles-pregrasp-xy-offset*) 0.0 0.01) + :lift-translation `(0.0 0.0 ,*lift-z-offset*) + :2nd-lift-translation `(0.0 0.0 ,*lift-z-offset*)) + +;; FRONT grasp +(man-int:def-object-type-to-gripper-transforms :pringles :left :front + :grasp-translation `(,*pringles-grasp-xy-offset* 0.0d0 ,*pringles-grasp-z-offset*) + :grasp-rot-matrix man-int:*x-across-z-grasp-rotation* + :pregrasp-offsets `(,(+ *pringles-pregrasp-xy-offset*) 0.0 0.01) + :2nd-pregrasp-offsets `(,(+ *pringles-pregrasp-xy-offset*) 0.0 0.01) + :lift-translation `(0.0 0.0 ,*lift-z-offset*) + :2nd-lift-translation `(0.0 0.0 ,*lift-z-offset*)) diff --git a/cram_3d_world/cl_bullet/src/lisp/examples/cl-bullet-examples.asd b/cram_demos/cram_hsrb_pick_demo/src/package.lisp similarity index 82% rename from cram_3d_world/cl_bullet/src/lisp/examples/cl-bullet-examples.asd rename to cram_demos/cram_hsrb_pick_demo/src/package.lisp index 1b4b925601..259a59ae4e 100644 --- a/cram_3d_world/cl_bullet/src/lisp/examples/cl-bullet-examples.asd +++ b/cram_demos/cram_hsrb_pick_demo/src/package.lisp @@ -1,20 +1,21 @@ ;;; -;;; Copyright (c) 2010, Lorenz Moesenlechner +;;; Copyright (c) 2019, Gayane Kazhoyan +;; Vanessa Hassouna ;;; All rights reserved. -;;; +;;; ;;; Redistribution and use in source and binary forms, with or without ;;; modification, are permitted provided that the following conditions are met: -;;; +;;; ;;; * Redistributions of source code must retain the above copyright ;;; notice, this list of conditions and the following disclaimer. ;;; * Redistributions in binary form must reproduce the above copyright ;;; notice, this list of conditions and the following disclaimer in the ;;; documentation and/or other materials provided with the distribution. ;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software ;;; without specific prior written permission. -;;; +;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" ;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE ;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE @@ -26,13 +27,10 @@ ;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE ;;; POSSIBILITY OF SUCH DAMAGE. -;;; -(defsystem cl-bullet-examples - :author "Lorenz Moesenlechner " - :license "BSD" - - :depends-on (cl-bullet cl-transforms) - :components - ((:file "package") - (:file "hello-world" :depends-on ("package")))) +(in-package :cl-user) + +(defpackage cram-hsrb-pick-demo + (:nicknames #:demo) + (:use #:common-lisp #:cram-prolog #:cram-designators #:cram-executive) + (:export)) diff --git a/cram_demos/cram_hsrb_pick_demo/src/setup-urdf.lisp b/cram_demos/cram_hsrb_pick_demo/src/setup-urdf.lisp new file mode 100644 index 0000000000..32b02f422b --- /dev/null +++ b/cram_demos/cram_hsrb_pick_demo/src/setup-urdf.lisp @@ -0,0 +1,78 @@ +;;; +;;; Copyright (c) 2019, Vanessa Hassouna +;;; Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Intelligent Autonomous Systems Group/ +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software +;;; without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :demo) + +(defparameter *collision-box* + "> + + + + + + + " + "The collision-box for base_footprint, since the URDF does not provide it.") + +(defparameter *tool-frame* + " + + + + + " + "The tool-frame for the HSRB, since the URDF does not provide one.") + +(defun get-urdf-hsrb (robot-description-parameter-name) + "Returns a correctly parsed HSRB URDF. +The URDF itself has some bugs and missing parts, so this function adds those." + (let* ((urdf-string + (substitute #\SPACE #\` + (roslisp:get-param robot-description-parameter-name))) + (urdf-object + (cl-urdf:parse-urdf + (concatenate 'string + ;; plus 15 because of base_footprint" + (subseq urdf-string + 0 + (+ 15 (search "base_footprint" urdf-string))) + *collision-box* + ;; plus 17 because of base_footprint"/> + (subseq + urdf-string + (+ 17 (search "base_footprint" urdf-string)) + (search " +;; Vanessa Hassouna +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Intelligent Autonomous Systems Group/ +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software +;;; without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :demo) + +(defun init-projection () + (btr-belief:setup-world-database) + + (setf cram-tf:*tf-default-timeout* 2.0) + (setf cram-tf:*tf-broadcasting-enabled* t) + (setf cram-tf:*transformer* (make-instance 'cl-tf2:buffer-client)) + + (setf prolog:*break-on-lisp-errors* t) + + (btr:clear-costmap-vis-object) + + (btr:add-objects-to-mesh-list "cram_hsrb_pick_demo")) + + +(roslisp-utilities:register-ros-init-function init-projection) + + + diff --git a/cram_pr2/cram_pr2_cloud/CMakeLists.txt b/cram_demos/cram_integration_tests/CMakeLists.txt similarity index 72% rename from cram_pr2/cram_pr2_cloud/CMakeLists.txt rename to cram_demos/cram_integration_tests/CMakeLists.txt index 88df96d75e..82f40210f7 100644 --- a/cram_pr2/cram_pr2_cloud/CMakeLists.txt +++ b/cram_demos/cram_integration_tests/CMakeLists.txt @@ -1,5 +1,4 @@ cmake_minimum_required(VERSION 2.8.3) -project(cram_pr2_cloud) +project(cram_integration_tests) find_package(catkin REQUIRED) catkin_package() - diff --git a/cram_common/cram_robot_interfaces/src/utilities.lisp b/cram_demos/cram_integration_tests/cram-integration-tests-boxy.asd similarity index 79% rename from cram_common/cram_robot_interfaces/src/utilities.lisp rename to cram_demos/cram_integration_tests/cram-integration-tests-boxy.asd index 7bd669355e..bad873a371 100644 --- a/cram_common/cram_robot_interfaces/src/utilities.lisp +++ b/cram_demos/cram_integration_tests/cram-integration-tests-boxy.asd @@ -1,5 +1,4 @@ -;;; -;;; Copyright (c) 2016, Gayane Kazhoyan +;;; Copyright (c) 2020, Christopher Pollok ;;; All rights reserved. ;;; ;;; Redistribution and use in source and binary forms, with or without @@ -27,12 +26,15 @@ ;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE ;;; POSSIBILITY OF SUCH DAMAGE. -(in-package :cram-robot-interfaces) +(defsystem cram-integration-tests-boxy + :author "Christopher Pollok" + :license "BSD" + + :depends-on (cram-integration-tests + cram-boxy-description) -(defun symbol-to-prolog-rule (the-symbol &rest parameters) - (let ((interned-symbol (find-symbol (string-upcase the-symbol)))) - (if interned-symbol - (cram-utilities:var-value - '?result - (car (prolog `(,interned-symbol ,@parameters ?result)))) - the-symbol))) + :components + ((:module "tests" + :components ((:file "package") + (:module "boxy" :depends-on ("package") + :components ((:file "setup"))))))) diff --git a/cram_demos/cram_integration_tests/cram-integration-tests-pr2.asd b/cram_demos/cram_integration_tests/cram-integration-tests-pr2.asd new file mode 100644 index 0000000000..d61c896dc3 --- /dev/null +++ b/cram_demos/cram_integration_tests/cram-integration-tests-pr2.asd @@ -0,0 +1,41 @@ +;;; Copyright (c) 2020, Christopher Pollok +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(defsystem cram-integration-tests-pr2 + :author "Christopher Pollok" + :license "BSD" + + :depends-on (cram-integration-tests + cram-pr2-description) + + :components + ((:module "tests" + :components ((:file "package") + (:module "pr2" :depends-on ("package") + :components ((:file "setup") + (:file "goals-tests"))))))) diff --git a/cram_demos/cram_integration_tests/cram-integration-tests.asd b/cram_demos/cram_integration_tests/cram-integration-tests.asd new file mode 100644 index 0000000000..b2609e9438 --- /dev/null +++ b/cram_demos/cram_integration_tests/cram-integration-tests.asd @@ -0,0 +1,73 @@ +;;; Copyright (c) 2020, Christopher Pollok +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(defsystem cram-integration-tests + :author "Christopher Pollok" + :license "BSD" + + :depends-on (roslisp-utilities ; for ros-init-function + + cl-transforms + cl-transforms-stamped + cl-tf + cram-tf + + cram-language + cram-executive + cram-designators + cram-prolog + cram-projection + cram-occasions-events + cram-utilities ; for EQUALIZE-LISTS-OF-LISTS-LENGTHS + + cram-common-failures + cram-mobile-pick-place-plans + cram-object-knowledge + + cram-physics-utils ; for reading "package://" paths + cl-bullet ; for handling BOUNDING-BOX datastructures + cram-bullet-reasoning + cram-bullet-reasoning-belief-state + cram-bullet-reasoning-utilities + + cram-location-costmap + cram-btr-visibility-costmap + cram-btr-spatial-relations-costmap + cram-robot-pose-gaussian-costmap + cram-occupancy-grid-costmap + + cram-urdf-projection ; for with-simulated-robot + cram-fetch-deliver-plans + cram-urdf-environment-manipulation + + lisp-unit) + + :components + ((:module "tests" + :components + ((:file "package"))))) diff --git a/cram_pr2/cram_pr2_pick_place_demo/launch/sandbox.launch b/cram_demos/cram_integration_tests/launch/pr2.launch similarity index 100% rename from cram_pr2/cram_pr2_pick_place_demo/launch/sandbox.launch rename to cram_demos/cram_integration_tests/launch/pr2.launch diff --git a/cram_demos/cram_integration_tests/package.xml b/cram_demos/cram_integration_tests/package.xml new file mode 100644 index 0000000000..9fe6d1d3ce --- /dev/null +++ b/cram_demos/cram_integration_tests/package.xml @@ -0,0 +1,61 @@ + + cram_integration_tests + 0.8.0 + Integration tests using projection. + Christopher Pollok + Gayane Kazhoyan + BSD + + http://cram-system.org + http://github.com/cram2/cram + + catkin + + roslisp_utilities + + cl_transforms + cl_transforms_stamped + cl_tf + cram_tf + + cram_language + cram_executive + cram_designators + cram_prolog + cram_projection + cram_occasions_events + cram_utilities + + cram_common_failures + cram_mobile_pick_place_plans + cram_object_knowledge + + cram_physics_utils + cl_bullet + cram_bullet_reasoning + cram_bullet_reasoning_belief_state + cram_bullet_reasoning_utilities + + cram_location_costmap + cram_btr_visibility_costmap + cram_btr_spatial_relations_costmap + cram_robot_pose_gaussian_costmap + cram_occupancy_grid_costmap + + cram_urdf_projection + cram_fetch_deliver_plans + cram_urdf_environment_manipulation + + cram_pr2_description + cram_boxy_description + + lisp_unit + + + iai_maps + iai_kitchen + robot_state_publisher + pr2_description + pr2_arm_kinematics + map_server + diff --git a/cram_demos/cram_integration_tests/tests/boxy/setup.lisp b/cram_demos/cram_integration_tests/tests/boxy/setup.lisp new file mode 100644 index 0000000000..0b04257b5b --- /dev/null +++ b/cram_demos/cram_integration_tests/tests/boxy/setup.lisp @@ -0,0 +1,32 @@ +;;; +;;; Copyright (c) 2017, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Intelligent Autonomous Systems Group/ +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software +;;; without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :cram-integration-tests) + + diff --git a/cram_demos/cram_integration_tests/tests/package.lisp b/cram_demos/cram_integration_tests/tests/package.lisp new file mode 100644 index 0000000000..da1aeb7263 --- /dev/null +++ b/cram_demos/cram_integration_tests/tests/package.lisp @@ -0,0 +1,31 @@ +;;; Copyright (c) 2020, Christopher Pollok +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(defpackage :cram-integration-tests + (:nicknames :int-tests) + (:use :common-lisp :lisp-unit :cram-prolog :cram-designators :cram-executive)) diff --git a/cram_demos/cram_integration_tests/tests/pr2/goals-tests.lisp b/cram_demos/cram_integration_tests/tests/pr2/goals-tests.lisp new file mode 100644 index 0000000000..e9a1532016 --- /dev/null +++ b/cram_demos/cram_integration_tests/tests/pr2/goals-tests.lisp @@ -0,0 +1,342 @@ +;;; +;;; Copyright (c) 2020, Christopher Pollok +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :cram-integration-tests) + +(defparameter *motions-executed* 0) + +(defmethod exe:generic-perform :after ((designator motion-designator)) + (incf *motions-executed*)) + +(defun reset-motions-counter () + (setf *motions-executed* 0)) + +(defun executed-motions? () + (> *motions-executed* 0)) + +(defun initialize () + (sb-ext:gc :full t) + (setf desig::*designators* (tg:make-weak-hash-table :weakness :key)) + (setf btr-belief:*spawn-debug-window* t) + (coe:clear-belief) + (reset-motions-counter)) + +(defun get-object-pose () + (let* ((map-T-surface + (cl-transforms:pose->transform + (btr:link-pose (btr:get-environment-object) "sink_area_surface"))) + (surface-T-object + (cl-transforms:pose->transform + (cram-tf:list->pose '((0.2 -0.15 0.1) (0 0 0 1))))) + (map-T-object + (cl-transforms:transform* map-T-surface surface-T-object))) + (cl-transforms:transform->pose map-T-object))) + +(defun spawn-object-on-sink-counter () + (btr:add-objects-to-mesh-list "cram_pr2_pick_place_demo") + (btr-utils:kill-all-objects) + (btr:detach-all-objects (btr:get-robot-object)) + (btr:detach-all-objects (btr:get-environment-object)) + (btr-utils:spawn-object :test-object :breakfast-cereal + :pose (get-object-pose))) + +(define-test navigation-goal + (initialize) + (let* ((?pose + (cl-transforms-stamped:make-pose-stamped + "map" 0.0 + (cl-transforms:make-3d-vector 0.7 0.7 0) + (cl-transforms:make-identity-rotation))) + (?goal + `(cpoe:robot-at-location ,(a location (pose ?pose)))) + (the-action + (an action + (type going) + (target (a location (pose ?pose))) + (goal ?goal))) + (executed-motions-initially? + nil)) + (urdf-proj:with-simulated-robot + (perform the-action) + (setf executed-motions-initially? (executed-motions?)) + (reset-motions-counter) + (perform the-action)) + (lisp-unit:assert-true executed-motions-initially?)) + (lisp-unit:assert-false (executed-motions?))) + +(define-test arms-positioned-goal + (initialize) + (let* ((?goal + `(cpoe:arms-positioned-at :park :park)) + (the-action + (an action + (type positioning-arm) + (left-configuration park) + (right-configuration park) + (goal ?goal))) + (executed-motions-initially? + nil)) + (urdf-proj:with-simulated-robot + (perform + (an action + (type positioning-arm) + (right-configuration carry-top) + (left-configuration carry-top))) + (perform the-action) + (setf executed-motions-initially? (executed-motions?)) + (reset-motions-counter) + (perform the-action)) + (lisp-unit:assert-true executed-motions-initially?)) + (lisp-unit:assert-false (executed-motions?))) + +(define-test torso-at-goal + (initialize) + (let* ((?goal + `(cpoe:torso-at :lower-limit)) + (the-action + (an action + (type moving-torso) + (joint-angle lower-limit) + (goal ?goal))) + (executed-motions-initially? + nil)) + (urdf-proj:with-simulated-robot + (perform the-action) + (setf executed-motions-initially? (executed-motions?)) + (reset-motions-counter) + (perform the-action)) + (lisp-unit:assert-true executed-motions-initially?)) + (lisp-unit:assert-false (executed-motions?))) + +(define-test gripper-joints-at-test + (initialize) + (let* ((?goal + `(cpoe:gripper-joint-at :left 0.05 0.005)) + (the-action + (an action + (type setting-gripper) + (gripper left) + (position 0.05) + (goal ?goal))) + (executed-motions-initially? + nil)) + (urdf-proj:with-simulated-robot + (perform the-action) + (setf executed-motions-initially? (executed-motions?)) + (reset-motions-counter) + (perform the-action)) + (lisp-unit:assert-true executed-motions-initially?)) + (lisp-unit:assert-false (executed-motions?))) + +(define-test gripper-opened-test + (initialize) + (let* ((?goal + `(cpoe:gripper-opened :left 0.01)) + (the-action + (an action + (type opening-gripper) + (gripper left) + (goal ?goal))) + (executed-motions-initially? + nil)) + (urdf-proj:with-simulated-robot + (perform the-action) + (setf executed-motions-initially? (executed-motions?)) + (reset-motions-counter) + (perform the-action)) + (lisp-unit:assert-true executed-motions-initially?)) + (lisp-unit:assert-false (executed-motions?))) + +(define-test gripper-closed-test + (initialize) + (let* ((?goal + `(cpoe:gripper-closed :left 0.01)) + (the-action + (an action + (type closing-gripper) + (gripper left) + (goal ?goal))) + (executed-motions-initially? + nil)) + (urdf-proj:with-simulated-robot + (perform (an action + (type opening-gripper) + (gripper left))) + (reset-motions-counter) + (perform the-action) + (setf executed-motions-initially? (executed-motions?)) + (reset-motions-counter) + (perform the-action)) + (lisp-unit:assert-true executed-motions-initially?)) + (lisp-unit:assert-false (executed-motions?))) + +(define-test look-at-goal + (initialize) + (let* ((?pose + (cl-transforms-stamped:make-pose-stamped + "map" 0.0 + (cl-transforms:make-3d-vector 0.7 0.7 1) + (cl-transforms:make-identity-rotation))) + (?look-pos + (a location (pose ?pose))) + (?goal + `(cpoe:looking-at ,?look-pos)) + (the-action + (an action + (type looking) + (target ?look-pos) + (goal ?goal))) + (executed-motions-initially? nil)) + (urdf-proj:with-simulated-robot + (perform the-action) + (setf executed-motions-initially? (executed-motions?)) + (reset-motions-counter) + (perform the-action)) + (lisp-unit:assert-true executed-motions-initially?)) + (lisp-unit:assert-false (executed-motions?))) + +(define-test container-state-open-goal + (initialize) + (let* ((?container + (an object + (type drawer) + (urdf-name sink-area-left-upper-drawer-main) + (part-of iai-kitchen))) + (?goal + `(cpoe:container-state ,?container :open)) + (the-action + (an action + (type opening) + (object ?container) + (arm left) + (goal ?goal))) + (executed-motions-initially? + nil)) + (urdf-proj:with-simulated-robot + (btr-utils:move-robot '((.5 .4 0) (0 0 0 1))) + (perform the-action) + (setf executed-motions-initially? (executed-motions?)) + (reset-motions-counter) + (perform the-action)) + (lisp-unit:assert-true executed-motions-initially?)) + (lisp-unit:assert-false (executed-motions?))) + +(define-test container-state-close-goal + (initialize) + (let* ((?container + (an object + (type drawer) + (urdf-name sink-area-left-upper-drawer-main) + (part-of iai-kitchen))) + (?goal + `(cpoe:container-state ,?container :closed)) + (the-action + (an action + (type closing) + (object ?container) + (arm left) + (goal ?goal))) + (executed-motions-initially? + nil)) + (urdf-proj:with-simulated-robot + (btr:set-robot-state-from-joints + `((,"sink_area_left_upper_drawer_main_joint" ,0.4)) + (btr:get-environment-object)) + (btr-utils:move-robot '((.5 .4 0) (0 0 0 1))) + (perform the-action) + (setf executed-motions-initially? (executed-motions?)) + (reset-motions-counter) + (perform the-action)) + (lisp-unit:assert-true executed-motions-initially?)) + (lisp-unit:assert-false (executed-motions?))) + +(define-test tool-frames-at + (initialize) + (let* ((?tool-pose + (btr:link-pose (btr:get-robot-object) cram-tf:*robot-right-tool-frame*)) + (?goal + `(cpoe:tool-frames-at nil ,?tool-pose)) + (the-action + (an action + (type reaching) + (right-poses (?tool-pose)) + (goal ?goal)))) + (urdf-proj:with-simulated-robot + (perform the-action))) + (lisp-unit:assert-false (executed-motions?))) + +(define-test picking-up-goal + (initialize) + (spawn-object-on-sink-counter) + (let ((?robot-pose + (cl-transforms-stamped:pose->pose-stamped + cram-tf:*fixed-frame* 0.0 + (cram-tf:list->pose '((.6 .6 0) (0 0 0 1))))) + (?look-pose + (cl-transforms-stamped:pose->pose-stamped + cram-tf:*fixed-frame* 0.0 + (get-object-pose))) + (executed-motions-initially? + nil)) + (urdf-proj:with-simulated-robot + (perform + (a motion + (type going) + (pose ?robot-pose))) + (perform + (an action + (type looking) + (target (a location + (pose ?look-pose))))) + (let* ((?object + (perform + (an action + (type perceiving) + (object (an object + (type breakfast-cereal)))))) + ;; We copy the object here because the original gets changed, + ;; in a way that referencing the pick up designator doesn't work anymore. + (?object-copy + (desig:copy-designator ?object)) + (?goal + `(cpoe:object-in-hand ,?object))) + (perform + (an action + (type picking-up) + (object ?object) + (goal ?goal))) + (setf executed-motions-initially? (executed-motions?)) + (reset-motions-counter) + (perform + (an action + (type picking-up) + (object ?object-copy) + (goal ?goal))))) + (lisp-unit:assert-true executed-motions-initially?)) + (lisp-unit:assert-false (executed-motions?))) diff --git a/cram_demos/cram_integration_tests/tests/pr2/setup.lisp b/cram_demos/cram_integration_tests/tests/pr2/setup.lisp new file mode 100644 index 0000000000..7e4d5cdcb8 --- /dev/null +++ b/cram_demos/cram_integration_tests/tests/pr2/setup.lisp @@ -0,0 +1,40 @@ +;;; +;;; Copyright (c) 2017, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Intelligent Autonomous Systems Group/ +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software +;;; without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :cram-integration-tests) + +;; roslaunch cram_integration_tests pr2.launch + +(defun init-projection () + (cram-occasions-events:clear-belief) + (setf cram-tf:*tf-default-timeout* 0.1) + (setf prolog:*break-on-lisp-errors* t) + (btr:clear-costmap-vis-object)) + +(roslisp-utilities:register-ros-init-function init-projection) diff --git a/cram_common/cram_object_knowledge/CMakeLists.txt b/cram_demos/cram_object_knowledge/CMakeLists.txt similarity index 100% rename from cram_common/cram_object_knowledge/CMakeLists.txt rename to cram_demos/cram_object_knowledge/CMakeLists.txt diff --git a/cram_common/cram_object_knowledge/cram-object-knowledge.asd b/cram_demos/cram_object_knowledge/cram-object-knowledge.asd similarity index 84% rename from cram_common/cram_object_knowledge/cram-object-knowledge.asd rename to cram_demos/cram_object_knowledge/cram-object-knowledge.asd index c6c2a2551e..93b115a8bd 100644 --- a/cram_common/cram_object_knowledge/cram-object-knowledge.asd +++ b/cram_demos/cram_object_knowledge/cram-object-knowledge.asd @@ -32,11 +32,16 @@ :license "BSD" :depends-on (cram-prolog - cram-manipulation-interfaces) + cram-manipulation-interfaces + cram-designators ; mostly used for likely locations + cram-location-costmap ; for specifying the metadata + ) :components ((:module "src" :components ((:file "package") (:file "environment" :depends-on ("package")) (:file "household" :depends-on ("package")) - (:file "assembly" :depends-on ("package")))))) + (:file "assembly" :depends-on ("package")) + (:file "retail" :depends-on ("package")) + (:file "multiple-trajectory-poses" :depends-on ("package")))))) diff --git a/cram_common/cram_object_knowledge/package.xml b/cram_demos/cram_object_knowledge/package.xml similarity index 91% rename from cram_common/cram_object_knowledge/package.xml rename to cram_demos/cram_object_knowledge/package.xml index f3414cecbe..dd7add77c3 100644 --- a/cram_common/cram_object_knowledge/package.xml +++ b/cram_demos/cram_object_knowledge/package.xml @@ -17,4 +17,6 @@ cram_prolog cram_manipulation_interfaces + cram_designators + cram_location_costmap diff --git a/cram_common/cram_object_knowledge/src/assembly.lisp b/cram_demos/cram_object_knowledge/src/assembly.lisp similarity index 78% rename from cram_common/cram_object_knowledge/src/assembly.lisp rename to cram_demos/cram_object_knowledge/src/assembly.lisp index 1a623993af..61d71c0f4c 100644 --- a/cram_common/cram_object_knowledge/src/assembly.lisp +++ b/cram_demos/cram_object_knowledge/src/assembly.lisp @@ -66,6 +66,14 @@ 0.02) (defmethod man-int:get-action-gripper-opening :heuristics 20 ((object-type (eql :window))) 0.02) +(defmethod man-int:get-action-gripper-opening :heuristics 20 ((object-type (eql :underbody))) + 0.05) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defmethod man-int:get-object-type-carry-config :heuristics 20 + ((object-type (eql :assembly-item)) grasp) + :carry) ;;;;;;;;;;;;;;;;;;;;;;;;;;;; CHASSIS ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; @@ -77,8 +85,8 @@ :grasp-rot-matrix man-int:*z-across-x-grasp-rotation* :pregrasp-offsets *default-lift-offsets* :2nd-pregrasp-offsets *default-lift-offsets* - :lift-offsets *default-lift-offsets* - :2nd-lift-offsets *default-lift-offsets*) + :lift-translation *default-lift-offsets* + :2nd-lift-translation *default-lift-offsets*) ;;;;;;;;;;;;;;;;;;;;;;;;;;;; BOTTOM-WING ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; @@ -87,25 +95,25 @@ (defparameter *bottom-wing-grasp-z-offset* 0.02) ;; SIDE grasp -(man-int:def-object-type-to-gripper-transforms :bottom-wing :left :right-side - :grasp-translation `(,(- *bottom-wing-grasp-x-offset*) - ,*bottom-wing-grasp-y-offset* - ,*bottom-wing-grasp-z-offset*) - :grasp-rot-matrix man-int:*y-across-x-grasp-rotation* - :pregrasp-offsets `(0 ,*default-z-offset* ,*default-z-offset*) - :2nd-pregrasp-offsets `(0 ,*default-z-offset* 0.0) - :lift-offsets *default-lift-offsets* - :2nd-lift-offsets *default-lift-offsets*) - -(man-int:def-object-type-to-gripper-transforms :bottom-wing :right :right-side - :grasp-translation `(,*bottom-wing-grasp-x-offset* - ,(- *bottom-wing-grasp-y-offset*) - ,*bottom-wing-grasp-z-offset*) - :grasp-rot-matrix man-int:*-y-across-x-grasp-rotation* - :pregrasp-offsets `(0 ,(- *default-z-offset*) ,*default-z-offset*) - :2nd-pregrasp-offsets `(0 ,(- *default-z-offset*) 0.0) - :lift-offsets *default-lift-offsets* - :2nd-lift-offsets *default-lift-offsets*) +;; (man-int:def-object-type-to-gripper-transforms :bottom-wing :left :right-side +;; :grasp-translation `(,(- *bottom-wing-grasp-x-offset*) +;; ,*bottom-wing-grasp-y-offset* +;; ,*bottom-wing-grasp-z-offset*) +;; :grasp-rot-matrix man-int:*y-across-x-grasp-rotation* +;; :pregrasp-offsets `(0 ,*default-z-offset* ,*default-z-offset*) +;; :2nd-pregrasp-offsets `(0 ,*default-z-offset* 0.0) +;; :lift-translation *default-lift-offsets* +;; :2nd-lift-translation *default-lift-offsets*) + +;; (man-int:def-object-type-to-gripper-transforms :bottom-wing :right :right-side +;; :grasp-translation `(,*bottom-wing-grasp-x-offset* +;; ,(- *bottom-wing-grasp-y-offset*) +;; ,*bottom-wing-grasp-z-offset*) +;; :grasp-rot-matrix man-int:*-y-across-x-grasp-rotation* +;; :pregrasp-offsets `(0 ,(- *default-z-offset*) ,*default-z-offset*) +;; :2nd-pregrasp-offsets `(0 ,(- *default-z-offset*) 0.0) +;; :lift-translation *default-lift-offsets* +;; :2nd-lift-translation *default-lift-offsets*) ;; BACK grasp (man-int:def-object-type-to-gripper-transforms :bottom-wing '(:left :right) :back @@ -115,8 +123,8 @@ :grasp-rot-matrix man-int:*-x-across-y-grasp-rotation* :pregrasp-offsets `(,(- *default-z-offset*) 0.0 ,*default-z-offset*) :2nd-pregrasp-offsets `(,(- *default-z-offset*) 0.0 0.0) - :lift-offsets *default-lift-offsets* - :2nd-lift-offsets *default-lift-offsets*) + :lift-translation *default-lift-offsets* + :2nd-lift-translation *default-lift-offsets*) ;;;;;;;;;;;;;;;;;;;;;;;;;;;; UNDERBODY ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; @@ -129,16 +137,16 @@ :grasp-rot-matrix man-int:*z-across-x-grasp-rotation* :pregrasp-offsets *default-lift-offsets* :2nd-pregrasp-offsets *default-lift-offsets* - :lift-offsets *default-lift-offsets* - :2nd-lift-offsets *default-lift-offsets*) + :lift-translation *default-lift-offsets* + :2nd-lift-translation *default-lift-offsets*) (man-int:def-object-type-to-gripper-transforms :underbody :right :top :grasp-translation `(0.0 ,(- *underbody-grasp-y-offset*) ,*underbody-grasp-z-offset*) :grasp-rot-matrix man-int:*z-across-x-grasp-rotation* :pregrasp-offsets *default-lift-offsets* :2nd-pregrasp-offsets *default-lift-offsets* - :lift-offsets *default-lift-offsets* - :2nd-lift-offsets *default-lift-offsets*) + :lift-translation *default-lift-offsets* + :2nd-lift-translation *default-lift-offsets*) ;;;;;;;;;;;;;;;;;;;;;;;;;;;; UPPER-BODY ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; @@ -151,8 +159,8 @@ :grasp-rot-matrix man-int:*z-across-x-grasp-rotation* :pregrasp-offsets *default-lift-offsets* :2nd-pregrasp-offsets *default-lift-offsets* - :lift-offsets *default-lift-offsets* - :2nd-lift-offsets *default-lift-offsets*) + :lift-translation *default-lift-offsets* + :2nd-lift-translation *default-lift-offsets*) ;;;;;;;;;;;;;;;;;;;;;;;;;;;; TOP-WING ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; @@ -168,8 +176,20 @@ :grasp-rot-matrix man-int:*-x-across-y-grasp-rotation* :pregrasp-offsets `(,(- *default-z-offset*) 0.0 ,*default-z-offset*) :2nd-pregrasp-offsets `(,(- *default-z-offset*) 0.0 0.0) - :lift-offsets *default-lift-offsets* - :2nd-lift-offsets *default-lift-offsets*) + :lift-translation *default-lift-offsets* + :2nd-lift-translation *default-lift-offsets*) + +;; SIDE grasp (for picking it up with the whole airplane later) +(man-int:def-object-type-to-gripper-transforms :top-wing :left :right-side + :grasp-translation `(,(- *top-wing-grasp-x-offset*) + ,(- *top-wing-grasp-y-offset*) + ,*top-wing-grasp-z-offset*) + :grasp-rot-matrix man-int:*-y-across-x-grasp-rotation* + :pregrasp-offsets `(0 ,(- *default-z-offset*) ,*default-z-offset*) + :2nd-pregrasp-offsets `(0 ,(- *default-z-offset*) 0.0) + :lift-translation *default-lift-offsets* + :2nd-lift-translation *default-lift-offsets*) + ;;;;;;;;;;;;;;;;;;;;;;;;;;;; WINDOW ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; @@ -185,8 +205,8 @@ :grasp-rot-matrix man-int:*z-diagonal-grasp-rotation* :pregrasp-offsets *default-lift-offsets* :2nd-pregrasp-offsets *default-lift-offsets* - :lift-offsets *default-lift-offsets* - :2nd-lift-offsets *default-lift-offsets*) + :lift-translation *default-lift-offsets* + :2nd-lift-translation *default-lift-offsets*) ;;;;;;;;;;;;;;;;;;;;;;;;;;; FRONT-WHEEL ;;;;;;;;;;;;;;;;;;;;;;;;;;; @@ -202,8 +222,8 @@ :grasp-rot-matrix man-int:*z-diagonal-grasp-rotation* :pregrasp-offsets *default-lift-offsets* :2nd-pregrasp-offsets *default-lift-offsets* - :lift-offsets *default-lift-offsets* - :2nd-lift-offsets *default-lift-offsets*) + :lift-translation *default-lift-offsets* + :2nd-lift-translation *default-lift-offsets*) ;;;;;;;;;;;;;;;;;;;;;;;;;; PROPELLER ;;;;;;;;;;;;;;;;;;;;;;;;;;;;; @@ -219,8 +239,8 @@ :grasp-rot-matrix man-int:*z-across-y-grasp-rotation* :pregrasp-offsets *default-lift-offsets* :2nd-pregrasp-offsets *default-lift-offsets* - :lift-offsets *default-lift-offsets* - :2nd-lift-offsets *default-lift-offsets*) + :lift-translation *default-lift-offsets* + :2nd-lift-translation *default-lift-offsets*) ;;;;;;;;;;;;;;;;;;;;;;;;;;;; BOLT ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; @@ -230,8 +250,8 @@ :grasp-rot-matrix man-int:*z-across-x-grasp-rotation* :pregrasp-offsets *default-lift-offsets* :2nd-pregrasp-offsets *default-lift-offsets* - :lift-offsets *default-lift-offsets* - :2nd-lift-offsets *default-lift-offsets*) + :lift-translation *default-lift-offsets* + :2nd-lift-translation *default-lift-offsets*) ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; @@ -242,10 +262,14 @@ :attachment-rot-matrix man-int:*rotation-around-z-90-matrix*) (man-int:def-object-type-in-other-object-transform :bottom-wing :chassis :wing-attachment - :attachment-translation `(0.0 -0.02 0.04;; 0.0 - ) + :attachment-translation `(0.0 -0.02 0.0) :attachment-rot-matrix man-int:*identity-matrix*) +(defmethod man-int:get-z-offset-for-placing-with-dropping ((object (eql :bottom-wing)) + (other-object (eql :chassis)) + (attachment (eql :wing-attachment))) + 0.04) + (man-int:def-object-type-in-other-object-transform :underbody :bottom-wing :body-attachment :attachment-translation `(0.0 -0.025 0.02) :attachment-rot-matrix man-int:*rotation-around-z+90-matrix*) @@ -271,10 +295,12 @@ :attachment-rot-matrix man-int:*rotation-around-z-180-and-x+90-matrix*) (man-int:def-object-type-in-other-object-transform :bolt :upper-body :rear-thread - :attachment-translation `(-0.0525 0.0 -0.01;; -0.025 - ) + :attachment-translation `(-0.0525 0.0 -0.025) :attachment-rot-matrix man-int:*identity-matrix*) +(defmethod man-int:get-z-offset-for-placing-with-dropping ((object (eql :bolt)) other-object attachment) + 0.015) + (man-int:def-object-type-in-other-object-transform :top-wing :upper-body :wing-attachment :attachment-translation `(0.05 0.0 0.0025) :attachment-rot-matrix man-int:*rotation-around-z-90-matrix*) @@ -284,8 +310,7 @@ :attachment-rot-matrix man-int:*rotation-around-z-90-matrix*) (man-int:def-object-type-in-other-object-transform :bolt :top-wing :middle-thread - :attachment-translation `(0.0 0.025 0.01;; -0.005 - ) + :attachment-translation `(0.0 0.025 -0.005) :attachment-rot-matrix man-int:*identity-matrix*) (man-int:def-object-type-in-other-object-transform :window :top-wing :window-attachment @@ -293,12 +318,10 @@ :attachment-rot-matrix man-int:*rotation-around-z+90-matrix*) (man-int:def-object-type-in-other-object-transform :bolt :window :window-thread - :attachment-translation `(-0.0125 0.0 -0.005;; -0.02 - ) + :attachment-translation `(-0.0125 0.0 -0.02) :attachment-rot-matrix man-int:*identity-matrix*) (man-int:def-object-type-in-other-object-transform :bolt :propeller :propeller-thread - :attachment-translation `(0.0 0.0 0.01;; -0.02 - ) + :attachment-translation `(0.0 0.0 -0.02) :attachment-rot-matrix man-int:*identity-matrix*) diff --git a/cram_common/cram_object_knowledge/src/environment.lisp b/cram_demos/cram_object_knowledge/src/environment.lisp similarity index 68% rename from cram_common/cram_object_knowledge/src/environment.lisp rename to cram_demos/cram_object_knowledge/src/environment.lisp index a849b73cf5..a77938c57d 100644 --- a/cram_common/cram_object_knowledge/src/environment.lisp +++ b/cram_demos/cram_object_knowledge/src/environment.lisp @@ -29,13 +29,37 @@ (in-package :objects) +(def-fact-group costmap-metadata (costmap:costmap-size + costmap:costmap-origin + costmap:costmap-resolution) + (<- (costmap:costmap-size :iai-kitchen 12 12)) + (<- (costmap:costmap-origin :iai-kitchen -6 -6)) + (<- (costmap:costmap-resolution :iai-kitchen 0.04))) + +(def-fact-group retail-small-environment-metadata (costmap:costmap-size + costmap:costmap-origin + costmap:costmap-resolution) + (<- (costmap:costmap-size :dm-shelves 10 10)) + (<- (costmap:costmap-origin :dm-shelves -5 -5)) + (<- (costmap:costmap-resolution :dm-shelves 0.04))) + +(def-fact-group retail-environment-metadata (costmap:costmap-size + costmap:costmap-origin + costmap:costmap-resolution) + (<- (costmap:costmap-size :dm-room 10 10)) + (<- (costmap:costmap-origin :dm-room -5 -5)) + (<- (costmap:costmap-resolution :dm-room 0.04))) + (def-fact-group environment-object-type-hierarchy (man-int:object-type-direct-subtype) (<- (man-int:object-type-direct-subtype :container :container-prismatic)) (<- (man-int:object-type-direct-subtype :container-prismatic :drawer)) (<- (man-int:object-type-direct-subtype :container :container-revolute)) (<- (man-int:object-type-direct-subtype :container-revolute :fridge)) - (<- (man-int:object-type-direct-subtype :container-revolute :oven))) + (<- (man-int:object-type-direct-subtype :container-revolute :oven)) + (<- (man-int:object-type-direct-subtype :container-revolute :dishwasher)) + + (<- (man-int:object-type-direct-subtype :container :shelf))) ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; @@ -62,9 +86,10 @@ ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; (defmethod man-int:get-container-opening-distance :heuristics 20 - ((container-name (eql :iai-fridge-door))) - 1.0) + ((container-name (eql :sink-area-dish-washer-main))) + ;; 0.78d0 ; 45 deg + 0.95d0) ; 54 deg -(defmethod man-int:get-container-opening-distance :heuristics 20 - ((container-name (eql :iai-fridge-main))) - 1.0) +;; (defmethod man-int:get-container-opening-distance :heuristics 20 +;; ((container-name (eql :iai-fridge-main))) +;; 1.0) diff --git a/cram_demos/cram_object_knowledge/src/household.lisp b/cram_demos/cram_object_knowledge/src/household.lisp new file mode 100644 index 0000000000..45e332b9ec --- /dev/null +++ b/cram_demos/cram_object_knowledge/src/household.lisp @@ -0,0 +1,898 @@ +;;; +;;; Copyright (c) 2017, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :objects) + +(defparameter *lift-z-offset* 0.07 "in meters") +(defparameter *lift-offset* `(0.0 0.0 ,*lift-z-offset*)) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(def-fact-group household-object-type-hierarchy (man-int:object-type-direct-subtype) + (<- (man-int:object-type-direct-subtype :household-item :cutlery)) + (<- (man-int:object-type-direct-subtype :household-item :plate)) + (<- (man-int:object-type-direct-subtype :household-item :tray)) + (<- (man-int:object-type-direct-subtype :household-item :bottle)) + (<- (man-int:object-type-direct-subtype :household-item :cup)) + (<- (man-int:object-type-direct-subtype :household-item :milk)) + (<- (man-int:object-type-direct-subtype :household-item :cereal)) + (<- (man-int:object-type-direct-subtype :household-item :bowl)) + + (<- (man-int:object-type-direct-subtype :cutlery :knife)) + (<- (man-int:object-type-direct-subtype :cutlery :fork)) + (<- (man-int:object-type-direct-subtype :cutlery :spoon)) + + (<- (man-int:object-type-direct-subtype :cereal :breakfast-cereal))) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defmethod man-int:get-action-gripping-effort :heuristics 20 + ((object-type (eql :household-item))) + 50) +(defmethod man-int:get-action-gripping-effort :heuristics 20 + ((object-type (eql :milk))) + 20) +(defmethod man-int:get-action-gripping-effort :heuristics 20 + ((object-type (eql :cereal))) + 30) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defmethod man-int:get-action-gripper-opening :heuristics 20 + ((object-type (eql :household-item))) + 0.10) +(defmethod man-int:get-action-gripper-opening :heuristics 20 + ((object-type (eql :cutlery))) + 0.04) +(defmethod man-int:get-action-gripper-opening :heuristics 20 + ((object-type (eql :plate))) + 0.02) +(defmethod man-int:get-action-gripper-opening :heuristics 20 + ((object-type (eql :tray))) + 0.02) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defmethod man-int:get-object-type-carry-config :heuristics 20 + ((object-type (eql :household-item)) grasp) + :carry) +(defmethod man-int:get-object-type-carry-config :heuristics 20 + ((object-type (eql :bowl)) grasp) + :carry-top) +(defmethod man-int:get-object-type-carry-config :heuristics 20 + ((object-type (eql :cup)) (grasp (eql :top))) + :carry-top) +(defmethod man-int:get-object-type-carry-config :heuristics 20 + ((object-type (eql :cereal)) (grasp (eql :top))) + :carry-top) +(defmethod man-int:get-object-type-carry-config :heuristics 20 + ((object-type (eql :basket)) (grasp (eql :top))) + :carry-top-basket) +(defmethod man-int:get-object-type-carry-config :heuristics 20 + ((object-type (eql :plate)) grasp) + :carry-side-gripper-vertical) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(def-fact-group pnp-object-knowledge (man-int:object-rotationally-symmetric + man-int:orientation-matters) + + (<- (object-rotationally-symmetric ?object-type) + (member ?object-type (;; :plate :bottle :drink :cup :bowl :milk + ))) + + (<- (orientation-matters ?object-type) + (member ?object-type (:knife :fork :spoon :cutlery :spatula)))) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;; CUTLERY ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defparameter *cutlery-grasp-z-offset* -0.015 ;; 0.015 + "in meters") ; because TCP is not at the edge +(defparameter *cutlery-pregrasp-z-offset* 0.20 "in meters") +(defparameter *cutlery-pregrasp-xy-offset* 0.10 "in meters") + +;; TOP grasp +(man-int:def-object-type-to-gripper-transforms '(:cutlery :fork :knife :spoon) + '(:left :right) :top + :grasp-translation `(0.0 0.0 ,*cutlery-grasp-z-offset*) + :grasp-rot-matrix man-int:*z-across-x-grasp-rotation* + :pregrasp-offsets `(0.0 0.0 ,*cutlery-pregrasp-z-offset*) + :2nd-pregrasp-offsets `(0.0 0.0 ,*cutlery-pregrasp-z-offset*) + :lift-translation `(0.0 0.0 ,*cutlery-pregrasp-z-offset*) + :2nd-lift-translation `(0.0 0.0 ,*cutlery-pregrasp-z-offset*)) + +;; BOTTOM grasp +;; Bottom grasp is commented out because the robot grasps the spoon through the +;; drawer, as in the last part of the grasping trajectory collisions are turned off +;; (man-int:def-object-type-to-gripper-transforms '(:cutlery :fork :knife :spoon) +;; '(:left :right) :bottom +;; :grasp-translation `(0.0 0.0 ,(- *cutlery-grasp-z-offset*)) +;; :grasp-rot-matrix man-int:*-z-across-x-grasp-rotation* +;; :pregrasp-offsets `(0.0 0.0 ,(- *cutlery-pregrasp-z-offset*)) +;; :2nd-pregrasp-offsets `(0.0 0.0 ,(- *cutlery-pregrasp-z-offset*)) +;; :lift-translation `(0.0 0.0 ,*cutlery-pregrasp-z-offset*) +;; :2nd-lift-translation `(0.0 0.0 ,*cutlery-pregrasp-z-offset*)) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; PLATE ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defparameter *plate-diameter* 0.26 "in meters") +(defparameter *plate-grasp-y-offset* (- (/ *plate-diameter* 2) 0.015) "in meters") +(defparameter *plate-grasp-z-offset* 0.015 "in meters") +(defparameter *plate-grasp-roll-offset* (/ pi 6)) +(defparameter *plate-pregrasp-y-offset* 0.2 "in meters") +(defparameter *plate-2nd-pregrasp-z-offset* 0.03 "in meters") ; grippers can't go into table + +;; SIDE grasp +(man-int:def-object-type-to-gripper-transforms '(:plate :tray) :left :left-side + :grasp-translation `(0.0 ,*plate-grasp-y-offset* ,*plate-grasp-z-offset*) + :grasp-rot-matrix + `((0 1 0) + (,(sin *plate-grasp-roll-offset*) 0 ,(- (cos *plate-grasp-roll-offset*))) + (,(- (cos *plate-grasp-roll-offset*)) 0 ,(- (sin *plate-grasp-roll-offset*)))) + :pregrasp-offsets `(0.0 ,*plate-pregrasp-y-offset* ,*lift-z-offset*) + :2nd-pregrasp-offsets `(0.0 ,*plate-pregrasp-y-offset* ,*plate-2nd-pregrasp-z-offset*) + :lift-translation *lift-offset* + :2nd-lift-translation *lift-offset*) + +(man-int:def-object-type-to-gripper-transforms :plate :right :right-side + :grasp-translation `(0.0 ,(- *plate-grasp-y-offset*) ,*plate-grasp-z-offset*) + :grasp-rot-matrix + `((0 -1 0) + (,(- (sin *plate-grasp-roll-offset*)) 0 ,(cos *plate-grasp-roll-offset*)) + (,(- (cos *plate-grasp-roll-offset*)) 0 ,(- (sin *plate-grasp-roll-offset*)))) + :pregrasp-offsets `(0.0 ,(- *plate-pregrasp-y-offset*) ,*lift-z-offset*) + :2nd-pregrasp-offsets `(0.0 ,(- *plate-pregrasp-y-offset*) ,*plate-2nd-pregrasp-z-offset*) + :lift-translation *lift-offset* + :2nd-lift-translation *lift-offset*) + + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; bottle ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defparameter *bottle-pregrasp-xy-offset* 0.15 "in meters") +(defparameter *bottle-grasp-xy-offset* 0.02 "in meters") +(defparameter *bottle-grasp-z-offset* 0.005 "in meters") + +;; SIDE grasp +(man-int:def-object-type-to-gripper-transforms '(:drink :bottle) '(:left :right) :left-side + :grasp-translation `(0.0d0 ,(- *bottle-grasp-xy-offset*) ,*bottle-grasp-z-offset*) + :grasp-rot-matrix man-int:*y-across-z-grasp-rotation* + :pregrasp-offsets `(0.0 ,*bottle-pregrasp-xy-offset* ,*lift-z-offset*) + :2nd-pregrasp-offsets `(0.0 ,*bottle-pregrasp-xy-offset* 0.0) + :lift-translation *lift-offset* + :2nd-lift-translation *lift-offset*) + +(man-int:def-object-type-to-gripper-transforms '(:drink :bottle) '(:left :right) :right-side + :grasp-translation `(0.0d0 ,*bottle-grasp-xy-offset* ,*bottle-grasp-z-offset*) + :grasp-rot-matrix man-int:*-y-across-z-grasp-rotation* + :pregrasp-offsets `(0.0 ,(- *bottle-pregrasp-xy-offset*) ,*lift-z-offset*) + :2nd-pregrasp-offsets `(0.0 ,(- *bottle-pregrasp-xy-offset*) 0.0) + :lift-translation *lift-offset* + :2nd-lift-translation *lift-offset*) + +;; BACK grasp +(man-int:def-object-type-to-gripper-transforms '(:drink :bottle) '(:left :right) :back + :grasp-translation `(,(- *bottle-grasp-xy-offset*) 0.0d0 ,*bottle-grasp-z-offset*) + :grasp-rot-matrix man-int:*-x-across-z-grasp-rotation* + :pregrasp-offsets `(,(- *bottle-pregrasp-xy-offset*) 0.0 ,*lift-z-offset*) + :2nd-pregrasp-offsets `(,(- *bottle-pregrasp-xy-offset*) 0.0 0.0) + :lift-translation *lift-offset* + :2nd-lift-translation *lift-offset*) + +;; FRONT grasp +(man-int:def-object-type-to-gripper-transforms '(:drink :bottle) '(:left :right) :front + :grasp-translation `(,*bottle-grasp-xy-offset* 0.0d0 ,*bottle-grasp-z-offset*) + :grasp-rot-matrix man-int:*x-across-z-grasp-rotation* + :pregrasp-offsets `(,*bottle-pregrasp-xy-offset* 0.0 ,*lift-z-offset*) + :2nd-pregrasp-offsets `(,*bottle-pregrasp-xy-offset* 0.0 0.0) + :lift-translation *lift-offset* + :2nd-lift-translation *lift-offset*) + + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;; cup ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defparameter *cup-pregrasp-xy-offset* 0.15 "in meters") +(defparameter *cup-grasp-xy-offset* 0.02 "in meters") +(defparameter *cup-grasp-z-offset* 0.01 "in meters") +(defparameter *cup-top-grasp-x-offset* 0.03 "in meters") +(defparameter *cup-top-grasp-z-offset* 0.02 "in meters") + +;; TOP grasp +(man-int:def-object-type-to-gripper-transforms :cup '(:left :right) :top + :grasp-translation `(,(- *cup-top-grasp-x-offset*) 0.0d0 ,*cup-top-grasp-z-offset*) + :grasp-rot-matrix man-int:*z-across-y-grasp-rotation* + :pregrasp-offsets *lift-offset* + :2nd-pregrasp-offsets *lift-offset* + :lift-translation *lift-offset* + :2nd-lift-translation *lift-offset*) + +;; SIDE grasp +(man-int:def-object-type-to-gripper-transforms :cup '(:left :right) :left-side + :grasp-translation `(0.0d0 ,(- *cup-grasp-xy-offset*) ,*cup-grasp-z-offset*) + :grasp-rot-matrix man-int:*y-across-z-flipped-grasp-rotation* + :pregrasp-offsets `(0.0 ,*cup-pregrasp-xy-offset* ,*lift-z-offset*) + :2nd-pregrasp-offsets `(0.0 ,*cup-pregrasp-xy-offset* 0.0) + :lift-translation *lift-offset* + :2nd-lift-translation *lift-offset*) + +(man-int:def-object-type-to-gripper-transforms :cup '(:left :right) :right-side + :grasp-translation `(0.0d0 ,*cup-grasp-xy-offset* ,*cup-grasp-z-offset*) + :grasp-rot-matrix man-int:*-y-across-z-flipped-grasp-rotation* + :pregrasp-offsets `(0.0 ,(- *cup-pregrasp-xy-offset*) ,*lift-z-offset*) + :2nd-pregrasp-offsets `(0.0 ,(- *cup-pregrasp-xy-offset*) 0.0) + :lift-translation *lift-offset* + :2nd-lift-translation *lift-offset*) + +;; BACK grasp +(man-int:def-object-type-to-gripper-transforms :cup '(:left :right) :back + :grasp-translation `(,*cup-grasp-xy-offset* 0.0d0 ,*cup-grasp-z-offset*) + :grasp-rot-matrix man-int:*-x-across-z-grasp-rotation* + :pregrasp-offsets `(,(- *cup-pregrasp-xy-offset*) 0.0 ,*lift-z-offset*) + :2nd-pregrasp-offsets `(,(- *cup-pregrasp-xy-offset*) 0.0 0.0) + :lift-translation *lift-offset* + :2nd-lift-translation *lift-offset*) + +;; FRONT grasp +(man-int:def-object-type-to-gripper-transforms :cup '(:left :right) :front + :grasp-translation `(,(- *cup-grasp-xy-offset*) 0.0d0 ,*cup-grasp-z-offset*) + :grasp-rot-matrix man-int:*x-across-z-grasp-rotation* + :pregrasp-offsets `(,*cup-pregrasp-xy-offset* 0.0 ,*lift-z-offset*) + :2nd-pregrasp-offsets `(,*cup-pregrasp-xy-offset* 0.0 0.0) + :lift-translation *lift-offset* + :2nd-lift-translation *lift-offset*) + + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; milk ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defparameter *milk-grasp-xy-offset* 0.01 "in meters") +(defparameter *milk-grasp-z-offset* 0.03 "in meters") +(defparameter *milk-pregrasp-xy-offset* 0.15 "in meters") +(defparameter *milk-lift-z-offset* 0.15 "in meters") + +;; BACK grasp +(man-int:def-object-type-to-gripper-transforms :milk '(:left :right) :back + :grasp-translation `(,*milk-grasp-xy-offset* 0.0d0 ,*milk-grasp-z-offset*) + :grasp-rot-matrix man-int:*-x-across-z-grasp-rotation* + :pregrasp-offsets `(,(- *milk-pregrasp-xy-offset*) 0.0 ,*milk-lift-z-offset*) + :2nd-pregrasp-offsets `(,(- *milk-pregrasp-xy-offset*) 0.0 0.0) + :lift-translation `(0.0 0.0 ,*milk-lift-z-offset*) + :2nd-lift-translation `(0.0 0.0 ,*milk-lift-z-offset*)) + +;; FRONT grasp +(man-int:def-object-type-to-gripper-transforms :milk '(:left :right) :front + :grasp-translation `(,(- *milk-grasp-xy-offset*) 0.0d0 ,*milk-grasp-z-offset*) + :grasp-rot-matrix man-int:*x-across-z-grasp-rotation* + :pregrasp-offsets `(,*milk-pregrasp-xy-offset* 0.0 ,*milk-lift-z-offset*) + :2nd-pregrasp-offsets `(,*milk-pregrasp-xy-offset* 0.0 0.0) + :lift-translation `(0.0 0.0 ,*milk-lift-z-offset*) + :2nd-lift-translation `(0.0 0.0 ,*milk-lift-z-offset*)) + +;; SIDE grasp +(man-int:def-object-type-to-gripper-transforms :milk '(:left :right) :left-side + :grasp-translation `(0.0d0 ,(- *milk-grasp-xy-offset*) ,*milk-grasp-z-offset*) + :grasp-rot-matrix man-int:*y-across-z-grasp-rotation* + :pregrasp-offsets `(0.0 ,*milk-pregrasp-xy-offset* ,*milk-lift-z-offset*) + :2nd-pregrasp-offsets `(0.0 ,*milk-pregrasp-xy-offset* 0.0) + :lift-translation `(0.0 0.0 ,*milk-lift-z-offset*) + :2nd-lift-translation `(0.0 0.0 ,*milk-lift-z-offset*)) + +(man-int:def-object-type-to-gripper-transforms :milk '(:left :right) :right-side + :grasp-translation `(0.0d0 ,*milk-grasp-xy-offset* ,*milk-grasp-z-offset*) + :grasp-rot-matrix man-int:*-y-across-z-grasp-rotation* + :pregrasp-offsets `(0.0 ,(- *milk-pregrasp-xy-offset*) ,*milk-lift-z-offset*) + :2nd-pregrasp-offsets `(0.0 ,(- *milk-pregrasp-xy-offset*) 0.0) + :lift-translation `(0.0 0.0 ,*milk-lift-z-offset*) + :2nd-lift-translation `(0.0 0.0 ,*milk-lift-z-offset*)) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; cereal ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defparameter *cereal-grasp-z-offset* 0.04 "in meters") +(defparameter *cereal-grasp-xy-offset* 0.03 "in meters") +(defparameter *cereal-pregrasp-z-offset* 0.05 "in meters") +(defparameter *cereal-pregrasp-xy-offset* 0.15 "in meters") +(defparameter *cereal-postgrasp-xy-offset* 0.40 "in meters") +(defparameter *cereal-lift-z-offset* 0.1 "in meters") +(defparameter *cereal-small-lift-z-offset* 0.07 "in meters") + +;; TOP grasp +(man-int:def-object-type-to-gripper-transforms + '(:cereal :breakfast-cereal) '(:left :right) :top + :grasp-translation `(0.0d0 0.0d0 ,*cereal-grasp-z-offset*) + :grasp-rot-matrix man-int:*z-across-x-grasp-rotation* + :pregrasp-offsets *lift-offset* + :2nd-pregrasp-offsets *lift-offset* + :lift-translation *lift-offset* + :2nd-lift-translation *lift-offset*) + +;; FRONT grasp table +(man-int:def-object-type-to-gripper-transforms + '(:cereal :breakfast-cereal) '(:left :right) :front + :grasp-translation `(,*cereal-grasp-xy-offset* 0.0d0 ,*cereal-grasp-z-offset*) + :grasp-rot-matrix man-int:*x-across-z-grasp-rotation* + :pregrasp-offsets `(,*cereal-pregrasp-xy-offset* 0.0 ,*cereal-pregrasp-z-offset*) + :2nd-pregrasp-offsets `(,*cereal-pregrasp-xy-offset* 0.0 0.0) + :lift-translation `(0.0 0.0 ,*cereal-lift-z-offset*) + :2nd-lift-translation `(0.0 0.0 ,*cereal-lift-z-offset*)) + +;; FRONT grasp shelf +(man-int:def-object-type-to-gripper-transforms + '(:cereal :breakfast-cereal) '(:left :right) :front + :location-type :shelf + :grasp-translation `(,*cereal-grasp-xy-offset* 0.0d0 ,*cereal-grasp-z-offset*) + :grasp-rot-matrix man-int:*x-across-z-grasp-rotation* + :pregrasp-offsets `(,*cereal-pregrasp-xy-offset* 0.0 ,*cereal-pregrasp-z-offset*) + :2nd-pregrasp-offsets `(,*cereal-pregrasp-xy-offset* 0.0 0.0) + :lift-translation `(,*cereal-grasp-xy-offset* 0.0 ,*cereal-small-lift-z-offset*) + :2nd-lift-translation `(,*cereal-postgrasp-xy-offset* 0.0 ,*cereal-small-lift-z-offset*)) + +;; BACK grasp table +(man-int:def-object-type-to-gripper-transforms + '(:cereal :breakfast-cereal) '(:left :right) :back + :grasp-translation `(,(- *cereal-grasp-xy-offset*) 0.0d0 ,*cereal-grasp-z-offset*) + :grasp-rot-matrix man-int:*-x-across-z-grasp-rotation* + :pregrasp-offsets `(,(- *cereal-pregrasp-xy-offset*) 0.0 ,*cereal-pregrasp-z-offset*) + :2nd-pregrasp-offsets `(,(- *cereal-pregrasp-xy-offset*) 0.0 0.0) + :lift-translation `(0.0 0.0 ,*cereal-lift-z-offset*) + :2nd-lift-translation `(0.0 0.0 ,*cereal-lift-z-offset*)) + +;; BACK grasp shelf +(man-int:def-object-type-to-gripper-transforms + '(:cereal :breakfast-cereal) '(:left :right) :back + :location-type :shelf + :grasp-translation `(,(- *cereal-grasp-xy-offset*) 0.0d0 ,*cereal-grasp-z-offset*) + :grasp-rot-matrix man-int:*-x-across-z-grasp-rotation* + :pregrasp-offsets `(,(- *cereal-pregrasp-xy-offset*) 0.0 ,*cereal-pregrasp-z-offset*) + :2nd-pregrasp-offsets `(,(- *cereal-pregrasp-xy-offset*) 0.0 0.0) + :lift-translation `(,(- *cereal-grasp-xy-offset*) 0.0 ,*cereal-small-lift-z-offset*) + :2nd-lift-translation `(,(- *cereal-postgrasp-xy-offset*) 0.0 ,*cereal-small-lift-z-offset*)) + + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;; bowl ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defparameter *bowl-grasp-x-offset* 0.07 "in meters") +(defparameter *bowl-grasp-z-offset* 0.0 "in meters") +(defparameter *bowl-pregrasp-z-offset* 0.20 "in meters") + +;; TOP grasp +(man-int:def-object-type-to-gripper-transforms :bowl '(:left :right) :top + :grasp-translation `(,(- *bowl-grasp-x-offset*) 0.0d0 ,*bowl-grasp-z-offset*) + :grasp-rot-matrix man-int:*z-across-y-grasp-rotation* + :pregrasp-offsets `(0.0 0.0 ,*bowl-pregrasp-z-offset*) + :2nd-pregrasp-offsets `(0.0 0.0 ,*bowl-pregrasp-z-offset*) + :lift-translation `(0.0 0.0 ,*bowl-pregrasp-z-offset*) + :2nd-lift-translation `(0.0 0.0 ,*bowl-pregrasp-z-offset*)) +(man-int:def-object-type-to-gripper-transforms :bowl '(:left :right) :top-front + :grasp-translation `(,*bowl-grasp-x-offset* 0.0d0 ,*bowl-grasp-z-offset*) + :grasp-rot-matrix man-int:*z-across-y-grasp-rotation* + :pregrasp-offsets `(0.0 0.0 ,*bowl-pregrasp-z-offset*) + :2nd-pregrasp-offsets `(0.0 0.0 ,*bowl-pregrasp-z-offset*) + :lift-translation `(0.0 0.0 ,*bowl-pregrasp-z-offset*) + :2nd-lift-translation `(0.0 0.0 ,*bowl-pregrasp-z-offset*)) +(man-int:def-object-type-to-gripper-transforms :bowl '(:left :right) :top-left + :grasp-translation `(0.0d0 ,*bowl-grasp-x-offset* ,*bowl-grasp-z-offset*) + :grasp-rot-matrix man-int:*z-across-x-grasp-rotation* + :pregrasp-offsets `(0.0 0.0 ,*bowl-pregrasp-z-offset*) + :2nd-pregrasp-offsets `(0.0 0.0 ,*bowl-pregrasp-z-offset*) + :lift-translation `(0.0 0.0 ,*bowl-pregrasp-z-offset*) + :2nd-lift-translation `(0.0 0.0 ,*bowl-pregrasp-z-offset*)) +(man-int:def-object-type-to-gripper-transforms :bowl '(:left :right) :top-right + :grasp-translation `(0.0d0 ,(- *bowl-grasp-x-offset*) ,*bowl-grasp-z-offset*) + :grasp-rot-matrix man-int:*z-across-x-grasp-rotation* + :pregrasp-offsets `(0.0 0.0 ,*bowl-pregrasp-z-offset*) + :2nd-pregrasp-offsets `(0.0 0.0 ,*bowl-pregrasp-z-offset*) + :lift-translation `(0.0 0.0 ,*bowl-pregrasp-z-offset*) + :2nd-lift-translation `(0.0 0.0 ,*bowl-pregrasp-z-offset*)) + + + + + +;;;;;;;;;;;;;;;;;;;;;;;;; table setting locations ;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +;;;;;;;;;;;;;;;;;;;; utilities + +;;;;;;;; sink + +(defun make-location-on-sink-left (?environment-name) + (desig:a location + (on (desig:an object + (type counter-top) + (urdf-name sink-area-surface) + (owl-name "kitchen_sink_block_counter_top") + (part-of ?environment-name))) + (side left))) + +(defun make-location-on-sink-left-front (?environment-name) + (desig:a location + (on (desig:an object + (type counter-top) + (urdf-name sink-area-surface) + (owl-name "kitchen_sink_block_counter_top") + (part-of ?environment-name))) + (side left) + (side front) + (range-invert 0.5))) + +(defun make-location-on-sink-middle-front (?environment-name) + (desig:a location + (on (desig:an object + (type counter-top) + (urdf-name sink-area-surface) + (owl-name "kitchen_sink_block_counter_top") + (part-of ?environment-name))) + (side left) + (side front) + (range 0.5))) + +(defun make-location-in-sink (?object-type ?environment-name) + (desig:a location + (above (desig:an object + (type sink) + (urdf-name sink-area-sink) + (part-of ?environment-name))) + (side right) + (for (desig:an object (type ?object-type))) + ;; the "for" condition for spoon adds a height that is too high to reach + ;; so adding a little negative z-offset + (z-offset -0.1))) + +;;;;;;;;; sink drawers + +(defun make-location-in-sink-left-upper-drawer (?environment-name) + (desig:a location + (in (desig:an object + (type drawer) + (urdf-name sink-area-left-upper-drawer-main) + (owl-name "drawer_sinkblock_upper_open") + (part-of ?environment-name))) + (side front))) + +(defun make-location-in-sink-left-bottom-drawer (?environment-name) + (desig:a location + (in (desig:an object + (type drawer) + (urdf-name sink-area-left-bottom-drawer-main) + (part-of ?environment-name))) + (side front))) + +(defun make-location-in-sink-left-middle-drawer (?environment-name) + (desig:a location + (in (desig:an object + (type drawer) + (urdf-name sink-area-left-middle-drawer-main) + (owl-name "drawer_sinkblock_middle_open") + (part-of ?environment-name))) + (side front))) + +(defun make-location-in-sink-trash-drawer (?object-type ?environment-name) + (desig:a location + (above (desig:an object + (type drawer) + (urdf-name sink-area-trash-drawer-main) + (part-of ?environment-name))) + (z-offset 0.1) + (side front) + (side right) + (range 0.2) + (for (desig:an object (type ?object-type))))) + +;;;;;;;; vertical drawer + +(defun make-location-in-oven-right-drawer (?object-type ?environment-name) + (desig:a location + ;; (side front) + (in (desig:an object + (type drawer) + (urdf-name oven-area-area-right-drawer-main) + (owl-name "drawer_oven_right_open") + (part-of ?environment-name) + (level topmost))) + (side front) + (for (desig:an object (type ?object-type))))) + +;;;;;;;; fridge + +(defun make-location-in-fridge (?environment-name) + (desig:a location + (in (desig:an object + (type fridge) + (urdf-name iai-fridge-main) + (owl-name "drawer_fridge_upper_interior") + (part-of ?environment-name) + (level topmost))))) + +(defun make-location-in-fridge-door (?environment-name) + (desig:a location + (in (desig:an object + (type fridge) + (urdf-name iai-fridge-door) + (owl-name "drawer_fridge_door_open") + (part-of ?environment-name) + (level bottommost))))) + +;;;;;;;; kitchen island + +(defun make-location-on-kitchen-island-slots (?object-type ?environment-name) + (desig:a location + (on (desig:an object + (type counter-top) + (urdf-name kitchen-island-surface) + (owl-name "kitchen_island_counter_top") + (part-of ?environment-name))) + (for (desig:an object (type ?object-type))) + (side back) + (side right) + (range-invert 0.5) + (context table-setting) + (object-count 3))) + +(defun make-location-on-kitchen-island (?object-type ?environment-name) + (desig:a location + (on (desig:an object + (type counter-top) + (urdf-name kitchen-island-surface) + (owl-name "kitchen_island_counter_top") + (part-of ?environment-name))) + (for (desig:an object (type ?object-type))) + (side back) + (side right))) + +(defun make-cereal-location (?object-type ?environment-name) + (desig:a location + ;; (left-of (desig:an object (type ?other-object))) + ;; (far-from (desig:an object (type ?other-object))) + ;; (orientation axis-aligned) + (on (desig:an object + (type counter-top) + (urdf-name kitchen-island-surface) + (owl-name "kitchen_island_counter_top") + (part-of ?environment-name))) + (for (desig:an object (type ?object-type))) + (side back) + (side right))) + +(defun make-location-in-kitchen-island-left-upper-drawer (?environment-name) + (desig:a location + (in (desig:an object + (type drawer) + (urdf-name kitchen-island-left-upper-drawer-main) + (part-of ?environment-name))) + (side front))) + +;;;;;;;; dining table + +(defun make-location-on-dining-table-slots (?object-type ?environment-name) + (desig:a location + (on (desig:an object + (type counter-top) + (urdf-name dining-area-jokkmokk-table-main) + (part-of ?environment-name))) + (for (desig:an object (type ?object-type))) + (side right) + (context table-setting) + (object-count 2))) + +(defun make-location-on-dining-table (?environment-name) + (desig:a location + (on (desig:an object + (type counter-top) + (urdf-name dining-area-jokkmokk-table-main) + (part-of ?environment-name))) + (side right))) + +(defun make-location-in-center-of-dining-table (?object-type ?environment-name) + (desig:a location + (on (desig:an object + (type counter-top) + (urdf-name dining-area-jokkmokk-table-main) + (part-of ?environment-name))) + (for (desig:an object (type ?object-type))) + (range 0.2) + (side right))) + +;;;;;;;;;; w.r.t. other object + +(defun make-location-right-of-other-object (?object-type ?other-object-type + ?other-object-location) + (let ((?other-object-designator + (desig:an object + (type ?other-object-type) + (location ?other-object-location)))) + (desig:a location + (right-of ?other-object-designator) + (near ?other-object-designator) + (for (desig:an object (type ?object-type))) + (orientation support-aligned)))) + +(defun make-location-right-of-behind-other-object (?object-type ?other-object-type + ?other-object-location) + (let ((?other-object-designator + (desig:an object + (type ?other-object-type) + (location ?other-object-location)))) + (desig:a location + (right-of ?other-object-designator) + ;; (behind ?other-object-designator) + (near ?other-object-designator) + (for (desig:an object (type ?object-type)))))) + +(defun make-location-left-of-far-other-object (?object-type ?other-object-type + ?other-object-location) + (let ((?other-object-designator + (desig:an object + (type ?other-object-type) + (location ?other-object-location)))) + (desig:a location + (left-of ?other-object-designator) + (far-from ?other-object-designator) + (for (desig:an object (type ?object-type)))))) + + +;;;;;;;;;;;;;;;;;;;; context TABLE-SETTING-COUNTER + +;;;;;;;; fetching locations + +(mapcar (lambda (type) + (defmethod man-int:get-object-likely-location :heuristics 20 + ((object-type (eql type)) + environment human + (context (eql :table-setting-counter))) + (make-location-on-sink-left-front environment))) + '(:plate)) + +(mapcar (lambda (type) + (defmethod man-int:get-object-likely-location :heuristics 20 + ((object-type (eql type)) + environment human + (context (eql :table-setting-counter))) + (make-location-on-sink-middle-front environment))) + '(:bottle :milk :cereal :breakfast-cereal :cup :bowl :mug)) + +(mapcar (lambda (type) + (defmethod man-int:get-object-likely-location :heuristics 20 + ((object-type (eql type)) + environment human + (context (eql :table-setting-counter))) + (make-location-in-sink-left-upper-drawer environment))) + '(:cutlery :spoon)) + +;;;;;;;;; destination locations + +(mapcar (lambda (object-type) + (defmethod man-int:get-object-destination :heuristics 20 + ((object-type (eql object-type)) + environment human + (context (eql :table-setting-counter))) + (make-location-on-kitchen-island-slots object-type environment))) + '(:bowl :plate)) + +(mapcar (lambda (object-type) + (defmethod man-int:get-object-destination :heuristics 20 + ((object-type (eql object-type)) + environment human + (context (eql :table-setting-counter))) + (make-location-on-kitchen-island object-type environment))) + '(:mug :bottle)) + +(mapcar (lambda (object-type-and-other-object-type) + (destructuring-bind (object-type other-object-type) + object-type-and-other-object-type + (defmethod man-int:get-object-destination :heuristics 20 + ((object-type (eql object-type)) + environment human + (context (eql :table-setting-counter))) + (make-location-right-of-other-object + object-type other-object-type + (make-location-on-kitchen-island-slots + other-object-type environment))))) + '((:spoon :bowl) + (:knife :plate))) + +(mapcar (lambda (object-type-and-other-object-type) + (destructuring-bind (object-type other-object-type) + object-type-and-other-object-type + (defmethod man-int:get-object-destination :heuristics 20 + ((object-type (eql object-type)) + environment human + (context (eql :table-setting-counter))) + (make-location-right-of-behind-other-object + object-type other-object-type + (make-location-on-kitchen-island-slots + other-object-type environment))))) + '((:cup :bowl))) + +(mapcar (lambda (object-type) + (defmethod man-int:get-object-destination :heuristics 20 + ((object-type (eql object-type)) + environment human + (context (eql :table-setting-counter))) + (make-cereal-location object-type environment))) + '(:cereal :breakfast-cereal)) + +(defmethod man-int:get-object-destination :heuristics 20 + ((object-type (eql :milk)) + environment human + (context (eql :table-setting-counter))) + (make-location-left-of-far-other-object + object-type :bowl + (make-location-on-kitchen-island-slots :bowl environment))) + +;;;;;;;;;;;;;;;;;;;; context TABLE-SETTING + +;;;;;;;;;; fetch locations + +(mapcar (lambda (type) + (defmethod man-int:get-object-likely-location :heuristics 20 + ((object-type (eql type)) + environment human + (context (eql :table-setting))) + (make-location-in-sink-left-upper-drawer environment))) + '(:cutlery :spoon)) + +(mapcar (lambda (type) + (defmethod man-int:get-object-likely-location :heuristics 20 + ((object-type (eql type)) + environment human + (context (eql :table-setting))) + (make-location-in-sink-left-middle-drawer environment))) + '(:bowl)) + +(mapcar (lambda (type) + (defmethod man-int:get-object-likely-location :heuristics 20 + ((object-type (eql type)) + environment human + (context (eql :table-setting))) + ;; (make-location-in-sink-left-bottom-drawer environment) + (make-location-in-kitchen-island-left-upper-drawer environment))) + '(:cup)) + +(mapcar (lambda (type) + (defmethod man-int:get-object-likely-location :heuristics 20 + ((object-type (eql type)) + environment human + (context (eql :table-setting))) + (make-location-in-fridge-door environment))) + '(:milk)) + +(mapcar (lambda (type) + (defmethod man-int:get-object-likely-location :heuristics 20 + ((object-type (eql type)) + environment human + (context (eql :table-setting))) + (make-location-in-oven-right-drawer object-type environment))) + '(:cereal :breakfast-cereal)) + +;;;;;;;; destination locations + +(mapcar (lambda (object-type) + (defmethod man-int:get-object-destination :heuristics 20 + ((object-type (eql object-type)) + environment human + (context (eql :table-setting))) + (make-location-on-dining-table-slots object-type environment))) + '(:bowl)) + +(mapcar (lambda (object-type-and-other-object-type) + (destructuring-bind (object-type other-object-type) + object-type-and-other-object-type + (defmethod man-int:get-object-destination :heuristics 20 + ((object-type (eql object-type)) + environment human + (context (eql :table-setting))) + (make-location-right-of-other-object + object-type other-object-type + (make-location-on-dining-table-slots + other-object-type environment))))) + '((:spoon :bowl))) + +(mapcar (lambda (object-type-and-other-object-type) + (destructuring-bind (object-type other-object-type) + object-type-and-other-object-type + (defmethod man-int:get-object-destination :heuristics 20 + ((object-type (eql object-type)) + environment human + (context (eql :table-setting))) + (make-location-right-of-behind-other-object + object-type other-object-type + (make-location-on-dining-table-slots + other-object-type environment))))) + '((:cup :bowl))) + +(mapcar (lambda (object-type) + (defmethod man-int:get-object-destination :heuristics 20 + ((object-type (eql object-type)) + environment human + (context (eql :table-setting))) + (make-location-in-center-of-dining-table object-type environment))) + '(:cereal :breakfast-cereal :milk)) + +;;;;;;;;;;;;;;;;;;;;;;;; table cleaning ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +;; This does not work. First, call-with-most-specific requires +;; a method to be defined for the given object-type, +;; if object-type is :household-item, then it is also +;; forwarded as :household-item to get-object-destination, +;; which is wrong. +;; Finally, get-object-destination of :table-setting is +;; no the same as object-likely-location of :table-cleaning, +;; as during setting we are relative to another object, +;; and during cleaning that object might already be taken away. +;; (defmethod man-int:get-object-likely-location (object-type +;; environment human +;; (context (eql :table-cleaning))) +;; (man-int:get-object-destination object-type environment human :table-setting)) + +(mapcar (lambda (type) + (defmethod man-int:get-object-likely-location :heuristics 20 + ((object-type (eql type)) + environment human + (context (eql :table-cleaning))) + (make-location-on-dining-table environment))) + '(:bowl :spoon :cup :breakfast-cereal :milk + :cereal :mug :cutlery :plate :bottle)) + +(mapcar (lambda (type) + (defmethod man-int:get-object-destination :heuristics 20 + ((object-type (eql type)) + environment human + (context (eql :table-cleaning))) + (make-location-in-oven-right-drawer object-type environment))) + '(:cereal :breakfast-cereal)) + +(mapcar (lambda (type) + (defmethod man-int:get-object-destination :heuristics 20 + ((object-type (eql type)) + environment human + (context (eql :table-cleaning))) + (make-location-in-sink object-type environment))) + '(:bowl :cup :spoon :plate :mug :cutlery)) + +(mapcar (lambda (type) + (defmethod man-int:get-object-destination :heuristics 20 + ((object-type (eql type)) + environment human + (context (eql :table-cleaning))) + (make-location-in-sink-trash-drawer object-type environment))) + '(:milk :bottle)) + + +;;;;;;;;;;;;;;;;;; Predefined poses for placing on dish-washer-drawer ;;;;;;;;;;;;; + +(man-int:def-object-type-in-other-object-transform :bowl :drawer + :bowl-dish-washer-drawer-front-1 + :attachment-translation `(-0.115 -0.15 0.22) + :attachment-rot-matrix '((1 0 0) + (0 1 0) + (0 0 1))) + +(man-int:def-object-type-in-other-object-transform :bowl :drawer + :bowl-dish-washer-drawer-front-2 + :attachment-translation `(-0.115 0.15 0.22) + :attachment-rot-matrix '((1 0 0) + (0 1 0) + (0 0 1))) diff --git a/cram_demos/cram_object_knowledge/src/multiple-trajectory-poses.lisp b/cram_demos/cram_object_knowledge/src/multiple-trajectory-poses.lisp new file mode 100644 index 0000000000..025be0fcbe --- /dev/null +++ b/cram_demos/cram_object_knowledge/src/multiple-trajectory-poses.lisp @@ -0,0 +1,109 @@ +;;; +;;; Copyright (c) 2020, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :objects) + +(defmethod man-int:get-action-gripping-effort :heuristics 20 ((type (eql :shoe))) + 30) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defmethod man-int:get-action-gripper-opening :heuristics 20 ((type (eql :shoe))) + 0.1) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;; SHOE ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defmethod man-int:get-object-type-to-gripper-transform ((object-type (eql :shoe)) + object-name + arm + (grasp (eql :top))) + (cl-transforms-stamped:make-transform-stamped + (roslisp-utilities:rosify-underscores-lisp-name object-name) + (ecase arm + (:left cram-tf:*robot-left-tool-frame*) + (:right cram-tf:*robot-right-tool-frame*)) + 0.0 + (cl-transforms:make-3d-vector 0.0 0.0 0.0) + (cl-transforms:make-quaternion 1 0 0 0))) + +(defmethod man-int:get-object-type-to-gripper-pregrasp-transforms ((type (eql :shoe)) + object-name + arm + (grasp (eql :top)) + location + grasp-transform) + (list + (cl-transforms-stamped:make-transform-stamped + (roslisp-utilities:rosify-underscores-lisp-name object-name) + (ecase arm + (:left cram-tf:*robot-left-tool-frame*) + (:right cram-tf:*robot-right-tool-frame*)) + 0.0 + (cl-transforms:make-3d-vector 0.0 0.0 0.3) + (cl-transforms:make-quaternion 1 0 0 0)) + (cl-transforms-stamped:make-transform-stamped + (roslisp-utilities:rosify-underscores-lisp-name object-name) + (ecase arm + (:left cram-tf:*robot-left-tool-frame*) + (:right cram-tf:*robot-right-tool-frame*)) + 0.0 + (cl-transforms:make-3d-vector 0.0 0.0 0.2) + (cl-transforms:make-quaternion 1 0 0 0)) + (cl-transforms-stamped:make-transform-stamped + (roslisp-utilities:rosify-underscores-lisp-name object-name) + (ecase arm + (:left cram-tf:*robot-left-tool-frame*) + (:right cram-tf:*robot-right-tool-frame*)) + 0.0 + (cl-transforms:make-3d-vector 0.0 0.0 0.1) + (cl-transforms:make-quaternion 1 0 0 0)))) + +(defmethod man-int:get-object-type-wrt-base-frame-lift-transforms ((type (eql :shoe)) + arm + (grasp (eql :top)) + location) + (list + (cl-transforms-stamped:make-transform-stamped + cram-tf:*robot-base-frame* + cram-tf:*robot-base-frame* + 0.0 + (cl-transforms:make-3d-vector 0.0 0.0 0.1) + (cl-transforms:make-identity-rotation)) + (cl-transforms-stamped:make-transform-stamped + cram-tf:*robot-base-frame* + cram-tf:*robot-base-frame* + 0.0 + (cl-transforms:make-3d-vector 0.0 0.0 0.2) + (cl-transforms:make-identity-rotation)) + (cl-transforms-stamped:make-transform-stamped + cram-tf:*robot-base-frame* + cram-tf:*robot-base-frame* + 0.0 + (cl-transforms:make-3d-vector 0.0 0.0 0.3) + (cl-transforms:make-identity-rotation)))) diff --git a/cram_common/cram_object_knowledge/src/package.lisp b/cram_demos/cram_object_knowledge/src/package.lisp similarity index 100% rename from cram_common/cram_object_knowledge/src/package.lisp rename to cram_demos/cram_object_knowledge/src/package.lisp diff --git a/cram_demos/cram_object_knowledge/src/retail.lisp b/cram_demos/cram_object_knowledge/src/retail.lisp new file mode 100644 index 0000000000..e0643d7da1 --- /dev/null +++ b/cram_demos/cram_object_knowledge/src/retail.lisp @@ -0,0 +1,483 @@ +;;; +;;; Copyright (c) 2019, Gayane Kazhoyan +;;; 2019, Jonas Dech +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :objects) + +(defparameter *default-retail-z-offset* 0.05 "in meters") +(defparameter *default-retail-lift-offsets* `(0.0 0.0 ,*default-retail-z-offset*)) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(def-fact-group retail-object-type-hierarchy (man-int:object-type-direct-subtype) + (<- (man-int:object-type-direct-subtype :retail-item ?item-type) + (member ?item-type (:dish-washer-tabs + :balea-bottle :deodorant :juice-box + :denkmit :dove :heitmann :somat :basket)))) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defmethod man-int:get-action-gripper-opening + :heuristics 20 ((object-type (eql :retail-item))) + 0.1) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defmethod man-int:get-action-gripping-effort + :heuristics 20 ((object-type (eql :retail-item))) + ;; it's actually not the effort but the slippage parameter, + ;; because that's what donbot's gripper speaks... + 0.72) + +(defmethod man-int:get-action-gripping-effort + :heuristics 20 ((object-type (eql :dish-washer-tabs))) + 0.2) +(defmethod man-int:get-action-gripping-effort + :heuristics 20 ((object-type (eql :balea-bottle))) + 0.72) +(defmethod man-int:get-action-gripping-effort + :heuristics 20 ((object-type (eql :deodorant))) + 0.9) +(defmethod man-int:get-action-gripping-effort + :heuristics 20 ((object-type (eql :juice-box))) + 0.82) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defmethod man-int:get-object-type-carry-config :heuristics 20 + ((object-type (eql :retail-item)) grasp) + :carry) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; DISH-WASHER-TABS ;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defparameter *dish-washer-tabs-grasp-x-offset* 0.0 "in meters") +(defparameter *dish-washer-tabs-grasp-z-offset* 0.0 "in meters") +(defparameter *dish-washer-tabs-pregrasp-x-offset* 0.3 "in meters") +(defparameter *dish-washer-tabs-small-lift-z-offset* 0.01 "in meters") +(defparameter *dish-washer-tabs-lift-z-top-grasp-offset* 0.10 "in meters") +(defparameter *dish-washer-tabs-lift-z-other-grasp-offset* 0.05 "in meters") + +;; TOP grasp +(man-int:def-object-type-to-gripper-transforms :dish-washer-tabs '(:left :right) :top + :grasp-translation `(0.0 + 0.0 + ,*dish-washer-tabs-grasp-z-offset*) + :grasp-rot-matrix man-int:*z-across-x-grasp-rotation* + :pregrasp-offsets `(0.0 + 0.0 + ,(+ *dish-washer-tabs-grasp-z-offset* + *dish-washer-tabs-lift-z-top-grasp-offset*)) + :2nd-pregrasp-offsets `(0.0 + 0.0 + ,(+ *dish-washer-tabs-grasp-z-offset* + *dish-washer-tabs-small-lift-z-offset*)) + :lift-translation `(0.0 + 0.0 + ,(+ *dish-washer-tabs-grasp-z-offset* + *dish-washer-tabs-small-lift-z-offset*)) + :2nd-lift-translation `(0.0 + 0.0 + ,(+ *dish-washer-tabs-grasp-z-offset* + *dish-washer-tabs-lift-z-top-grasp-offset*))) + +;; BACK grasp robot +(man-int:def-object-type-to-gripper-transforms :dish-washer-tabs '(:left :right) :back + :location-type :robot + :grasp-translation `(,(- *dish-washer-tabs-grasp-x-offset*) + 0.0 + ,*dish-washer-tabs-grasp-z-offset*) + :grasp-rot-matrix man-int:*-x-across-z-grasp-rotation-2* + :pregrasp-offsets `(,(- *dish-washer-tabs-pregrasp-x-offset*) + 0.0 + ,(+ *dish-washer-tabs-grasp-z-offset* + *dish-washer-tabs-lift-z-other-grasp-offset*)) + :2nd-pregrasp-offsets `(,(- *dish-washer-tabs-pregrasp-x-offset*) + 0.0 + ,(+ *dish-washer-tabs-grasp-z-offset* + *dish-washer-tabs-small-lift-z-offset*)) + :lift-translation `(0.0 + 0.0 + ,(+ *dish-washer-tabs-grasp-z-offset* + *dish-washer-tabs-small-lift-z-offset*)) + :2nd-lift-translation `(0.0 + 0.0 + ,(+ *dish-washer-tabs-grasp-z-offset* + *dish-washer-tabs-lift-z-other-grasp-offset*))) + +;; FRONT grasp robot +(man-int:def-object-type-to-gripper-transforms :dish-washer-tabs '(:left :right) :front + :location-type :robot + :grasp-translation `(,*dish-washer-tabs-grasp-x-offset* + 0.0 + ,*dish-washer-tabs-grasp-z-offset*) + :grasp-rot-matrix man-int:*x-across-z-grasp-rotation-2* + :pregrasp-offsets `(,*dish-washer-tabs-pregrasp-x-offset* + 0.0 + ,(+ *dish-washer-tabs-grasp-z-offset* + *default-retail-z-offset*)) + :2nd-pregrasp-offsets `(,*dish-washer-tabs-pregrasp-x-offset* + 0.0 + ,*dish-washer-tabs-grasp-z-offset*) + :lift-translation `(0.0 + 0.0 + ,(+ *dish-washer-tabs-grasp-z-offset* + *dish-washer-tabs-small-lift-z-offset*)) + :2nd-lift-translation `(0.0 + 0.0 + ,(+ *dish-washer-tabs-grasp-z-offset* + *dish-washer-tabs-lift-z-other-grasp-offset*))) + +;; BACK grasp shelf +;; util +(defun make-arm-transform (object-name arm x y z &optional rot-matrix) + (cl-transforms-stamped:make-transform-stamped + (roslisp-utilities:rosify-underscores-lisp-name object-name) + (ecase arm + (:left cram-tf:*robot-left-tool-frame*) + (:right cram-tf:*robot-right-tool-frame*)) + 0.0 + (cl-transforms:make-3d-vector x y z) + (if rot-matrix + (cl-transforms:matrix->quaternion + (make-array '(3 3) :initial-contents rot-matrix)) + (cl-transforms:make-identity-rotation)))) +(defun make-base-transform (x y z) + (cl-transforms-stamped:make-transform-stamped + cram-tf:*robot-base-frame* + cram-tf:*robot-base-frame* + 0.0 + (cl-transforms:make-3d-vector x y z) + (cl-transforms:make-identity-rotation))) +;; grasp +(defmethod man-int:get-object-type-to-gripper-transform + ((object-type (eql :dish-washer-tabs)) + object-name + arm + (grasp (eql :back))) + (make-arm-transform + object-name arm + (- *dish-washer-tabs-grasp-x-offset*) + 0.0 + *dish-washer-tabs-grasp-z-offset* + man-int:*-x-across-z-grasp-rotation-2*)) +;; pregrasp +(defmethod man-int:get-object-type-to-gripper-pregrasp-transforms + ((type (eql :dish-washer-tabs)) + object-name + arm + (grasp (eql :back)) + location + grasp-transform) + (list + (make-arm-transform + object-name arm + (- *dish-washer-tabs-pregrasp-x-offset*) + 0.0 + (+ *dish-washer-tabs-grasp-z-offset* + *dish-washer-tabs-lift-z-other-grasp-offset*) + man-int:*-x-across-z-grasp-rotation-2*) + (make-arm-transform + object-name arm + (- *dish-washer-tabs-pregrasp-x-offset*) + 0.0 + (+ *dish-washer-tabs-grasp-z-offset* + *dish-washer-tabs-lift-z-other-grasp-offset*) + man-int:*-x-across-z-grasp-rotation-2*) + (make-arm-transform + object-name arm + (- *dish-washer-tabs-pregrasp-x-offset*) + 0.0 + (+ *dish-washer-tabs-grasp-z-offset* + *dish-washer-tabs-small-lift-z-offset*) + man-int:*-x-across-z-grasp-rotation-2*))) +;; postgrasp +(defmethod man-int:get-object-type-wrt-base-frame-lift-transforms + ((type (eql :dish-washer-tabs)) + arm + (grasp (eql :back)) + location) + (list + (make-base-transform + 0.0 + 0.0 + (+ *dish-washer-tabs-grasp-z-offset* + *dish-washer-tabs-small-lift-z-offset*)) + (make-base-transform + 0.0 + 0.0 + (+ *dish-washer-tabs-grasp-z-offset* + *dish-washer-tabs-lift-z-other-grasp-offset*)) + (make-base-transform + (- *dish-washer-tabs-pregrasp-x-offset*) + 0.0 + (+ *dish-washer-tabs-grasp-z-offset* + *dish-washer-tabs-lift-z-other-grasp-offset*)))) + + +;; FRONT grasp shelf +;; grasp +(defmethod man-int:get-object-type-to-gripper-transform + ((object-type (eql :dish-washer-tabs)) + object-name + arm + (grasp (eql :front))) + (make-arm-transform + object-name arm + *dish-washer-tabs-grasp-x-offset* + 0.0 + *dish-washer-tabs-grasp-z-offset* + man-int:*x-across-z-grasp-rotation-2*)) +;; pregrasp +(defmethod man-int:get-object-type-to-gripper-pregrasp-transforms + ((type (eql :dish-washer-tabs)) + object-name + arm + (grasp (eql :front)) + location + grasp-transform) + (list + (make-arm-transform + object-name arm + *dish-washer-tabs-pregrasp-x-offset* + 0.0 + (+ *dish-washer-tabs-grasp-z-offset* + *dish-washer-tabs-lift-z-other-grasp-offset*) + man-int:*x-across-z-grasp-rotation-2*) + (make-arm-transform + object-name arm + *dish-washer-tabs-pregrasp-x-offset* + 0.0 + (+ *dish-washer-tabs-grasp-z-offset* + *dish-washer-tabs-lift-z-other-grasp-offset*) + man-int:*x-across-z-grasp-rotation-2*) + (make-arm-transform + object-name arm + *dish-washer-tabs-pregrasp-x-offset* + 0.0 + (+ *dish-washer-tabs-grasp-z-offset* + *dish-washer-tabs-small-lift-z-offset*) + man-int:*x-across-z-grasp-rotation-2*))) +;; postgrasp +(defmethod man-int:get-object-type-wrt-base-frame-lift-transforms + ((type (eql :dish-washer-tabs)) + arm + (grasp (eql :front)) + location) + (list + (make-base-transform + 0.0 + 0.0 + (+ *dish-washer-tabs-grasp-z-offset* + *dish-washer-tabs-small-lift-z-offset*)) + (make-base-transform + 0.0 + 0.0 + (+ *dish-washer-tabs-grasp-z-offset* + *dish-washer-tabs-lift-z-other-grasp-offset*)) + (make-base-transform + *dish-washer-tabs-pregrasp-x-offset* + 0.0 + (+ *dish-washer-tabs-grasp-z-offset* + *dish-washer-tabs-lift-z-other-grasp-offset*)))) + + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; BALEA-BOTTLE ;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defparameter *balea-bottle-grasp-z-offset* 0.0 "in meters") +(defparameter *balea-bottle-pregrasp-x-offset* 0.2 "in meters") + +;; TOP grasp +(man-int:def-object-type-to-gripper-transforms :balea-bottle '(:left :right) :top + :grasp-translation `(0.0 + 0.0 + ,*balea-bottle-grasp-z-offset*) + :grasp-rot-matrix man-int:*z-across-x-grasp-rotation* + :pregrasp-offsets *default-retail-lift-offsets* + :2nd-pregrasp-offsets *default-retail-lift-offsets* + :lift-translation *default-retail-lift-offsets* + :2nd-lift-translation *default-retail-lift-offsets*) + +;; BACK grasp +(man-int:def-object-type-to-gripper-transforms :balea-bottle '(:left :right) :back + :grasp-translation `(0.0 + 0.0 + ,*balea-bottle-grasp-z-offset*) + :grasp-rot-matrix man-int:*-x-across-z-grasp-rotation-2* + :pregrasp-offsets `(,(- *balea-bottle-pregrasp-x-offset*) + 0.0 + ,*default-retail-z-offset*) + :2nd-pregrasp-offsets `(,(- *dish-washer-tabs-pregrasp-x-offset*) + 0.0 + ,*balea-bottle-grasp-z-offset*) + :lift-translation *default-retail-lift-offsets* + :2nd-lift-translation *default-retail-lift-offsets*) + +;; FRONT grasp +(man-int:def-object-type-to-gripper-transforms :balea-bottle '(:left :right) :front + :grasp-translation `(0.0 + 0.0 + ,*balea-bottle-grasp-z-offset*) + :grasp-rot-matrix man-int:*x-across-z-grasp-rotation-2* + :pregrasp-offsets `(,*balea-bottle-pregrasp-x-offset* + 0.0 + ,*default-retail-z-offset*) + :2nd-pregrasp-offsets `(,*balea-bottle-pregrasp-x-offset* + 0.0 + ,*balea-bottle-grasp-z-offset*) + :lift-translation *default-retail-lift-offsets* + :2nd-lift-translation *default-retail-lift-offsets*) + + +;;;;;;;;;;;;;;; DENKMIT, DOVE, HEITMANN and SOMAT ;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defparameter *denkmit-pregrasp-xy-offste* 0.3 "in meters") +(defparameter *denkmit-grasp-xy-offset* 0.03 "in meters") +(defparameter *denkmit-grasp-z-offset* 0.03 "in meters") + +(man-int:def-object-type-to-gripper-transforms :denkmit '(:left :right) :left-side + :grasp-translation `(0.0d0 ,*denkmit-grasp-xy-offset* ,*denkmit-grasp-z-offset*) + :grasp-rot-matrix man-int:*y-across-z-grasp-rotation* + :pregrasp-offsets `(0.0 ,*denkmit-pregrasp-xy-offste* ,*default-retail-z-offset*) + :2nd-pregrasp-offsets `(0.0 ,*denkmit-pregrasp-xy-offste* 0.0) + :lift-translation *default-retail-lift-offsets* + :2nd-lift-translation *default-retail-lift-offsets*) + +(man-int:def-object-type-to-gripper-transforms :dove '(:left :right) :left-side + :grasp-translation `(0.0d0 ,*denkmit-grasp-xy-offset* ,*denkmit-grasp-z-offset*) + :grasp-rot-matrix man-int:*y-across-z-grasp-rotation* + :pregrasp-offsets `(0.0 ,*denkmit-pregrasp-xy-offste* ,*default-retail-z-offset*) + :2nd-pregrasp-offsets `(0.0 ,*denkmit-pregrasp-xy-offste* 0.0) + :lift-translation *default-retail-lift-offsets* + :2nd-lift-translation *default-retail-lift-offsets*) + +(man-int:def-object-type-to-gripper-transforms :heitmann '(:left :right) :left-side + :grasp-translation `(0.0d0 ,*denkmit-grasp-xy-offset* ,*denkmit-grasp-z-offset*) + :grasp-rot-matrix man-int:*y-across-z-grasp-rotation* + :pregrasp-offsets `(0.0 ,*denkmit-pregrasp-xy-offste* ,*default-retail-z-offset*) + :2nd-pregrasp-offsets `(0.0 ,*denkmit-pregrasp-xy-offste* 0.0) + :lift-translation *default-retail-lift-offsets* + :2nd-lift-translation *default-retail-lift-offsets*) + +(man-int:def-object-type-to-gripper-transforms :somat '(:left :right) :left-side + :grasp-translation `(0.0d0 ,*denkmit-grasp-xy-offset* ,*denkmit-grasp-z-offset*) + :grasp-rot-matrix man-int:*y-across-z-grasp-rotation* + :pregrasp-offsets `(0.0 ,*denkmit-pregrasp-xy-offste* ,*default-retail-z-offset*) + :2nd-pregrasp-offsets `(0.0 ,*denkmit-pregrasp-xy-offste* 0.0) + :lift-translation *default-retail-lift-offsets* + :2nd-lift-translation *default-retail-lift-offsets*) + + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; BASKET ;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(man-int:def-object-type-to-gripper-transforms :basket '(:left :right) :top + :grasp-translation `(0.15 0.0 0.18) + :grasp-rot-matrix man-int:*z-across-x-grasp-rotation* + :pregrasp-offsets *default-retail-lift-offsets* + :2nd-pregrasp-offsets *default-retail-lift-offsets* + :lift-translation *default-retail-lift-offsets* + :2nd-lift-translation *default-retail-lift-offsets*) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; +;;;;;;;;;;;;;;;;;;;;;;; placing poses on robot, environment and basket + +(man-int:def-object-type-in-other-object-transform :dish-washer-tabs :robot + :donbot-tray-front + :attachment-translation `(0.2 0.05 0.11) + :attachment-rot-matrix '((0 0 1) + (0 -1 0) + (1 0 0))) + +(man-int:def-object-type-in-other-object-transform :dish-washer-tabs :robot + :donbot-tray-back + :attachment-translation `(0.2 0.05 0.11) + :attachment-rot-matrix '(( 0 0 1) + ( 0 1 0) + (-1 0 0))) + +(man-int:def-object-type-in-other-object-transform :dish-washer-tabs :environment + :dish-washer-tabs-shelf-1-front + :attachment-translation `(0.39968 -0.26038335 0.1202) + :attachment-rot-matrix man-int:*rotation-around-z-90-matrix*) + +(man-int:def-object-type-in-other-object-transform :dish-washer-tabs :environment + :dish-washer-tabs-shelf-1-back + :attachment-translation `(0.39968 -0.26038335 0.1202) + :attachment-rot-matrix man-int:*rotation-around-z+90-matrix*) + +(man-int:def-object-type-in-other-object-transform :dish-washer-tabs :basket + :in-basket-front + :attachment-translation `(0.15 0.15 0.05;; -0.02 + ) + :attachment-rot-matrix '(( 0 0 1) + ( 0 1 0) + (-1 0 0))) + +(man-int:def-object-type-in-other-object-transform :dish-washer-tabs :basket + :in-basket-back + :attachment-translation `(0.15 0.15 0.05;; -0.02 + ) + :attachment-rot-matrix '(( 0 0 -1) + ( 0 -1 0) + (-1 0 0))) + +(man-int:def-object-type-in-other-object-transform :balea-bottle :environment + :balea-bottle-shelf-1-front + :attachment-translation `(0.3 -0.27 0.105) + :attachment-rot-matrix man-int:*rotation-around-z-90-matrix*) + +(man-int:def-object-type-in-other-object-transform :balea-bottle :environment + :balea-bottle-shelf-1-back + :attachment-translation `(0.3 -0.27 0.105) + :attachment-rot-matrix man-int:*rotation-around-z+90-matrix*) + +(man-int:def-object-type-in-other-object-transform :balea-bottle :robot + :donbot-tray-left + :attachment-translation `(0.2 0.1 0.1) + :attachment-rot-matrix '((0.43809 0.89892 0.005072) + (-0.89879 0.43811461 -0.01522) + (-0.0159 0.0021 0.999871))) + +(man-int:def-object-type-in-other-object-transform :heitmann :basket + :in-basket + :attachment-translation `(0.2 0.15 -0.005) + :attachment-rot-matrix '((1 0 0) + (0 1 0) + (0 0 1))) + +(man-int:def-object-type-in-other-object-transform :dove :basket + :in-basket + :attachment-translation `(0.1 0.15 -0.005) + :attachment-rot-matrix '((1 0 0) + (0 1 0) + (0 0 1))) + +(defmethod man-int:get-z-offset-for-placing-with-dropping (object + (other-object (eql :basket)) + attachment) + 0.15) diff --git a/cram_pr2/cram_pr2_pick_place_demo/CMakeLists.txt b/cram_demos/cram_pr2_pick_place_demo/CMakeLists.txt similarity index 100% rename from cram_pr2/cram_pr2_pick_place_demo/CMakeLists.txt rename to cram_demos/cram_pr2_pick_place_demo/CMakeLists.txt diff --git a/cram_pr2/cram_pr2_pick_place_demo/cram-pr2-pick-place-demo-tests.asd b/cram_demos/cram_pr2_pick_place_demo/cram-pr2-pick-place-demo-tests.asd similarity index 100% rename from cram_pr2/cram_pr2_pick_place_demo/cram-pr2-pick-place-demo-tests.asd rename to cram_demos/cram_pr2_pick_place_demo/cram-pr2-pick-place-demo-tests.asd diff --git a/cram_pr2/cram_pr2_pick_place_demo/cram-pr2-pick-place-demo.asd b/cram_demos/cram_pr2_pick_place_demo/cram-pr2-pick-place-demo.asd similarity index 85% rename from cram_pr2/cram_pr2_pick_place_demo/cram-pr2-pick-place-demo.asd rename to cram_demos/cram_pr2_pick_place_demo/cram-pr2-pick-place-demo.asd index b076c0b7cb..16ac77e21a 100644 --- a/cram_pr2/cram_pr2_pick_place_demo/cram-pr2-pick-place-demo.asd +++ b/cram_demos/cram_pr2_pick_place_demo/cram-pr2-pick-place-demo.asd @@ -66,9 +66,13 @@ cram-urdf-projection ; for with-simulated-robot cram-urdf-projection-reasoning ; to set projection reasoning to T - ;; cram-pr2-description cram-fetch-deliver-plans - cram-urdf-environment-manipulation) + cram-urdf-environment-manipulation + + cram-pr2-description + cram-boxy-description + cram-donbot-description + cram-hsrb-description) :components ((:module "src" @@ -78,7 +82,11 @@ (:file "costmaps" :depends-on ("package")) (:file "projection-demo" :depends-on ("package" "costmaps")) (:file "demo" :depends-on ("package" "projection-demo" "costmaps")) - (:file "milestone-projection-demo" :depends-on ("package" "costmaps")) - (:file "data-generation-script" :depends-on ("package" "projection-demo" "costmaps")) + (:file "milestone-projection-demo" :depends-on ("package" + "projection-demo" + "costmaps")) + (:file "data-generation-script" :depends-on ("package" + "projection-demo" + "costmaps")) (:file "data-generation-plan" :depends-on ("package" "demo")) (:file "evaluation-plan" :depends-on ("package" "demo")))))) diff --git a/cram_pr2/cram_urdf_bringup/launch/sandbox.launch b/cram_demos/cram_pr2_pick_place_demo/launch/sandbox.launch similarity index 54% rename from cram_pr2/cram_urdf_bringup/launch/sandbox.launch rename to cram_demos/cram_pr2_pick_place_demo/launch/sandbox.launch index cbcb27deec..e6bf6e5a39 100644 --- a/cram_pr2/cram_urdf_bringup/launch/sandbox.launch +++ b/cram_demos/cram_pr2_pick_place_demo/launch/sandbox.launch @@ -1,14 +1,13 @@ - - - - - + + + + + + - /kitchen/cram_joint_states + @@ -29,23 +31,17 @@ - + + + + - + + - - - - - - - + '$(find pr2_description)/robots/pr2.urdf.xacro'"/> + @@ -56,37 +52,7 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/cram_demos/cram_pr2_pick_place_demo/launch/sandbox_with_giskard.launch b/cram_demos/cram_pr2_pick_place_demo/launch/sandbox_with_giskard.launch new file mode 100644 index 0000000000..50397b37c1 --- /dev/null +++ b/cram_demos/cram_pr2_pick_place_demo/launch/sandbox_with_giskard.launch @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/cram_pr2/cram_pr2_pick_place_demo/package.xml b/cram_demos/cram_pr2_pick_place_demo/package.xml similarity index 94% rename from cram_pr2/cram_pr2_pick_place_demo/package.xml rename to cram_demos/cram_pr2_pick_place_demo/package.xml index 7a7b9da945..ada99b1fec 100644 --- a/cram_pr2/cram_pr2_pick_place_demo/package.xml +++ b/cram_demos/cram_pr2_pick_place_demo/package.xml @@ -39,10 +39,14 @@ cram_mobile_pick_place_plans cram_object_knowledge cram_cloud_logger - cram_pr2_description cram_fetch_deliver_plans cram_urdf_environment_manipulation + cram_pr2_description + cram_boxy_description + cram_donbot_description + cram_hsrb_description + iai_maps iai_kitchen diff --git a/cram_boxy/cram_boxy_assembly_demo/resource/blue_metal_plate.stl b/cram_demos/cram_pr2_pick_place_demo/resource/blue_metal_plate.stl similarity index 100% rename from cram_boxy/cram_boxy_assembly_demo/resource/blue_metal_plate.stl rename to cram_demos/cram_pr2_pick_place_demo/resource/blue_metal_plate.stl diff --git a/cram_boxy/cram_boxy_assembly_demo/resource/bottle.dae b/cram_demos/cram_pr2_pick_place_demo/resource/bottle.dae similarity index 100% rename from cram_boxy/cram_boxy_assembly_demo/resource/bottle.dae rename to cram_demos/cram_pr2_pick_place_demo/resource/bottle.dae diff --git a/cram_demos/cram_pr2_pick_place_demo/resource/bowl.obj b/cram_demos/cram_pr2_pick_place_demo/resource/bowl.obj new file mode 100644 index 0000000000..f14870ddce --- /dev/null +++ b/cram_demos/cram_pr2_pick_place_demo/resource/bowl.obj @@ -0,0 +1,6905 @@ +# Blender v2.83.4 OBJ File: '' +# www.blender.org +mtllib bowl_39.mtl +o Bowl_hull_1 +v 0.033177 -0.029301 -0.019176 +v -0.003464 0.040094 -0.026073 +v -0.003464 0.040094 -0.025642 +v -0.038369 -0.021546 -0.019609 +v -0.005614 -0.037064 -0.033400 +v 0.036191 0.009906 -0.033400 +v -0.034060 0.015950 -0.033400 +v 0.026701 0.035337 -0.018744 +v -0.033189 0.029301 -0.018744 +v 0.009896 0.036201 -0.033400 +v -0.018102 -0.040086 -0.019177 +v 0.028859 -0.024136 -0.033400 +v -0.030175 -0.022410 -0.033400 +v 0.040084 -0.018532 -0.018744 +v 0.019385 -0.039654 -0.018744 +v 0.039652 0.019388 -0.018744 +v -0.017694 0.033187 -0.033400 +v -0.019398 0.039646 -0.018744 +v -0.040104 0.018532 -0.018744 +v -0.037506 -0.002582 -0.032969 +v 0.028859 0.024136 -0.033400 +v 0.015932 -0.034042 -0.033400 +v 0.037046 -0.005597 -0.033400 +v 0.018522 0.040086 -0.018744 +v -0.022420 -0.030172 -0.033400 +v -0.028448 -0.033618 -0.019177 +v 0.003428 -0.040094 -0.026073 +v 0.040076 0.003862 -0.026073 +v -0.040096 0.003438 -0.026073 +v -0.008205 0.036632 -0.033400 +v 0.019817 0.031884 -0.033400 +v -0.039656 -0.018964 -0.019177 +v -0.024146 0.028877 -0.033400 +v -0.034923 -0.013791 -0.033400 +v -0.040104 0.004741 -0.018744 +v 0.026709 -0.035345 -0.019176 +v 0.033177 -0.017669 -0.033400 +v 0.033177 0.029301 -0.019176 +v 0.008177 -0.036632 -0.033400 +v -0.036642 0.008195 -0.033400 +v -0.025434 0.036201 -0.019176 +v -0.015960 -0.034050 -0.033400 +v 0.032745 0.018532 -0.033400 +v 0.007745 -0.039654 -0.018744 +v -0.030175 0.022410 -0.033400 +v 0.024119 -0.028869 -0.033400 +v 0.002988 0.037496 -0.032969 +v -0.033620 -0.028438 -0.019609 +v 0.010759 0.040086 -0.023918 +v -0.039656 -0.010345 -0.024779 +v 0.040084 -0.013367 -0.022622 +v -0.037930 0.022841 -0.019176 +v -0.011643 -0.040086 -0.023486 +v -0.023707 -0.037064 -0.019609 +v 0.037917 -0.022841 -0.019176 +v 0.024119 0.028877 -0.033400 +v 0.037917 0.022833 -0.019176 +v -0.018534 0.039646 -0.020038 +v 0.039652 0.018532 -0.020038 +v 0.018514 -0.039654 -0.020038 +v -0.040096 -0.003438 -0.026073 +v -0.040104 0.015510 -0.021331 +v 0.034896 -0.013783 -0.033400 +v 0.040076 -0.003870 -0.026073 +v 0.037486 0.002991 -0.032969 +v 0.018090 0.040086 -0.019609 +v -0.036642 -0.008171 -0.033400 +v -0.033189 0.029301 -0.019176 +v -0.024146 -0.028869 -0.033400 +v 0.022823 0.037927 -0.019176 +v 0.015932 0.034050 -0.033400 +v -0.009924 -0.036209 -0.033400 +v 0.002572 -0.040086 -0.019609 +v -0.003464 -0.040094 -0.026073 +v 0.002988 -0.037504 -0.032969 +v 0.022831 -0.037928 -0.019176 +v 0.040084 0.000424 -0.019609 +v -0.001282 0.040086 -0.019609 +v -0.029311 0.033187 -0.019176 +v -0.033197 -0.017669 -0.033400 +v 0.039652 0.010345 -0.024777 +v -0.018102 -0.040086 -0.019609 +v 0.026701 0.035337 -0.019176 +v -0.039656 -0.018964 -0.019609 +v 0.009472 -0.039654 -0.025212 +v 0.033177 -0.029301 -0.018744 +v 0.040084 -0.018100 -0.019609 +v 0.019817 -0.031884 -0.033400 +v -0.009484 0.039646 -0.025212 +v -0.013809 0.034913 -0.033400 +v -0.028448 -0.033618 -0.019609 +v 0.003420 0.040094 -0.026073 +v -0.005622 0.037072 -0.033400 +v 0.036191 -0.009906 -0.033400 +v -0.028887 0.024136 -0.033400 +v -0.028887 -0.024136 -0.033400 +v 0.034896 0.013791 -0.033400 +v -0.040104 0.009474 -0.024350 +v -0.037066 0.005596 -0.033400 +v -0.035339 -0.026287 -0.019609 +v -0.022836 0.037927 -0.019176 +v 0.029299 0.033187 -0.019176 +v -0.040104 0.018100 -0.019609 +v 0.029299 -0.033187 -0.019176 +v 0.035335 0.026287 -0.019609 +v -0.035347 0.026279 -0.019609 +v -0.017686 -0.033187 -0.033400 +v 0.037046 0.005596 -0.033400 +v -0.035339 -0.026287 -0.019177 +v 0.035335 -0.026287 -0.019609 +v 0.030155 -0.022402 -0.033400 +v -0.039656 -0.014655 -0.022624 +v -0.036211 0.009906 -0.033400 +v 0.005586 0.037064 -0.033400 +v -0.022420 0.030165 -0.033400 +v -0.033197 0.017669 -0.033400 +v 0.011191 -0.035769 -0.033400 +v 0.033177 0.029301 -0.018744 +v 0.014637 -0.039654 -0.022622 +v 0.040084 -0.008626 -0.024777 +v -0.014657 0.039646 -0.022622 +v -0.037082 -0.005597 -0.033400 +vt 0.037882 0.430207 +vt 0.043168 0.601899 +vt 0.037686 0.569793 +vt 0.951449 0.376468 +vt 0.430110 0.962216 +vt 0.075372 0.301096 +vt 0.623532 0.048551 +vt 0.860023 0.800998 +vt 0.123825 0.779464 +vt 0.833105 0.059319 +vt 0.086237 0.134593 +vt 1.000000 0.731108 +vt 0.741875 0.994518 +vt 0.994616 0.258222 +vt 0.279464 0.086139 +vt 0.456930 0.000000 +vt 0.456930 0.000000 +vt 0.258222 0.005579 +vt 0.000000 0.268892 +vt 0.860023 0.199002 +vt 0.698806 0.924530 +vt 0.962118 0.569793 +vt 0.731108 0.000098 +vt 0.220536 0.876272 +vt 0.397807 0.043168 +vt 0.747259 0.102388 +vt 0.199002 0.139879 +vt 0.064605 0.671985 +vt 0.000000 0.440877 +vt 0.913861 0.720341 +vt 0.602095 0.956832 +vt 0.043168 0.397807 +vt 0.182948 0.048551 +vt 0.301096 0.924628 +vt 0.908477 0.268892 +vt 0.274374 0.999902 +vt 0.596711 0.994518 +vt 0.145360 0.919244 +vt 0.123825 0.220536 +vt 0.800901 0.860024 +vt 0.027114 0.215153 +vt 0.204483 0.962216 +vt 0.800901 0.139879 +vt 0.268990 0.005579 +vt 0.999902 0.451840 +vt 0.994616 0.268892 +vt 0.972984 0.215251 +vt 0.542874 1.000000 +vt 0.731010 0.994518 +vt 0.000098 0.457126 +vt 0.032400 0.532204 +vt 0.000098 0.542874 +vt 0.005579 0.736492 +vt 0.000000 0.306578 +vt 0.935298 0.671887 +vt 0.999902 0.548258 +vt 0.967600 0.462706 +vt 0.634299 0.000098 +vt 0.725724 0.000098 +vt 0.086237 0.134593 +vt 0.199002 0.860024 +vt 0.784749 0.027016 +vt 0.698806 0.075372 +vt 0.376370 0.951547 +vt 0.354933 0.999902 +vt 0.532204 0.999902 +vt 0.456930 1.000000 +vt 0.537392 0.967698 +vt 0.833203 0.940779 +vt 0.784847 0.972984 +vt 1.000000 0.494714 +vt 1.000000 0.666699 +vt 0.484143 0.000098 +vt 0.134593 0.086139 +vt 0.021633 0.768696 +vt 0.086139 0.720341 +vt 0.994616 0.370987 +vt 0.274374 0.999902 +vt 0.833105 0.059319 +vt 0.005579 0.736492 +vt 0.618246 0.994518 +vt 0.913861 0.865407 +vt 0.913861 0.865407 +vt 0.972984 0.784847 +vt 1.000000 0.725724 +vt 0.747259 0.897612 +vt 0.327917 0.064605 +vt 0.080854 0.854640 +vt 0.145360 0.919244 +vt 0.542776 0.000000 +vt 0.537392 0.032400 +vt 0.430012 0.037686 +vt 0.381852 0.005579 +vt 0.951449 0.623532 +vt 0.139879 0.199002 +vt 0.139879 0.800998 +vt 0.935298 0.328015 +vt 0.000000 0.381852 +vt 0.059417 0.827819 +vt 0.215348 0.027016 +vt 0.913861 0.134593 +vt 0.865505 0.086139 +vt 0.000000 0.274276 +vt 0.865505 0.913861 +vt 0.940779 0.172181 +vt 0.059319 0.172279 +vt 0.279561 0.913861 +vt 0.962118 0.430207 +vt 0.059417 0.827819 +vt 0.940779 0.827819 +vt 0.876175 0.779366 +vt 0.005579 0.629013 +vt 0.005579 0.682753 +vt 0.048551 0.376468 +vt 0.569793 0.037784 +vt 0.220536 0.123825 +vt 0.086139 0.279659 +vt 0.639683 0.946065 +vt 0.913861 0.134593 +vt 0.682655 0.994518 +vt 1.000000 0.607576 +vt 0.317345 0.005579 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -0.0000 1.0000 +vn -0.0281 0.9996 0.0000 +vn -0.2679 0.3571 0.8948 +vn 0.0000 -0.7084 0.7058 +vn -0.0163 -0.0261 0.9995 +vn -0.0146 -0.0157 0.9998 +vn -0.5507 0.3536 0.7560 +vn -0.3851 -0.6160 0.6872 +vn -0.0405 0.9988 -0.0270 +vn 0.9989 0.0396 -0.0262 +vn 0.8735 0.4061 -0.2685 +vn 0.8100 0.4106 -0.4187 +vn 0.0398 -0.9988 -0.0268 +vn -0.9362 0.0000 -0.3516 +vn -0.9996 -0.0192 0.0204 +vn -1.0000 -0.0000 0.0000 +vn 0.9261 -0.0285 -0.3762 +vn 0.9362 0.0000 -0.3516 +vn 0.2274 0.8937 -0.3869 +vn -0.8062 0.5917 0.0000 +vn 0.4155 0.7156 0.5616 +vn 0.4215 0.8821 -0.2103 +vn 0.4082 0.8111 -0.4189 +vn 0.3044 0.8542 -0.4215 +vn 0.4401 0.7892 -0.4284 +vn -0.1797 -0.9052 -0.3852 +vn 0.0070 -0.9424 0.3345 +vn 0.0000 -1.0000 0.0012 +vn 0.0254 -0.9997 0.0046 +vn 0.0000 -1.0000 0.0011 +vn -0.1120 -0.9295 -0.3515 +vn 0.0162 -0.5190 -0.8546 +vn -0.0286 -0.9267 -0.3748 +vn 0.0000 -0.9362 -0.3516 +vn 0.3738 -0.5613 0.7384 +vn 0.4037 -0.8736 -0.2718 +vn 0.4081 -0.8109 -0.4195 +vn 0.9702 0.0110 0.2420 +vn 0.9997 0.0223 0.0106 +vn 1.0000 0.0000 0.0000 +vn -0.0238 0.9997 0.0099 +vn -0.0001 1.0000 0.0013 +vn -0.0112 0.9665 0.2565 +vn -0.3263 0.4198 0.8469 +vn -0.5571 0.7167 -0.4194 +vn -0.7078 0.7064 0.0000 +vn -0.7639 -0.4869 -0.4234 +vn 0.9022 0.2160 -0.3732 +vn 0.9807 0.0979 -0.1692 +vn -0.4746 -0.8802 0.0000 +vn -0.3054 -0.8540 -0.4212 +vn -0.2335 -0.8912 -0.3890 +vn -0.0005 -1.0000 0.0000 +vn -0.0020 -1.0000 -0.0034 +vn 0.5172 0.7400 -0.4300 +vn 0.5555 0.8315 0.0000 +vn 0.5026 0.7523 -0.4259 +vn -0.8950 -0.4461 0.0000 +vn -0.9996 -0.0283 0.0000 +vn -0.8127 -0.4051 -0.4187 +vn -0.8280 -0.3687 -0.4225 +vn 0.1253 -0.9242 -0.3609 +vn 0.1181 -0.9271 -0.3557 +vn 0.2483 -0.3308 0.9104 +vn 0.8062 -0.5917 0.0000 +vn 0.5483 -0.3517 0.7587 +vn 0.8817 -0.4222 -0.2107 +vn 0.8108 -0.4088 -0.4189 +vn 0.8274 -0.3661 -0.4259 +vn 0.5179 -0.7391 -0.4308 +vn 0.5014 -0.7529 -0.4262 +vn 0.4388 -0.7898 -0.4286 +vn -0.3679 0.8279 -0.4234 +vn -0.7076 -0.7066 0.0000 +vn -0.5343 -0.7351 -0.4172 +vn -0.5879 -0.8089 0.0000 +vn -0.5466 -0.7244 -0.4200 +vn 0.0000 1.0000 0.0000 +vn 0.0001 1.0000 0.0009 +vn 0.0000 0.9358 -0.3525 +vn 0.0007 1.0000 -0.0003 +vn 0.0021 1.0000 -0.0036 +vn -0.0269 0.9269 -0.3744 +vn -0.1189 0.9298 -0.3484 +vn -0.1564 0.9187 -0.3626 +vn 0.9053 -0.1798 -0.3848 +vn 0.8805 -0.2545 -0.3998 +vn 0.8630 -0.2882 -0.4149 +vn -0.6397 0.6397 -0.4261 +vn -0.6405 0.6392 -0.4258 +vn -0.6421 -0.6411 -0.4203 +vn -0.6409 -0.6419 -0.4209 +vn 0.8651 0.2884 -0.4103 +vn 0.8239 0.3738 -0.4259 +vn -1.0000 0.0000 -0.0046 +vn -1.0000 -0.0005 -0.0005 +vn -0.9084 0.1870 -0.3739 +vn -0.9268 0.0301 -0.3744 +vn -0.9295 0.1001 -0.3549 +vn -0.9163 0.1495 -0.3716 +vn -0.7635 -0.4879 -0.4231 +vn -0.7261 -0.5413 -0.4241 +vn -0.7089 -0.5666 -0.4200 +vn -0.3739 0.5625 0.7374 +vn -0.4034 0.8745 -0.2692 +vn -0.4081 0.8116 -0.4180 +vn 0.6403 0.6390 -0.4263 +vn 0.6395 0.6395 -0.4267 +vn 0.6377 0.7703 0.0000 +vn 0.5781 0.6983 -0.4221 +vn -0.8810 0.4233 -0.2112 +vn 0.6403 -0.6390 -0.4263 +vn 0.6389 -0.6400 -0.4269 +vn 0.5802 -0.6962 -0.4226 +vn 0.7078 -0.7064 0.0000 +vn 0.4173 -0.5007 0.7584 +vn 0.7078 0.5674 -0.4208 +vn 0.7424 0.5147 -0.4289 +vn 0.8029 0.5886 -0.0942 +vn 0.7494 0.5070 -0.4258 +vn -0.7490 0.5092 -0.4238 +vn -0.8013 0.5881 -0.1096 +vn -0.7260 0.5412 -0.4242 +vn -0.7089 0.5666 -0.4201 +vn -0.4858 -0.7629 -0.4266 +vn -0.4321 -0.8013 -0.4139 +vn -0.4061 -0.8123 -0.4186 +vn 0.6996 0.0000 -0.7145 +vn 0.9277 0.0969 -0.3606 +vn 0.9095 0.1806 -0.3743 +vn 0.9267 0.1310 -0.3522 +vn -0.7800 -0.4598 0.4245 +vn -0.0178 -0.0167 0.9997 +vn -0.0320 -0.0189 0.9993 +vn -0.6489 -0.6100 0.4549 +vn -0.8426 -0.5385 0.0000 +vn -0.7811 -0.6243 0.0000 +vn 0.7078 -0.5674 -0.4208 +vn 0.8022 -0.5887 -0.0991 +vn 0.7493 -0.5082 -0.4246 +vn 0.7609 -0.4858 -0.4303 +vn 0.7253 -0.5415 -0.4250 +vn -0.9751 -0.0992 -0.1984 +vn -0.8742 -0.2674 -0.4054 +vn -0.9128 -0.1826 -0.3652 +vn -0.9926 -0.0694 -0.0992 +vn -0.8696 -0.2830 -0.4046 +vn -0.8919 0.2250 -0.3922 +vn -0.8542 0.3040 -0.4218 +vn -0.8724 0.2706 -0.4071 +vn 0.1812 0.9041 -0.3870 +vn 0.0955 0.9295 -0.3561 +vn 0.1048 0.9296 -0.3534 +vn 0.0005 0.7075 -0.7067 +vn -0.5416 0.7265 -0.4230 +vn -0.5008 0.7535 -0.4259 +vn -0.4866 0.7608 -0.4295 +vn -0.7614 0.4853 -0.4298 +vn -0.8113 0.4075 -0.4191 +vn -0.8103 0.4099 -0.4187 +vn 0.3108 -0.8534 -0.4185 +vn 0.5918 0.3866 0.7073 +vn 0.8065 0.5912 0.0000 +vn 0.6197 0.6648 0.4172 +vn 0.7078 0.7064 0.0000 +vn 0.0723 -0.9915 -0.1084 +vn 0.0991 -0.9753 -0.1976 +vn 0.1834 -0.9125 -0.3658 +vn 0.2526 -0.8817 -0.3986 +vn 0.2674 -0.8760 -0.4013 +vn 0.9083 -0.1731 -0.3808 +vn 0.9276 -0.0967 -0.3608 +vn 1.0000 0.0000 -0.0061 +vn 1.0000 0.0005 -0.0009 +vn -0.0737 0.9911 -0.1106 +vn -0.1013 0.9740 -0.2024 +vn -0.1826 0.9131 -0.3646 +vn -0.2681 0.8741 -0.4050 +vn -0.2698 0.8736 -0.4049 +vn -0.9299 -0.0795 -0.3591 +vn -0.9300 -0.1240 -0.3460 +vn -0.9193 -0.1569 -0.3610 +vn -0.7090 0.0010 -0.7052 +usemtl None +s off +f 99/1/1 67/2/1 122/3/1 +f 6/4/1 5/5/1 7/6/1 +f 6/4/1 7/6/1 10/7/1 +f 5/5/1 6/4/1 12/8/1 +f 7/6/1 5/5/1 13/9/1 +f 8/10/2 9/11/2 14/12/2 +f 14/12/2 9/11/2 15/13/2 +f 8/10/2 14/12/2 16/14/2 +f 10/7/1 7/6/1 17/15/1 +f 3/16/3 2/17/3 18/18/3 +f 9/11/2 8/10/2 18/18/2 +f 15/13/2 9/11/2 19/19/2 +f 6/4/1 10/7/1 21/20/1 +f 5/5/1 12/8/1 22/21/1 +f 12/8/1 6/4/1 23/22/1 +f 18/18/2 8/10/2 24/23/2 +f 13/9/1 5/5/1 25/24/1 +f 10/7/1 17/15/1 30/25/1 +f 21/20/1 10/7/1 31/26/1 +f 17/15/1 7/6/1 33/27/1 +f 7/6/1 13/9/1 34/28/1 +f 15/13/2 19/19/2 35/29/2 +f 12/8/1 23/22/1 37/30/1 +f 5/5/1 22/21/1 39/31/1 +f 7/6/1 34/28/1 40/32/1 +f 9/11/4 18/18/4 41/33/4 +f 25/24/1 5/5/1 42/34/1 +f 6/4/1 21/20/1 43/35/1 +f 11/36/5 15/13/5 44/37/5 +f 26/38/6 11/36/6 44/37/6 +f 15/13/2 35/29/2 44/37/2 +f 35/29/7 26/38/7 44/37/7 +f 33/27/1 7/6/1 45/39/1 +f 22/21/1 12/8/1 46/40/1 +f 19/19/8 9/11/8 52/41/8 +f 11/36/9 26/38/9 54/42/9 +f 21/20/1 31/26/1 56/43/1 +f 18/18/10 2/17/10 58/44/10 +f 16/14/11 28/45/11 59/46/11 +f 57/47/12 16/14/12 59/46/12 +f 43/35/13 57/47/13 59/46/13 +f 15/13/14 27/48/14 60/49/14 +f 29/50/15 20/51/15 61/52/15 +f 32/53/16 35/29/16 61/52/16 +f 35/29/17 19/19/17 62/54/17 +f 37/30/1 23/22/1 63/55/1 +f 64/56/18 23/22/18 65/57/18 +f 28/45/19 64/56/19 65/57/19 +f 10/7/20 49/58/20 66/59/20 +f 40/32/1 34/28/1 67/2/1 +f 52/41/21 9/11/21 68/60/21 +f 13/9/1 25/24/1 69/61/1 +f 24/23/22 8/10/22 70/62/22 +f 66/59/23 24/23/23 70/62/23 +f 66/59/24 70/62/24 71/63/24 +f 31/26/1 10/7/1 71/63/1 +f 10/7/25 66/59/25 71/63/25 +f 70/62/26 31/26/26 71/63/26 +f 42/34/1 5/5/1 72/64/1 +f 5/5/27 53/65/27 72/64/27 +f 15/13/28 11/36/28 73/66/28 +f 11/36/29 27/48/29 73/66/29 +f 27/48/30 15/13/30 73/66/30 +f 27/48/31 11/36/31 74/67/31 +f 53/65/32 5/5/32 74/67/32 +f 5/5/33 39/31/33 75/68/33 +f 74/67/34 5/5/34 75/68/34 +f 27/48/35 74/67/35 75/68/35 +f 36/69/36 15/13/36 76/70/36 +f 15/13/37 60/49/37 76/70/37 +f 60/49/38 22/21/38 76/70/38 +f 16/14/39 14/12/39 77/71/39 +f 28/45/40 16/14/40 77/71/40 +f 14/12/41 51/72/41 77/71/41 +f 3/16/42 18/18/42 78/73/42 +f 24/23/43 3/16/43 78/73/43 +f 18/18/44 24/23/44 78/73/44 +f 9/11/45 41/33/45 79/74/45 +f 41/33/46 33/27/46 79/74/46 +f 68/60/47 9/11/47 79/74/47 +f 13/9/48 4/75/48 80/76/48 +f 34/28/1 13/9/1 80/76/1 +f 6/4/49 59/46/49 81/77/49 +f 59/46/50 28/45/50 81/77/50 +f 11/36/51 54/42/51 82/78/51 +f 42/34/52 72/64/52 82/78/52 +f 72/64/53 53/65/53 82/78/53 +f 74/67/54 11/36/54 82/78/54 +f 53/65/55 74/67/55 82/78/55 +f 56/43/56 31/26/56 83/79/56 +f 70/62/57 8/10/57 83/79/57 +f 31/26/58 70/62/58 83/79/58 +f 4/75/59 32/53/59 84/80/59 +f 32/53/60 61/52/60 84/80/60 +f 80/76/61 4/75/61 84/80/61 +f 34/28/62 80/76/62 84/80/62 +f 75/68/63 39/31/63 85/81/63 +f 27/48/64 75/68/64 85/81/64 +f 14/12/2 15/13/2 86/82/2 +f 15/13/65 36/69/65 86/82/65 +f 1/83/66 55/84/66 86/82/66 +f 55/84/67 14/12/67 86/82/67 +f 51/72/41 14/12/41 87/85/41 +f 14/12/68 55/84/68 87/85/68 +f 55/84/69 37/30/69 87/85/69 +f 37/30/70 63/55/70 87/85/70 +f 22/21/1 46/40/1 88/86/1 +f 46/40/71 36/69/71 88/86/71 +f 36/69/72 76/70/72 88/86/72 +f 76/70/73 22/21/73 88/86/73 +f 30/25/1 17/15/1 90/87/1 +f 17/15/74 58/44/74 90/87/74 +f 26/38/75 48/88/75 91/89/75 +f 25/24/76 54/42/76 91/89/76 +f 54/42/77 26/38/77 91/89/77 +f 69/61/78 25/24/78 91/89/78 +f 2/17/79 3/16/79 92/90/79 +f 3/16/80 24/23/80 92/90/80 +f 47/91/81 2/17/81 92/90/81 +f 24/23/82 66/59/82 92/90/82 +f 66/59/83 49/58/83 92/90/83 +f 10/7/1 30/25/1 93/92/1 +f 2/17/84 47/91/84 93/92/84 +f 89/93/85 2/17/85 93/92/85 +f 30/25/86 89/93/86 93/92/86 +f 23/22/87 51/72/87 94/94/87 +f 63/55/1 23/22/1 94/94/1 +f 51/72/88 87/85/88 94/94/88 +f 87/85/89 63/55/89 94/94/89 +f 33/27/1 45/39/1 95/95/1 +f 79/74/90 33/27/90 95/95/90 +f 68/60/91 79/74/91 95/95/91 +f 13/9/1 69/61/1 96/96/1 +f 91/89/92 48/88/92 96/96/92 +f 69/61/93 91/89/93 96/96/93 +f 6/4/1 43/35/1 97/97/1 +f 59/46/94 6/4/94 97/97/94 +f 43/35/95 59/46/95 97/97/95 +f 29/50/96 61/52/96 98/98/96 +f 61/52/97 35/29/97 98/98/97 +f 35/29/17 62/54/17 98/98/17 +f 62/54/98 40/32/98 98/98/98 +f 20/51/99 29/50/99 99/1/99 +f 40/32/1 67/2/1 99/1/1 +f 29/50/100 98/98/100 99/1/100 +f 98/98/101 40/32/101 99/1/101 +f 4/75/102 13/9/102 100/99/102 +f 13/9/103 96/96/103 100/99/103 +f 96/96/104 48/88/104 100/99/104 +f 41/33/105 18/18/105 101/100/105 +f 18/18/106 58/44/106 101/100/106 +f 58/44/107 17/15/107 101/100/107 +f 38/101/108 21/20/108 102/102/108 +f 21/20/109 56/43/109 102/102/109 +f 83/79/110 8/10/110 102/102/110 +f 56/43/111 83/79/111 102/102/111 +f 19/19/112 52/41/112 103/103/112 +f 62/54/17 19/19/17 103/103/17 +f 12/8/113 1/83/113 104/104/113 +f 46/40/114 12/8/114 104/104/114 +f 36/69/115 46/40/115 104/104/115 +f 1/83/116 86/82/116 104/104/116 +f 86/82/117 36/69/117 104/104/117 +f 21/20/118 38/101/118 105/105/118 +f 43/35/119 21/20/119 105/105/119 +f 38/101/120 57/47/120 105/105/120 +f 57/47/121 43/35/121 105/105/121 +f 45/39/122 52/41/122 106/106/122 +f 52/41/123 68/60/123 106/106/123 +f 95/95/124 45/39/124 106/106/124 +f 68/60/125 95/95/125 106/106/125 +f 25/24/1 42/34/1 107/107/1 +f 54/42/126 25/24/126 107/107/126 +f 82/78/127 54/42/127 107/107/127 +f 42/34/128 82/78/128 107/107/128 +f 23/22/1 6/4/1 108/108/1 +f 65/57/129 23/22/129 108/108/129 +f 28/45/130 65/57/130 108/108/130 +f 6/4/131 81/77/131 108/108/131 +f 81/77/132 28/45/132 108/108/132 +f 32/53/133 4/75/133 109/109/133 +f 26/38/134 35/29/134 109/109/134 +f 35/29/135 32/53/135 109/109/135 +f 48/88/136 26/38/136 109/109/136 +f 4/75/137 100/99/137 109/109/137 +f 100/99/138 48/88/138 109/109/138 +f 1/83/139 12/8/139 110/110/139 +f 55/84/140 1/83/140 110/110/140 +f 55/84/141 110/110/141 111/111/141 +f 12/8/1 37/30/1 111/111/1 +f 37/30/142 55/84/142 111/111/142 +f 110/110/143 12/8/143 111/111/143 +f 61/52/144 50/112/144 112/113/144 +f 67/2/145 34/28/145 112/113/145 +f 50/112/146 67/2/146 112/113/146 +f 84/80/147 61/52/147 112/113/147 +f 34/28/148 84/80/148 112/113/148 +f 7/6/1 40/32/1 113/114/1 +f 40/32/149 62/54/149 113/114/149 +f 103/103/150 7/6/150 113/114/150 +f 62/54/151 103/103/151 113/114/151 +f 49/58/152 10/7/152 114/115/152 +f 47/91/153 92/90/153 114/115/153 +f 92/90/154 49/58/154 114/115/154 +f 10/7/1 93/92/1 114/115/1 +f 93/92/155 47/91/155 114/115/155 +f 17/15/1 33/27/1 115/116/1 +f 33/27/156 41/33/156 115/116/156 +f 41/33/157 101/100/157 115/116/157 +f 101/100/158 17/15/158 115/116/158 +f 45/39/1 7/6/1 116/117/1 +f 52/41/159 45/39/159 116/117/159 +f 7/6/160 103/103/160 116/117/160 +f 103/103/161 52/41/161 116/117/161 +f 39/31/1 22/21/1 117/118/1 +f 22/21/162 60/49/162 117/118/162 +f 8/10/2 16/14/2 118/119/2 +f 16/14/163 57/47/163 118/119/163 +f 57/47/164 38/101/164 118/119/164 +f 102/102/165 8/10/165 118/119/165 +f 38/101/166 102/102/166 118/119/166 +f 60/49/167 27/48/167 119/120/167 +f 27/48/168 85/81/168 119/120/168 +f 85/81/169 39/31/169 119/120/169 +f 39/31/170 117/118/170 119/120/170 +f 117/118/171 60/49/171 119/120/171 +f 51/72/172 23/22/172 120/121/172 +f 23/22/173 64/56/173 120/121/173 +f 64/56/174 28/45/174 120/121/174 +f 28/45/175 77/71/175 120/121/175 +f 77/71/41 51/72/41 120/121/41 +f 58/44/176 2/17/176 121/122/176 +f 2/17/177 89/93/177 121/122/177 +f 89/93/178 30/25/178 121/122/178 +f 30/25/179 90/87/179 121/122/179 +f 90/87/180 58/44/180 121/122/180 +f 61/52/181 20/51/181 122/3/181 +f 50/112/182 61/52/182 122/3/182 +f 67/2/183 50/112/183 122/3/183 +f 20/51/184 99/1/184 122/3/184 +o Bowl_hull_2 +v 0.033184 -0.043115 -0.001496 +v 0.021546 -0.080619 0.050235 +v 0.021115 -0.080619 0.050235 +v 0.039651 -0.068111 0.049366 +v 0.021115 -0.040100 -0.009251 +v 0.039651 -0.040100 0.010149 +v 0.021115 -0.076305 0.049794 +v 0.040082 -0.072857 0.048938 +v 0.021546 -0.040100 -0.017020 +v 0.040082 -0.040100 0.002816 +v 0.030600 -0.077600 0.049366 +v 0.040082 -0.058200 0.026950 +v 0.021115 -0.057343 0.010584 +v 0.040082 -0.068977 0.050235 +v 0.040082 -0.039667 0.009280 +v 0.021115 -0.039667 -0.017020 +v 0.021979 -0.078891 0.046785 +v 0.034478 -0.075439 0.048503 +v 0.040082 -0.073286 0.050235 +v 0.024996 -0.040100 -0.013991 +v 0.021979 -0.056914 0.010149 +v 0.040082 -0.050876 0.016608 +v 0.034911 -0.039667 -0.003649 +v 0.021115 -0.039667 -0.010114 +v 0.040082 -0.066387 0.039023 +v 0.034911 -0.040096 -0.003649 +v 0.038359 -0.073286 0.048075 +v 0.021979 -0.050010 -0.001055 +v 0.024132 -0.079320 0.048510 +v 0.021979 -0.076305 0.050235 +v 0.040082 -0.041391 0.004113 +v 0.021979 -0.065529 0.024363 +v 0.028013 -0.041395 -0.009251 +v 0.021115 -0.079753 0.048075 +v 0.039651 -0.039667 0.001953 +v 0.022409 -0.046562 -0.006230 +v 0.028013 -0.076734 0.046351 +v 0.034048 -0.076305 0.050235 +vt 0.980717 0.810475 +vt 1.000000 0.820950 +vt 1.000000 0.894665 +vt 0.115505 0.010573 +vt 1.000000 1.000000 +vt 0.993442 0.894665 +vt 0.403974 0.010573 +vt 0.987079 0.694567 +vt 0.294930 0.010573 +vt 0.653778 0.452570 +vt 0.410435 0.431620 +vt 1.000000 1.000000 +vt 1.000000 0.715712 +vt 0.391053 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.010573 +vt 0.045027 0.010573 +vt 0.230814 0.084190 +vt 0.500000 0.273715 +vt 0.198806 0.000000 +vt 0.102682 0.000000 +vt 0.833301 0.652472 +vt 0.198806 0.010475 +vt 0.974256 0.873519 +vt 0.967893 0.820950 +vt 0.237373 0.252570 +vt 0.987079 0.926285 +vt 0.403974 0.421145 +vt 0.974354 0.968282 +vt 1.000000 0.894665 +vt 0.314213 0.042095 +vt 0.615309 0.631522 +vt 0.948708 0.957807 +vt 0.115505 0.042193 +vt 0.967893 0.978855 +vt 0.282106 0.000000 +vt 0.160435 0.168380 +vt 0.942247 0.905140 +vn 0.4290 -0.8576 -0.2837 +vn -1.0000 -0.0000 0.0000 +vn -0.4800 0.7479 0.4586 +vn -0.3273 0.7689 0.5492 +vn 1.0000 -0.0000 0.0000 +vn 0.0000 -0.0000 1.0000 +vn 0.3342 0.7669 0.5478 +vn 0.4184 0.7386 0.5286 +vn -0.6461 -0.6428 -0.4116 +vn 0.5515 0.5487 -0.6283 +vn 0.5136 -0.7002 -0.4959 +vn 0.0000 1.0000 -0.0000 +vn 0.4422 0.7722 -0.4563 +vn -0.4251 0.8089 0.4061 +vn -0.3056 0.9040 0.2989 +vn 0.4357 -0.7509 -0.4963 +vn 0.5513 -0.6699 -0.4973 +vn 0.7219 0.0000 -0.6920 +vn 0.4078 -0.8164 -0.4088 +vn 0.4342 -0.7544 -0.4923 +vn 0.4258 -0.7569 -0.4958 +vn 0.0769 -0.8462 -0.5274 +vn 0.3360 -0.8009 -0.4957 +vn 0.1571 -0.8408 -0.5180 +vn 0.3247 -0.8053 -0.4961 +vn 0.2808 -0.9204 -0.2721 +vn -0.4531 0.0907 0.8869 +vn -0.3098 0.7324 0.6064 +vn -0.2512 0.6205 0.7429 +vn 0.5779 -0.6500 -0.4935 +vn 0.6612 -0.5317 -0.5292 +vn 0.1619 -0.8439 -0.5115 +vn 0.2323 -0.8355 -0.4979 +vn 0.5106 -0.7022 -0.4962 +vn 0.4689 -0.7311 -0.4957 +vn 0.4642 -0.7338 -0.4960 +vn 0.5394 -0.6712 -0.5085 +vn 0.5501 -0.6477 -0.5271 +vn 0.0000 -0.9281 -0.3722 +vn 0.1862 -0.8985 -0.3975 +vn 0.1903 -0.8704 -0.4541 +vn 0.0494 -0.8573 -0.5124 +vn 0.0922 -0.8554 -0.5097 +vn 0.7508 0.6591 -0.0441 +vn 0.7072 -0.4237 -0.5660 +vn 0.7634 0.0000 -0.6459 +vn 0.3788 -0.7814 -0.4958 +vn 0.3882 -0.7766 -0.4962 +vn 0.3293 -0.7982 -0.5044 +vn 0.3606 -0.7898 -0.4962 +vn 0.3061 -0.8126 -0.4959 +vn 0.2842 -0.8289 -0.4819 +vn 0.2881 -0.8189 -0.4964 +vn 0.2738 -0.8245 -0.4953 +vn 0.3241 -0.9392 0.1137 +vn 0.4167 -0.8503 -0.3216 +vn 0.4034 -0.8546 -0.3271 +usemtl None +s off +f 130/123/185 141/124/185 160/125/185 +f 127/126/186 125/127/186 129/128/186 +f 128/129/187 127/126/187 129/128/187 +f 126/130/188 128/129/188 129/128/188 +f 132/131/189 130/123/189 134/132/189 +f 125/127/186 127/126/186 135/133/186 +f 125/127/190 124/134/190 136/135/190 +f 130/123/189 132/131/189 136/135/189 +f 128/129/191 126/130/191 137/136/191 +f 126/130/192 136/135/192 137/136/192 +f 136/135/189 132/131/189 137/136/189 +f 135/133/186 127/126/186 138/137/186 +f 131/138/193 135/133/193 138/137/193 +f 136/135/190 124/134/190 141/124/190 +f 130/123/189 136/135/189 141/124/189 +f 131/138/194 138/137/194 142/139/194 +f 134/132/195 123/140/195 144/141/195 +f 132/131/189 134/132/189 144/141/189 +f 138/137/196 137/136/196 145/142/196 +f 142/139/197 138/137/197 145/142/197 +f 127/126/198 128/129/198 146/143/198 +f 128/129/199 137/136/199 146/143/199 +f 138/137/186 127/126/186 146/143/186 +f 137/136/196 138/137/196 146/143/196 +f 134/132/189 130/123/189 147/144/189 +f 131/138/200 142/139/200 147/144/200 +f 144/141/201 123/140/201 148/145/201 +f 142/139/202 145/142/202 148/145/202 +f 130/123/203 140/146/203 149/147/203 +f 147/144/204 130/123/204 149/147/204 +f 131/138/205 147/144/205 149/147/205 +f 135/133/206 131/138/206 150/148/206 +f 140/146/207 133/149/207 150/148/207 +f 143/150/208 135/133/208 150/148/208 +f 133/149/209 143/150/209 150/148/209 +f 133/149/210 124/134/210 151/151/210 +f 129/128/211 125/127/211 152/152/211 +f 126/130/212 129/128/212 152/152/212 +f 125/127/190 136/135/190 152/152/190 +f 136/135/213 126/130/213 152/152/213 +f 132/131/189 144/141/189 153/153/189 +f 144/141/214 148/145/214 153/153/214 +f 148/145/215 132/131/215 153/153/215 +f 135/133/216 143/150/216 154/154/216 +f 151/151/217 139/155/217 154/154/217 +f 123/140/218 134/132/218 155/156/218 +f 134/132/219 147/144/219 155/156/219 +f 147/144/220 142/139/220 155/156/220 +f 148/145/221 123/140/221 155/156/221 +f 142/139/222 148/145/222 155/156/222 +f 124/134/223 125/127/223 156/157/223 +f 125/127/186 135/133/186 156/157/186 +f 151/151/224 124/134/224 156/157/224 +f 139/155/225 151/151/225 156/157/225 +f 135/133/226 154/154/226 156/157/226 +f 154/154/227 139/155/227 156/157/227 +f 137/136/228 132/131/228 157/158/228 +f 145/142/196 137/136/196 157/158/196 +f 132/131/229 148/145/229 157/158/229 +f 148/145/230 145/142/230 157/158/230 +f 149/147/231 140/146/231 158/159/231 +f 131/138/232 149/147/232 158/159/232 +f 150/148/233 131/138/233 158/159/233 +f 140/146/234 150/148/234 158/159/234 +f 143/150/235 133/149/235 159/160/235 +f 133/149/236 151/151/236 159/160/236 +f 154/154/237 143/150/237 159/160/237 +f 151/151/238 154/154/238 159/160/238 +f 124/134/239 133/149/239 160/125/239 +f 140/146/240 130/123/240 160/125/240 +f 133/149/241 140/146/241 160/125/241 +f 141/124/190 124/134/190 160/125/190 +o Bowl_hull_3 +v 0.071125 -0.028888 0.037727 +v 0.040084 -0.026731 -0.010980 +v 0.040517 -0.026731 -0.010980 +v 0.040084 -0.043972 0.007990 +v 0.074570 -0.026731 0.049801 +v 0.070263 -0.043972 0.048507 +v 0.040084 -0.043540 0.014887 +v 0.040517 -0.026731 -0.003652 +v 0.065948 -0.043972 0.049801 +v 0.078884 -0.026731 0.049801 +v 0.050000 -0.042678 0.018332 +v 0.042241 -0.027163 -0.008823 +v 0.074141 -0.036644 0.048075 +v 0.040950 -0.032766 -0.004946 +v 0.071550 -0.043110 0.050232 +v 0.052158 -0.027163 0.006264 +v 0.065086 -0.043972 0.040747 +v 0.065948 -0.043540 0.049801 +v 0.074570 -0.027163 0.050232 +v 0.071983 -0.042247 0.049369 +v 0.042674 -0.043972 0.010572 +v 0.040084 -0.043972 0.014887 +v 0.076727 -0.032766 0.049369 +v 0.072846 -0.026731 0.047212 +v 0.040084 -0.026731 -0.004515 +v 0.077156 -0.027593 0.046781 +v 0.055606 -0.043972 0.027380 +v 0.040517 -0.036644 -0.001064 +v 0.066381 -0.043972 0.050232 +v 0.058193 -0.027163 0.015749 +v 0.078884 -0.027163 0.050232 +v 0.040084 -0.043110 0.014455 +v 0.064657 -0.026731 0.026091 +v 0.041379 -0.029749 -0.007529 +v 0.051296 -0.029318 0.006696 +v 0.056036 -0.042247 0.026091 +v 0.068968 -0.034921 0.038590 +v 0.040084 -0.034059 -0.004083 +vt 0.098571 0.022318 +vt 0.162001 0.011159 +vt 0.112666 0.000000 +vt 0.000000 0.011159 +vt 0.000000 0.000000 +vt 0.992952 0.888802 +vt 0.309906 0.000000 +vt 0.422572 0.000000 +vt 0.119714 0.011159 +vt 0.971809 0.777800 +vt 0.992952 0.666601 +vt 0.992952 1.000000 +vt 0.035239 0.055599 +vt 0.281715 0.311179 +vt 0.845047 0.644381 +vt 0.992952 0.666601 +vt 1.000000 0.888802 +vt 1.000000 0.810983 +vt 0.985904 0.822142 +vt 0.352095 0.066758 +vt 0.422572 0.000000 +vt 0.964761 0.877741 +vt 0.985904 0.944401 +vt 0.950666 0.844362 +vt 0.105619 0.000000 +vt 0.795713 0.800020 +vt 0.943618 0.955462 +vt 0.478857 0.255579 +vt 0.626664 0.400059 +vt 1.000000 0.677760 +vt 0.436668 0.466719 +vt 1.000000 1.000000 +vt 0.415525 0.000000 +vt 0.605619 0.633320 +vt 0.056382 0.033379 +vt 0.288763 0.288959 +vt 0.605619 0.411120 +vt 0.809808 0.744420 +vn 0.3783 -0.6757 -0.6327 +vn 0.0000 1.0000 0.0000 +vn -1.0000 -0.0000 0.0000 +vn 0.0000 -1.0000 -0.0000 +vn 0.7188 0.5100 -0.4725 +vn -0.8035 0.0000 0.5953 +vn -0.7277 0.4847 0.4854 +vn 0.0000 0.7066 0.7076 +vn -0.7442 0.3772 0.5513 +vn 0.7450 -0.6201 -0.2460 +vn 0.7282 -0.4834 -0.4858 +vn 0.7352 -0.4624 -0.4956 +vn 0.8166 -0.4086 -0.4077 +vn 0.8943 -0.4474 0.0016 +vn 0.8101 -0.3147 -0.4947 +vn 0.8656 -0.2797 -0.4154 +vn 0.6729 -0.5493 -0.4955 +vn 0.6098 -0.6387 -0.4692 +vn 0.6536 -0.5707 -0.4971 +vn 0.5205 -0.6757 -0.5220 +vn 0.6294 -0.5996 -0.4943 +vn 0.1543 -0.9250 0.3471 +vn -0.7058 0.0000 0.7084 +vn 0.0000 -0.0000 1.0000 +vn -0.5375 0.2618 0.8016 +vn 0.7997 -0.3367 -0.4970 +vn 0.7898 -0.3613 -0.4956 +vn 0.8158 -0.2864 -0.5025 +vn 0.9043 -0.3017 -0.3021 +vn 0.8310 -0.3822 0.4041 +vn -0.7274 0.4858 0.4846 +vn -0.7274 0.4859 0.4846 +vn -0.7188 0.5241 0.4568 +vn -0.7931 0.4610 0.3980 +vn 0.6549 0.6240 -0.4264 +vn 0.8545 0.0833 -0.5128 +vn 0.8229 0.2209 -0.5236 +vn 0.8332 -0.2089 -0.5120 +vn 0.6212 -0.5065 -0.5980 +vn 0.4381 -0.6196 -0.6512 +vn 0.7180 -0.4879 -0.4964 +vn 0.7637 -0.4060 -0.5020 +vn 0.7441 -0.4473 -0.4962 +vn 0.6806 -0.5395 -0.4956 +vn 0.6886 -0.5361 -0.4883 +vn 0.6925 -0.5234 -0.4965 +vn 0.7066 -0.5050 -0.4958 +vn 0.7676 -0.4094 -0.4930 +vn 0.7810 -0.3783 -0.4969 +vn 0.7871 -0.3668 -0.4959 +vn 0.7671 -0.4063 -0.4964 +vn 0.7628 -0.4152 -0.4956 +vn 0.0000 -0.6853 -0.7282 +vn 0.3066 -0.6619 -0.6840 +vn -0.1858 -0.7594 -0.6235 +usemtl None +s off +f 174/161/242 188/162/242 198/163/242 +f 163/164/243 162/165/243 165/166/243 +f 162/165/244 164/167/244 167/168/244 +f 165/166/243 162/165/243 168/169/243 +f 164/167/245 166/170/245 169/171/245 +f 163/164/243 165/166/243 170/172/243 +f 172/173/246 163/164/246 176/174/246 +f 166/170/245 164/167/245 177/175/245 +f 167/168/247 169/171/247 178/176/247 +f 165/166/248 167/168/248 179/177/248 +f 170/172/249 165/166/249 179/177/249 +f 167/168/250 178/176/250 179/177/250 +f 175/178/251 166/170/251 180/179/251 +f 166/170/252 177/175/252 180/179/252 +f 177/175/253 172/173/253 180/179/253 +f 177/175/245 164/167/245 181/180/245 +f 167/168/244 164/167/244 182/181/244 +f 164/167/245 169/171/245 182/181/245 +f 169/171/247 167/168/247 182/181/247 +f 180/179/254 173/182/254 183/183/254 +f 175/178/255 180/179/255 183/183/255 +f 165/166/243 168/169/243 184/184/243 +f 162/165/244 167/168/244 185/185/244 +f 168/169/243 162/165/243 185/185/243 +f 183/183/256 161/186/256 186/187/256 +f 170/172/257 183/183/257 186/187/257 +f 171/188/258 174/161/258 187/189/258 +f 181/180/259 171/188/259 187/189/259 +f 177/175/245 181/180/245 187/189/245 +f 174/161/260 171/188/260 188/162/260 +f 181/180/261 164/167/261 188/162/261 +f 171/188/262 181/180/262 188/162/262 +f 169/171/245 166/170/245 189/190/245 +f 166/170/263 175/178/263 189/190/263 +f 178/176/264 169/171/264 189/190/264 +f 175/178/265 179/177/265 189/190/265 +f 179/177/266 178/176/266 189/190/266 +f 161/186/267 183/183/267 190/191/267 +f 183/183/268 173/182/268 190/191/268 +f 186/187/269 161/186/269 190/191/269 +f 179/177/265 175/178/265 191/192/265 +f 170/172/249 179/177/249 191/192/249 +f 183/183/270 170/172/270 191/192/270 +f 175/178/271 183/183/271 191/192/271 +f 167/168/272 165/166/272 192/193/272 +f 165/166/273 184/184/273 192/193/273 +f 184/184/274 168/169/274 192/193/274 +f 185/185/244 167/168/244 192/193/244 +f 168/169/275 185/185/275 192/193/275 +f 163/164/243 170/172/243 193/194/243 +f 176/174/276 163/164/276 193/194/276 +f 170/172/277 186/187/277 193/194/277 +f 190/191/278 176/174/278 193/194/278 +f 186/187/279 190/191/279 193/194/279 +f 163/164/280 172/173/280 194/195/280 +f 174/161/281 163/164/281 194/195/281 +f 172/173/282 177/175/282 194/195/282 +f 172/173/283 176/174/283 195/196/283 +f 180/179/284 172/173/284 195/196/284 +f 187/189/285 174/161/285 196/197/285 +f 177/175/286 187/189/286 196/197/286 +f 174/161/287 194/195/287 196/197/287 +f 194/195/288 177/175/288 196/197/288 +f 173/182/289 180/179/289 197/198/289 +f 176/174/290 190/191/290 197/198/290 +f 190/191/291 173/182/291 197/198/291 +f 195/196/292 176/174/292 197/198/292 +f 180/179/293 195/196/293 197/198/293 +f 162/165/294 163/164/294 198/163/294 +f 164/167/244 162/165/244 198/163/244 +f 163/164/295 174/161/295 198/163/295 +f 188/162/296 164/167/296 198/163/296 +o Bowl_hull_4 +v -0.022432 -0.027589 -0.050212 +v -0.014237 -0.034487 -0.033402 +v -0.014669 -0.034487 -0.033402 +v -0.030618 -0.011640 -0.033404 +v -0.014237 -0.029314 -0.050212 +v -0.029756 -0.022850 -0.033404 +v -0.033205 -0.011640 -0.050212 +v -0.014237 -0.029314 -0.033402 +v -0.035362 -0.012074 -0.033404 +v -0.030618 -0.011640 -0.050212 +v -0.030618 -0.018108 -0.050212 +v -0.014669 -0.032333 -0.050212 +v -0.022860 -0.029746 -0.033835 +v -0.025874 -0.024570 -0.049352 +v -0.033637 -0.016386 -0.034266 +v -0.018118 -0.030607 -0.050212 +v -0.032775 -0.013799 -0.050212 +v -0.025444 -0.027589 -0.033835 +v -0.018980 -0.032333 -0.033835 +v -0.035362 -0.011640 -0.034266 +v -0.028029 -0.021991 -0.049783 +v -0.031480 -0.020265 -0.034266 +v -0.027601 -0.025433 -0.033835 +v -0.014237 -0.032333 -0.050212 +v -0.030186 -0.012074 -0.033404 +v -0.020273 -0.029314 -0.049783 +v -0.034499 -0.014662 -0.033835 +v -0.022860 -0.029746 -0.033404 +vt 0.603720 0.367365 +vt 0.698091 0.469460 +vt 0.792462 0.591817 +vt 0.773568 1.000000 +vt 0.698091 0.612079 +vt 0.000000 0.102095 +vt 1.000000 0.979542 +vt 1.000000 1.000000 +vt 0.773568 1.000000 +vt 0.490651 0.265368 +vt 0.018992 0.000000 +vt 0.000000 0.224550 +vt 0.000000 0.224550 +vt 0.283113 0.224550 +vt 0.905727 0.979542 +vt 0.830152 0.816269 +vt 0.094469 0.122455 +vt 0.207734 0.081637 +vt 0.792462 0.591817 +vt 0.565932 0.449099 +vt 0.905727 0.775450 +vt 0.000000 0.000000 +vt 0.453059 0.347103 +vt 0.377484 0.183731 +vt 0.905727 1.000000 +vt 0.018992 0.245008 +vt 0.773568 0.714272 +vt 0.132256 0.040818 +vn -0.5787 -0.5789 0.5745 +vn 0.0000 -0.0000 -1.0000 +vn 0.0000 0.0000 1.0000 +vn 1.0000 0.0000 0.0000 +vn -0.0002 -0.0001 1.0000 +vn -0.0001 0.0000 1.0000 +vn -0.0000 0.0001 1.0000 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -0.9919 -0.1271 +vn -0.8878 -0.4443 -0.1201 +vn -0.6362 -0.7626 -0.1170 +vn -0.6716 -0.7306 -0.1235 +vn -0.4348 -0.8932 -0.1144 +vn -0.4446 -0.8881 -0.1170 +vn -0.0814 0.8903 0.4480 +vn -0.9722 -0.1937 -0.1315 +vn -0.9619 -0.2444 -0.1230 +vn -0.4514 -0.3898 -0.8027 +vn -0.6519 -0.6181 -0.4393 +vn -0.8684 -0.4829 -0.1123 +vn -0.8198 -0.5599 -0.1200 +vn -0.8081 -0.5776 -0.1155 +vn -0.7021 -0.7023 -0.1172 +vn -0.7722 -0.6250 -0.1142 +vn -0.7519 -0.6483 -0.1197 +vn 0.0013 0.0013 1.0000 +vn 0.7341 0.6791 0.0000 +vn 0.7085 0.7057 0.0000 +vn 0.7334 0.6798 -0.0013 +vn -0.6050 -0.7872 -0.1194 +vn -0.5305 -0.7584 -0.3786 +vn -0.5515 -0.8267 -0.1118 +vn -0.5280 -0.8412 -0.1165 +vn -0.6287 -0.3270 0.7056 +vn -0.9480 -0.2966 -0.1155 +vn -0.8997 -0.4206 -0.1169 +vn -0.8409 -0.4733 0.2625 +vn -0.8576 -0.4769 0.1923 +vn -0.0005 -0.0005 1.0000 +vn -0.6405 -0.7679 0.0000 +vn -0.4134 -0.7138 0.5653 +vn -0.5549 -0.8319 0.0000 +vn -0.5783 -0.5784 0.5753 +usemtl None +s off +f 221/199/297 216/200/297 226/201/297 +f 203/202/298 199/203/298 205/204/298 +f 201/205/299 200/206/299 206/207/299 +f 200/206/300 203/202/300 206/207/300 +f 204/208/301 201/205/301 207/209/301 +f 201/205/302 206/207/302 207/209/302 +f 206/207/303 202/210/303 207/209/303 +f 205/204/304 202/210/304 208/211/304 +f 203/202/298 205/204/298 208/211/298 +f 205/204/298 199/203/298 209/212/298 +f 200/206/305 201/205/305 210/213/305 +f 199/203/298 203/202/298 210/213/298 +f 199/203/298 210/213/298 214/214/298 +f 205/204/298 209/212/298 215/215/298 +f 209/212/306 213/216/306 215/215/306 +f 199/203/307 211/217/307 216/200/307 +f 212/218/308 199/203/308 216/200/308 +f 210/213/309 201/205/309 217/219/309 +f 214/214/310 210/213/310 217/219/310 +f 202/210/304 205/204/304 218/220/304 +f 207/209/311 202/210/311 218/220/311 +f 205/204/312 215/215/312 218/220/312 +f 215/215/313 207/209/313 218/220/313 +f 209/212/314 199/203/314 219/221/314 +f 199/203/315 212/218/315 219/221/315 +f 213/216/316 209/212/316 220/222/316 +f 209/212/317 219/221/317 220/222/317 +f 219/221/318 204/208/318 220/222/318 +f 212/218/319 216/200/319 221/199/319 +f 204/208/320 219/221/320 221/199/320 +f 219/221/321 212/218/321 221/199/321 +f 203/202/300 200/206/300 222/223/300 +f 200/206/305 210/213/305 222/223/305 +f 210/213/298 203/202/298 222/223/298 +f 202/210/322 206/207/322 223/224/322 +f 206/207/323 203/202/323 223/224/323 +f 208/211/324 202/210/324 223/224/324 +f 203/202/325 208/211/325 223/224/325 +f 211/217/326 199/203/326 224/225/326 +f 199/203/327 214/214/327 224/225/327 +f 217/219/328 211/217/328 224/225/328 +f 214/214/329 217/219/329 224/225/329 +f 204/208/330 207/209/330 225/226/330 +f 207/209/331 215/215/331 225/226/331 +f 215/215/332 213/216/332 225/226/332 +f 220/222/333 204/208/333 225/226/333 +f 213/216/334 220/222/334 225/226/334 +f 201/205/335 204/208/335 226/201/335 +f 216/200/336 211/217/336 226/201/336 +f 217/219/337 201/205/337 226/201/337 +f 211/217/338 217/219/338 226/201/338 +f 204/208/339 221/199/339 226/201/339 +o Bowl_hull_5 +v -0.012940 -0.033197 -0.049352 +v 0.005163 -0.036644 -0.033404 +v 0.005163 -0.032335 -0.033404 +v -0.014237 -0.029748 -0.033404 +v 0.005163 -0.032335 -0.050214 +v -0.013373 -0.034920 -0.033404 +v -0.002598 -0.035351 -0.050214 +v -0.014237 -0.029748 -0.050214 +v -0.004749 -0.037075 -0.033835 +v 0.005163 -0.035351 -0.048058 +v -0.014237 -0.032335 -0.050214 +v -0.012940 -0.029748 -0.050214 +v 0.002575 -0.037075 -0.035128 +v -0.008629 -0.034489 -0.049783 +v -0.014237 -0.034489 -0.034697 +v -0.009491 -0.036213 -0.033835 +v -0.012940 -0.029748 -0.033404 +v 0.002575 -0.035351 -0.050214 +v 0.004729 -0.037075 -0.033404 +v -0.000011 -0.037075 -0.035559 +v 0.005163 -0.034920 -0.050214 +v -0.006474 -0.034920 -0.049783 +vt 0.244616 0.974354 +vt 0.289056 0.025646 +vt 0.400157 0.025646 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.044538 1.000000 +vt 0.599941 0.000000 +vt 0.000000 0.000000 +vt 1.000000 0.128230 +vt 0.000000 0.000000 +vt 0.066856 0.000000 +vt 0.066856 0.051292 +vt 0.000000 0.923062 +vt 0.489037 0.974354 +vt 0.066856 1.000000 +vt 0.866582 0.000000 +vt 0.866582 0.897416 +vt 0.977584 1.000000 +vt 0.733262 0.871770 +vt 1.000000 0.000000 +vn -0.1948 -0.9740 -0.1158 +vn 0.0000 0.0000 1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn 0.1414 0.9899 0.0000 +vn 0.0000 1.0000 0.0000 +vn -0.2992 -0.8611 -0.4111 +vn -0.1346 -0.5192 -0.8440 +vn -0.8443 -0.1410 0.5170 +vn -0.4933 -0.8616 -0.1196 +vn -0.1068 -0.5878 0.8019 +vn -0.2959 -0.9478 -0.1185 +vn -0.3215 -0.9403 -0.1114 +vn -0.3243 -0.9410 -0.0970 +vn 0.0905 -0.9895 -0.1131 +vn -0.0425 -0.3566 0.9333 +vn 0.7021 -0.7094 -0.0626 +vn 0.0000 -1.0000 0.0000 +vn 0.0945 -0.9890 -0.1135 +vn -0.0400 -0.9932 -0.1098 +vn 0.0000 -0.9932 -0.1168 +vn 0.0189 -0.9934 -0.1135 +vn 0.1612 -0.9678 -0.1936 +vn -0.1229 -0.9852 -0.1198 +vn -0.1544 -0.7721 -0.6164 +vn -0.1776 -0.9776 -0.1129 +usemtl None +s off +f 242/227/340 240/228/340 248/229/340 +f 228/230/341 229/231/341 230/232/341 +f 229/231/342 228/230/342 231/233/342 +f 228/230/341 230/232/341 232/234/341 +f 231/233/343 233/235/343 234/236/343 +f 231/233/342 228/230/342 236/237/342 +f 230/232/344 234/236/344 237/238/344 +f 234/236/343 233/235/343 237/238/343 +f 229/231/345 231/233/345 238/239/345 +f 234/236/346 230/232/346 238/239/346 +f 231/233/343 234/236/343 238/239/343 +f 227/240/347 237/238/347 240/228/347 +f 237/238/348 233/235/348 240/228/348 +f 232/234/349 230/232/349 241/241/349 +f 237/238/350 227/240/350 241/241/350 +f 230/232/344 237/238/344 241/241/344 +f 235/242/351 232/234/351 242/227/351 +f 227/240/352 240/228/352 242/227/352 +f 241/241/353 227/240/353 242/227/353 +f 232/234/354 241/241/354 242/227/354 +f 230/232/341 229/231/341 243/243/341 +f 229/231/345 238/239/345 243/243/345 +f 238/239/346 230/232/346 243/243/346 +f 233/235/343 231/233/343 244/244/343 +f 239/245/355 244/244/355 245/246/355 +f 228/230/341 232/234/341 245/246/341 +f 232/234/356 235/242/356 245/246/356 +f 236/237/357 228/230/357 245/246/357 +f 235/242/358 239/245/358 245/246/358 +f 244/244/359 236/237/359 245/246/359 +f 235/242/360 233/235/360 246/247/360 +f 239/245/358 235/242/358 246/247/358 +f 233/235/361 244/244/361 246/247/361 +f 244/244/362 239/245/362 246/247/362 +f 231/233/342 236/237/342 247/248/342 +f 244/244/343 231/233/343 247/248/343 +f 236/237/363 244/244/363 247/248/363 +f 233/235/364 235/242/364 248/229/364 +f 240/228/365 233/235/365 248/229/365 +f 235/242/366 242/227/366 248/229/366 +o Bowl_hull_6 +v 0.014650 0.032333 -0.050214 +v 0.029737 0.022419 -0.033404 +v 0.029737 0.022419 -0.033835 +v 0.005163 0.032333 -0.050214 +v 0.005163 0.036644 -0.033404 +v 0.005163 0.032333 -0.033404 +v 0.023697 0.022419 -0.050214 +v 0.018958 0.032333 -0.033404 +v 0.025855 0.024575 -0.049783 +v 0.023697 0.022419 -0.033404 +v 0.005163 0.034918 -0.050214 +v 0.009479 0.036212 -0.033835 +v 0.025422 0.027592 -0.033835 +v 0.020250 0.029317 -0.049783 +v 0.027146 0.022419 -0.050214 +v 0.008613 0.034488 -0.049783 +v 0.014650 0.034488 -0.033835 +v 0.029737 0.022851 -0.033835 +v 0.011632 0.033625 -0.049783 +v 0.022838 0.029746 -0.033835 +v 0.022408 0.027592 -0.050214 +v 0.007321 0.036644 -0.033835 +v 0.017662 0.031039 -0.048921 +v 0.027579 0.025438 -0.033404 +v 0.027579 0.022851 -0.048058 +vt 0.842013 0.025646 +vt 1.000000 0.974354 +vt 0.912197 0.128230 +vt 1.000000 1.000000 +vt 0.000000 1.000000 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 0.754209 0.000000 +vt 1.000000 0.974354 +vt 0.386061 0.000000 +vt 0.561374 1.000000 +vt 0.754209 1.000000 +vt 0.000000 0.000000 +vt 0.175607 0.974354 +vt 0.894577 0.000000 +vt 0.140368 0.025646 +vt 0.386061 0.974354 +vt 0.263215 0.025646 +vt 0.613939 0.025646 +vt 0.719264 0.974354 +vt 0.701742 0.000000 +vt 0.824393 0.974354 +vt 0.087803 0.974354 +vt 0.508614 0.076938 +vt 0.912197 1.000000 +vn 0.7573 0.6428 -0.1149 +vn 0.0000 0.0000 1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.4717 -0.8818 -0.0000 +vn -0.0000 -1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.1318 0.4218 0.8970 +vn 0.1733 0.6359 -0.7521 +vn 0.1689 0.5066 0.8455 +vn 1.0000 0.0000 0.0000 +vn 0.1987 0.6949 -0.6912 +vn 0.2730 0.9547 -0.1180 +vn 0.3143 0.9429 -0.1105 +vn 0.3760 0.9187 -0.1209 +vn 0.5428 0.8325 -0.1105 +vn 0.6053 0.7870 -0.1194 +vn 0.6623 0.7392 -0.1219 +vn 0.4063 0.6648 -0.6268 +vn 0.4796 0.4393 -0.7596 +vn 0.6360 0.7628 -0.1170 +vn -0.0204 0.9946 -0.1021 +vn 0.1400 0.6997 0.7006 +vn 0.1378 0.9830 -0.1217 +vn 0.1948 0.9740 -0.1158 +vn 0.4733 0.8416 -0.2604 +vn 0.5237 0.8442 -0.1141 +vn 0.4341 0.8932 -0.1175 +vn 0.4535 0.8842 -0.1116 +vn 0.7132 0.6921 -0.1116 +vn 0.7031 0.5025 0.5031 +vn 0.7536 0.6475 -0.1135 +vn 0.4563 0.5705 0.6829 +vn 0.5412 0.6491 0.5345 +vn 0.9665 -0.2061 -0.1529 +vn 0.8018 0.5341 -0.2680 +vn 0.9887 0.0000 -0.1500 +usemtl None +s off +f 257/249/367 266/250/367 273/251/367 +f 250/252/368 253/253/368 254/254/368 +f 253/253/369 252/255/369 254/254/369 +f 254/254/370 252/255/370 255/256/370 +f 251/257/371 250/252/371 255/256/371 +f 252/255/372 249/258/372 255/256/372 +f 253/253/368 250/252/368 256/259/368 +f 250/252/368 254/254/368 258/260/368 +f 254/254/370 255/256/370 258/260/370 +f 255/256/371 250/252/371 258/260/371 +f 249/258/372 252/255/372 259/261/372 +f 252/255/369 253/253/369 259/261/369 +f 253/253/373 256/259/373 260/262/373 +f 255/256/372 249/258/372 263/263/372 +f 251/257/371 255/256/371 263/263/371 +f 249/258/374 259/261/374 264/264/374 +f 260/262/375 256/259/375 265/265/375 +f 250/252/376 251/257/376 266/250/376 +f 249/258/377 264/264/377 267/266/377 +f 264/264/378 260/262/378 267/266/378 +f 260/262/379 265/265/379 267/266/379 +f 265/265/380 249/258/380 267/266/380 +f 262/267/381 256/259/381 268/268/381 +f 262/267/382 268/268/382 269/269/382 +f 261/270/383 257/249/383 269/269/383 +f 249/258/384 262/267/384 269/269/384 +f 263/263/372 249/258/372 269/269/372 +f 257/249/385 263/263/385 269/269/385 +f 268/268/386 261/270/386 269/269/386 +f 259/261/387 253/253/387 270/271/387 +f 253/253/388 260/262/388 270/271/388 +f 264/264/389 259/261/389 270/271/389 +f 260/262/390 264/264/390 270/271/390 +f 262/267/391 249/258/391 271/272/391 +f 256/259/392 262/267/392 271/272/392 +f 249/258/393 265/265/393 271/272/393 +f 265/265/394 256/259/394 271/272/394 +f 256/259/368 250/252/368 272/273/368 +f 257/249/395 261/270/395 272/273/395 +f 250/252/396 266/250/396 272/273/396 +f 266/250/397 257/249/397 272/273/397 +f 268/268/398 256/259/398 272/273/398 +f 261/270/399 268/268/399 272/273/399 +f 251/257/400 263/263/400 273/251/400 +f 263/263/401 257/249/401 273/251/401 +f 266/250/402 251/257/402 273/251/402 +o Bowl_hull_7 +v 0.034477 0.009055 -0.048921 +v 0.024133 0.022418 -0.050214 +v 0.027583 0.022418 -0.050214 +v 0.024133 0.022418 -0.033404 +v 0.032323 0.003453 -0.050214 +v 0.036201 0.009488 -0.033404 +v 0.032323 0.003453 -0.033404 +v 0.030599 0.021554 -0.033404 +v 0.037065 0.003018 -0.034697 +v 0.032753 0.013793 -0.050214 +v 0.035339 0.003018 -0.049783 +v 0.032753 0.018104 -0.034266 +v 0.024133 0.021983 -0.033404 +v 0.029738 0.022418 -0.033404 +v 0.030170 0.018968 -0.049783 +v 0.024133 0.021983 -0.050214 +v 0.034477 0.014657 -0.033835 +v 0.032753 0.003018 -0.033404 +v 0.037065 0.004744 -0.033404 +v 0.034909 0.006037 -0.050214 +v 0.032753 0.003018 -0.050214 +v 0.034047 0.010350 -0.049783 +v 0.030599 0.021554 -0.034266 +v 0.031461 0.016812 -0.049352 +v 0.036633 0.006899 -0.034697 +vt 0.911022 1.000000 +vt 0.844362 0.000000 +vt 0.799922 0.923062 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 0.977584 0.000000 +vt 0.666503 1.000000 +vt 0.977584 1.000000 +vt 0.044538 1.000000 +vt 0.444597 0.000000 +vt 0.022416 1.000000 +vt 0.000000 1.000000 +vt 0.177858 0.025646 +vt 0.022416 0.000000 +vt 0.400059 0.974354 +vt 0.222396 0.948708 +vt 1.000000 1.000000 +vt 1.000000 0.025646 +vt 1.000000 0.923062 +vt 1.000000 0.000000 +vt 0.688821 0.076938 +vt 0.622064 0.025646 +vt 0.044538 0.948708 +vt 0.288958 0.051292 +vn 0.9850 0.1273 -0.1165 +vn 0.0000 1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -0.0000 1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.9146 -0.4043 0.0000 +vn 0.5973 0.3580 -0.7177 +vn 0.5217 0.2422 0.8180 +vn 0.8442 0.4573 0.2796 +vn -0.7108 -0.7034 0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.9899 0.0848 -0.1132 +vn 0.2334 -0.5830 0.7782 +vn 0.9854 0.1238 -0.1168 +vn 0.1633 -0.1166 -0.9797 +vn 0.9630 0.2443 -0.1138 +vn 0.9457 0.3064 -0.1083 +vn 0.9345 0.3366 -0.1161 +vn 0.9636 0.2093 -0.1666 +vn 0.7699 0.2140 -0.6013 +vn 0.8482 0.5296 0.0000 +vn 0.6623 0.7445 -0.0849 +vn 0.7084 0.7058 0.0000 +vn 0.8015 0.5858 -0.1198 +vn 0.8430 0.5264 -0.1111 +vn 0.8441 0.4462 -0.2973 +vn 0.8621 0.4932 -0.1161 +vn 0.9005 0.4188 -0.1169 +vn 0.8942 0.4331 -0.1137 +vn 0.9692 0.2185 -0.1138 +vn 0.9834 0.1790 -0.0300 +vn 0.9745 0.1903 -0.1189 +usemtl None +s off +f 292/274/403 293/275/403 298/276/403 +f 276/277/404 275/278/404 277/279/404 +f 275/278/405 276/277/405 278/280/405 +f 279/281/406 277/279/406 280/282/406 +f 277/279/406 279/281/406 281/283/406 +f 278/280/405 276/277/405 283/284/405 +f 277/279/407 275/278/407 286/285/407 +f 278/280/408 280/282/408 286/285/408 +f 280/282/406 277/279/406 286/285/406 +f 276/277/404 277/279/404 287/286/404 +f 277/279/406 281/283/406 287/286/406 +f 283/284/409 276/277/409 288/287/409 +f 275/278/405 278/280/405 289/288/405 +f 286/285/407 275/278/407 289/288/407 +f 278/280/408 286/285/408 289/288/408 +f 281/283/410 279/281/410 290/289/410 +f 285/290/411 281/283/411 290/289/411 +f 280/282/412 278/280/412 291/291/412 +f 279/281/406 280/282/406 291/291/406 +f 284/292/413 282/293/413 291/291/413 +f 282/293/414 284/292/414 292/274/414 +f 279/281/406 291/291/406 292/274/406 +f 291/291/415 282/293/415 292/274/415 +f 278/280/405 283/284/405 293/275/405 +f 292/274/416 284/292/416 293/275/416 +f 291/291/412 278/280/412 294/294/412 +f 284/292/413 291/291/413 294/294/413 +f 278/280/405 293/275/405 294/294/405 +f 293/275/417 284/292/417 294/294/417 +f 279/281/418 274/295/418 295/296/418 +f 290/289/419 279/281/419 295/296/419 +f 283/284/420 290/289/420 295/296/420 +f 274/295/421 293/275/421 295/296/421 +f 293/275/422 283/284/422 295/296/422 +f 281/283/423 285/290/423 296/297/423 +f 276/277/424 287/286/424 296/297/424 +f 287/286/425 281/283/425 296/297/425 +f 288/287/426 276/277/426 296/297/426 +f 285/290/427 288/287/427 296/297/427 +f 283/284/428 288/287/428 297/298/428 +f 288/287/429 285/290/429 297/298/429 +f 290/289/430 283/284/430 297/298/430 +f 285/290/431 290/289/431 297/298/431 +f 274/295/432 279/281/432 298/276/432 +f 279/281/433 292/274/433 298/276/433 +f 293/275/434 274/295/434 298/276/434 +o Bowl_hull_8 +v -0.030178 0.002587 -0.050214 +v 0.037056 -0.003018 -0.033404 +v 0.037056 -0.003018 -0.034697 +v 0.037056 0.003017 -0.033404 +v -0.030178 -0.002587 -0.033404 +v 0.034904 -0.003018 -0.050214 +v 0.034904 0.003017 -0.050214 +v -0.030178 0.002587 -0.033404 +v -0.030178 -0.002587 -0.050214 +v 0.035332 0.002586 -0.050214 +v 0.032745 -0.003018 -0.033404 +v 0.032745 0.003017 -0.033404 +v 0.035332 -0.002586 -0.050214 +v 0.037056 0.002586 -0.035130 +v 0.032745 -0.003018 -0.050214 +v 0.032745 0.003017 -0.050214 +vt 0.935872 1.000000 +vt 0.967985 0.000000 +vt 0.935872 0.000000 +vt 1.000000 1.000000 +vt 1.000000 0.923062 +vt 1.000000 1.000000 +vt 0.000000 1.000000 +vt 0.967985 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 0.974349 0.000000 +vt 0.935872 1.000000 +vt 0.974349 0.000000 +vt 1.000000 0.897318 +vt 0.935872 0.000000 +vn 0.0000 1.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn -0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn 0.7070 0.7014 -0.0905 +vn -0.0069 -1.0000 0.0000 +vn -0.0068 1.0000 0.0000 +vn 0.7069 -0.7004 -0.0981 +vn 0.9935 0.0000 -0.1136 +vn 0.9044 0.4139 -0.1034 +vn 0.9938 -0.0085 -0.1107 +usemtl None +s off +f 310/299/435 305/300/435 314/301/435 +f 300/302/436 301/303/436 302/304/436 +f 300/302/437 302/304/437 303/305/437 +f 301/303/438 300/302/438 304/306/438 +f 304/306/439 299/307/439 305/300/439 +f 299/307/440 303/305/440 306/308/440 +f 303/305/437 302/304/437 306/308/437 +f 303/305/440 299/307/440 307/309/440 +f 299/307/439 304/306/439 307/309/439 +f 304/306/439 305/300/439 308/310/439 +f 305/300/441 302/304/441 308/310/441 +f 300/302/437 303/305/437 309/311/437 +f 304/306/438 300/302/438 309/311/438 +f 303/305/442 307/309/442 309/311/442 +f 302/304/435 305/300/435 310/299/435 +f 306/308/437 302/304/437 310/299/437 +f 299/307/443 306/308/443 310/299/443 +f 301/303/444 304/306/444 311/312/444 +f 304/306/439 308/310/439 311/312/439 +f 311/312/445 308/310/445 312/313/445 +f 302/304/436 301/303/436 312/313/436 +f 308/310/446 302/304/446 312/313/446 +f 301/303/447 311/312/447 312/313/447 +f 307/309/439 304/306/439 313/314/439 +f 304/306/438 309/311/438 313/314/438 +f 309/311/442 307/309/442 313/314/442 +f 305/300/439 299/307/439 314/301/439 +f 299/307/443 310/299/443 314/301/443 +o Bowl_hull_9 +v 0.080174 -0.023279 0.050233 +v 0.040084 -0.012505 -0.021762 +v 0.040518 -0.012505 -0.021762 +v 0.040084 -0.026726 -0.011409 +v 0.078450 -0.012505 0.050233 +v 0.040518 -0.026296 -0.004080 +v 0.075005 -0.026726 0.050233 +v 0.040084 -0.012505 -0.015293 +v 0.082333 -0.012505 0.049366 +v 0.073280 -0.026726 0.039887 +v 0.040518 -0.020692 -0.017019 +v 0.046556 -0.013367 -0.011839 +v 0.081039 -0.018540 0.048936 +v 0.051296 -0.026726 0.004538 +v 0.078450 -0.026726 0.048506 +v 0.075005 -0.025865 0.050233 +v 0.040948 -0.016814 -0.019168 +v 0.040084 -0.026726 -0.004940 +v 0.079314 -0.023279 0.048076 +v 0.040518 -0.012505 -0.014426 +v 0.059058 -0.012935 0.009281 +v 0.061639 -0.026726 0.020916 +v 0.040948 -0.026726 -0.010980 +v 0.082333 -0.012505 0.050233 +v 0.041378 -0.014229 -0.020028 +v 0.077156 -0.012505 0.048076 +v 0.081039 -0.013367 0.047216 +v 0.078880 -0.026726 0.050233 +v 0.048707 -0.012505 -0.008393 +v 0.040948 -0.024573 -0.013136 +vt 0.365309 0.265368 +vt 0.149765 0.020458 +vt 0.119812 0.020458 +vt 0.000000 0.010278 +vt 0.000000 0.000000 +vt 1.000000 0.908085 +vt 1.000000 0.948904 +vt 1.000000 0.826547 +vt 0.143794 0.000000 +vt 0.089859 0.000000 +vt 0.987960 1.000000 +vt 0.856304 0.785728 +vt 0.065877 0.010278 +vt 0.981989 0.969362 +vt 0.976018 0.908085 +vt 0.245595 0.010278 +vt 1.000000 0.826547 +vt 0.036022 0.020458 +vt 0.233653 0.000000 +vt 0.970047 0.928544 +vt 0.137823 0.153191 +vt 0.101899 0.010278 +vt 0.431186 0.449099 +vt 0.592796 0.510180 +vt 1.000000 1.000000 +vt 0.024080 0.030638 +vt 0.970047 0.877447 +vt 0.958105 0.969362 +vt 1.000000 0.918265 +vt 0.185689 0.204092 +vn 0.7273 -0.4856 -0.4850 +vn 0.0000 1.0000 0.0000 +vn -0.0000 0.0000 1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.0000 -1.0000 0.0000 +vn 0.0000 -0.5013 -0.8653 +vn -0.9148 -0.2376 -0.3265 +vn 0.9750 -0.2027 -0.0909 +vn -0.8256 0.2129 0.5225 +vn -0.8442 0.0000 0.5360 +vn 0.1915 -0.4920 -0.8493 +vn -0.8259 -0.2111 0.5228 +vn -0.9092 0.2450 0.3366 +vn 0.8965 -0.2613 -0.3576 +vn 0.8412 -0.2162 -0.4957 +vn 0.8946 -0.2688 -0.3569 +vn 0.8260 -0.2689 -0.4954 +vn -0.8475 0.3185 0.4246 +vn 0.8455 -0.1967 -0.4965 +vn 0.7857 -0.3694 -0.4962 +vn 0.7885 -0.3628 -0.4967 +vn 0.8079 -0.3185 -0.4958 +vn 0.9805 -0.1965 0.0000 +vn 0.8455 -0.1047 -0.5236 +vn 0.6709 -0.3321 -0.6631 +vn 0.8145 -0.3005 -0.4963 +vn 0.8260 -0.2682 -0.4958 +vn 0.8280 -0.2617 -0.4960 +vn -0.8139 0.3145 0.4885 +vn -0.8066 0.3547 0.4728 +vn 0.8725 -0.1541 -0.4637 +vn 0.8640 -0.0478 -0.5012 +vn 0.8526 -0.1649 -0.4959 +vn 0.9117 -0.3423 -0.2271 +vn 0.8521 -0.0393 -0.5219 +vn 0.8577 0.1228 -0.4993 +vn 0.8554 -0.1196 -0.5039 +vn 0.2703 -0.6659 -0.6954 +vn 0.7632 -0.4129 -0.4971 +vn 0.3316 -0.6675 -0.6667 +usemtl None +s off +f 328/315/448 337/316/448 344/317/448 +f 317/318/449 316/319/449 319/320/449 +f 315/321/450 319/320/450 321/322/450 +f 316/319/451 318/323/451 322/324/451 +f 319/320/449 316/319/449 322/324/449 +f 317/318/449 319/320/449 323/325/449 +f 321/322/452 318/323/452 324/326/452 +f 316/319/453 317/318/453 325/327/453 +f 318/323/454 316/319/454 325/327/454 +f 323/325/455 315/321/455 327/328/455 +f 324/326/452 318/323/452 328/315/452 +f 321/322/452 324/326/452 329/329/452 +f 319/320/456 320/330/456 330/331/456 +f 321/322/450 319/320/450 330/331/450 +f 320/330/457 321/322/457 330/331/457 +f 325/327/458 317/318/458 331/332/458 +f 318/323/452 321/322/452 332/333/452 +f 321/322/459 320/330/459 332/333/459 +f 322/324/451 318/323/451 332/333/451 +f 320/330/460 322/324/460 332/333/460 +f 327/328/461 315/321/461 333/334/461 +f 326/335/462 327/328/462 333/334/462 +f 315/321/463 329/329/463 333/334/463 +f 329/329/464 324/326/464 333/334/464 +f 319/320/449 322/324/449 334/336/449 +f 322/324/465 320/330/465 334/336/465 +f 327/328/466 326/335/466 335/337/466 +f 324/326/452 328/315/452 336/338/452 +f 328/315/467 325/327/467 336/338/467 +f 325/327/468 331/332/468 336/338/468 +f 331/332/469 324/326/469 336/338/469 +f 328/315/452 318/323/452 337/316/452 +f 319/320/450 315/321/450 338/339/450 +f 315/321/470 323/325/470 338/339/470 +f 323/325/449 319/320/449 338/339/449 +f 317/318/471 326/335/471 339/340/471 +f 331/332/472 317/318/472 339/340/472 +f 324/326/473 331/332/473 339/340/473 +f 333/334/474 324/326/474 339/340/474 +f 326/335/475 333/334/475 339/340/475 +f 320/330/476 319/320/476 340/341/476 +f 319/320/449 334/336/449 340/341/449 +f 334/336/477 320/330/477 340/341/477 +f 323/325/478 327/328/478 341/342/478 +f 335/337/479 323/325/479 341/342/479 +f 327/328/480 335/337/480 341/342/480 +f 315/321/450 321/322/450 342/343/450 +f 329/329/481 315/321/481 342/343/481 +f 321/322/452 329/329/452 342/343/452 +f 317/318/449 323/325/449 343/344/449 +f 326/335/482 317/318/482 343/344/482 +f 323/325/483 335/337/483 343/344/483 +f 335/337/484 326/335/484 343/344/484 +f 318/323/485 325/327/485 344/317/485 +f 325/327/486 328/315/486 344/317/486 +f 337/316/487 318/323/487 344/317/487 +o Bowl_hull_10 +v 0.082330 -0.012501 0.050235 +v 0.040088 0.000431 -0.025211 +v 0.040519 0.000431 -0.025211 +v 0.079743 0.000431 0.050235 +v 0.040949 -0.012501 -0.013993 +v 0.041379 -0.012501 -0.020898 +v 0.082760 0.000431 0.048507 +v 0.040088 0.000431 -0.018742 +v 0.078021 -0.012501 0.049371 +v 0.081899 -0.008621 0.047642 +v 0.042240 -0.004312 -0.022190 +v 0.078452 0.000431 0.048507 +v 0.080173 -0.012501 0.045486 +v 0.040519 -0.007759 -0.024339 +v 0.040088 -0.012501 -0.022190 +v 0.083191 -0.004312 0.049371 +v 0.040949 -0.000434 -0.024775 +v 0.040519 -0.011638 -0.014857 +v 0.083191 0.000431 0.050235 +v 0.076726 -0.012069 0.047214 +v 0.056900 -0.012501 0.005400 +v 0.040088 -0.012501 -0.015721 +v 0.078882 -0.012501 0.050235 +v 0.040949 -0.012069 -0.013993 +v 0.057761 0.000431 0.012298 +v 0.077591 -0.003020 0.039453 +v 0.043536 -0.006035 -0.019598 +v 0.082330 -0.012501 0.049371 +v 0.053879 -0.003882 -0.001933 +vt 0.005775 0.019973 +vt 0.857087 0.870080 +vt 0.308536 0.319953 +vt 0.000000 0.009986 +vt 0.000000 0.000000 +vt 1.000000 0.920012 +vt 1.000000 0.980027 +vt 0.148688 0.019973 +vt 0.057165 0.029959 +vt 0.977095 0.990014 +vt 0.085748 0.000000 +vt 0.988547 0.880067 +vt 0.977095 0.890053 +vt 0.937060 0.929998 +vt 0.011551 0.009986 +vt 0.040035 0.000000 +vt 0.040035 0.049931 +vt 1.000000 1.000000 +vt 0.988547 1.000000 +vt 0.959965 0.850010 +vt 0.405736 0.390053 +vt 0.125783 0.000000 +vt 0.137236 0.009986 +vt 1.000000 0.900039 +vt 0.148688 0.019973 +vt 0.497161 0.410026 +vt 0.965642 0.970041 +vt 0.074393 0.079988 +vt 0.988547 0.980027 +vn 0.8675 -0.0348 -0.4963 +vn 0.0000 1.0000 0.0000 +vn -0.0000 -1.0000 -0.0000 +vn -0.7993 0.0665 0.5973 +vn 0.0000 -0.1058 -0.9944 +vn -1.0000 0.0000 0.0000 +vn -0.9205 -0.0889 -0.3804 +vn 0.6603 -0.3589 -0.6597 +vn 0.8537 0.1785 -0.4892 +vn 0.8374 -0.0813 -0.5404 +vn 0.6219 -0.0829 -0.7787 +vn 0.0000 -0.0000 1.0000 +vn 0.9374 -0.0624 0.3426 +vn 0.9694 0.0440 -0.2415 +vn -0.8612 -0.0675 0.5038 +vn -0.8498 0.0632 0.5232 +vn 0.8538 -0.1592 -0.4957 +vn 0.8424 -0.2079 -0.4972 +vn -0.9237 0.0871 0.3731 +vn -0.8951 0.0000 0.4459 +vn -0.7076 0.0471 0.7050 +vn -0.8633 0.0000 0.5046 +vn -0.8614 0.0669 0.5035 +vn 0.0001 1.0000 -0.0001 +vn -0.8619 0.1272 0.4908 +vn -0.8616 0.1233 0.4923 +vn -0.8618 0.1249 0.4917 +vn 0.8701 -0.0108 -0.4927 +vn 0.8686 -0.0009 -0.4956 +vn 0.8628 -0.0975 -0.4960 +vn 0.8617 -0.1078 -0.4958 +vn 0.8564 -0.1138 -0.5036 +vn 0.8575 -0.1361 -0.4962 +vn 0.8682 -0.1183 -0.4819 +vn 0.9945 -0.1045 0.0000 +vn 0.8957 -0.0942 -0.4345 +vn 0.8656 -0.0692 -0.4959 +vn 0.8664 -0.0609 -0.4955 +vn 0.8667 -0.0427 -0.4970 +vn 0.8671 -0.0478 -0.4958 +usemtl None +s off +f 361/345/488 370/346/488 373/347/488 +f 347/348/489 346/349/489 348/350/489 +f 345/351/490 349/352/490 350/353/490 +f 347/348/489 348/350/489 351/354/489 +f 348/350/489 346/349/489 352/355/489 +f 349/352/490 345/351/490 353/356/490 +f 348/350/489 352/355/489 356/357/489 +f 353/356/491 348/350/491 356/357/491 +f 345/351/490 350/353/490 357/358/490 +f 346/349/492 347/348/492 358/359/492 +f 350/353/490 349/352/490 359/360/490 +f 352/355/493 346/349/493 359/360/493 +f 346/349/494 358/359/494 359/360/494 +f 358/359/495 350/353/495 359/360/495 +f 347/348/496 351/354/496 361/345/496 +f 355/361/497 358/359/497 361/345/497 +f 358/359/498 347/348/498 361/345/498 +f 348/350/499 345/351/499 363/362/499 +f 351/354/489 348/350/489 363/362/489 +f 345/351/500 360/363/500 363/362/500 +f 360/363/501 351/354/501 363/362/501 +f 349/352/502 353/356/502 364/364/502 +f 353/356/503 356/357/503 364/364/503 +f 357/358/490 350/353/490 365/365/490 +f 358/359/504 357/358/504 365/365/504 +f 350/353/505 358/359/505 365/365/505 +f 359/360/490 349/352/490 366/366/490 +f 352/355/493 359/360/493 366/366/493 +f 362/367/506 352/355/506 366/366/506 +f 349/352/507 362/367/507 366/366/507 +f 345/351/499 348/350/499 367/368/499 +f 353/356/490 345/351/490 367/368/490 +f 348/350/508 353/356/508 367/368/508 +f 362/367/507 349/352/507 368/369/507 +f 349/352/509 364/364/509 368/369/509 +f 364/364/510 356/357/510 368/369/510 +f 356/357/511 352/355/511 369/370/511 +f 352/355/512 362/367/512 369/370/512 +f 368/369/513 356/357/513 369/370/513 +f 362/367/514 368/369/514 369/370/514 +f 351/354/515 360/363/515 370/346/515 +f 361/345/516 351/354/516 370/346/516 +f 355/361/517 354/371/517 371/372/517 +f 354/371/518 357/358/518 371/372/518 +f 358/359/519 355/361/519 371/372/519 +f 357/358/520 358/359/520 371/372/520 +f 345/351/490 357/358/490 372/373/490 +f 357/358/521 354/371/521 372/373/521 +f 360/363/522 345/351/522 372/373/522 +f 354/371/523 360/363/523 372/373/523 +f 354/371/524 355/361/524 373/347/524 +f 360/363/525 354/371/525 373/347/525 +f 355/361/526 361/345/526 373/347/526 +f 370/346/527 360/363/527 373/347/527 +o Bowl_hull_11 +v -0.015099 0.032335 -0.048921 +v 0.005163 0.032335 -0.033404 +v 0.005163 0.032335 -0.050214 +v 0.002145 0.037076 -0.035128 +v -0.024153 0.028023 -0.033404 +v -0.016390 0.028023 -0.050214 +v -0.009495 0.036214 -0.033404 +v -0.002599 0.035351 -0.050214 +v -0.016390 0.028023 -0.033404 +v 0.005163 0.035351 -0.048058 +v -0.021134 0.028454 -0.050214 +v -0.018979 0.032335 -0.033835 +v 0.005163 0.036644 -0.033404 +v -0.009925 0.034057 -0.050214 +v -0.004754 0.037076 -0.033835 +v -0.014666 0.034489 -0.033835 +v -0.022858 0.029748 -0.033404 +v 0.002575 0.035351 -0.050214 +v -0.018115 0.030609 -0.050214 +v -0.006479 0.034920 -0.049783 +v -0.021134 0.028023 -0.050214 +v 0.004730 0.037076 -0.033404 +v -0.011650 0.033626 -0.049783 +v -0.024153 0.028454 -0.034697 +v -0.020270 0.029317 -0.049783 +v 0.005163 0.034920 -0.050214 +v -0.000011 0.037076 -0.035559 +v -0.009495 0.036214 -0.033835 +vt 0.426488 0.025646 +vt 0.323610 0.974354 +vt 0.500000 0.974354 +vt 1.000000 0.000000 +vt 1.000000 1.000000 +vt 0.264781 0.000000 +vt 0.000000 1.000000 +vt 0.500000 1.000000 +vt 0.735219 0.000000 +vt 0.264781 1.000000 +vt 1.000000 0.128230 +vt 0.102976 0.000000 +vt 1.000000 1.000000 +vt 0.485317 0.000000 +vt 0.308829 0.076938 +vt 0.176488 0.974354 +vt 0.044146 1.000000 +vt 0.911707 0.000000 +vt 0.205951 0.000000 +vt 0.602878 0.025646 +vt 0.661707 0.974354 +vt 0.102976 0.000000 +vt 0.985219 1.000000 +vt 0.897024 0.897416 +vt 0.000000 0.923062 +vt 0.132439 0.025646 +vt 1.000000 0.000000 +vt 0.823512 0.871770 +vn -0.3144 0.9428 -0.1105 +vn 0.1962 -0.9806 -0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 -0.0000 +vn 1.0000 -0.0000 0.0000 +vn -0.4439 0.8888 -0.1142 +vn -0.2664 0.5334 0.8028 +vn -0.2285 0.4722 0.8514 +vn -0.4549 0.8828 -0.1170 +vn -0.1504 0.8514 -0.5026 +vn -0.1227 0.9852 -0.1199 +vn 0.7043 0.7071 -0.0624 +vn 0.0000 1.0000 0.0000 +vn -0.0363 0.5995 0.7995 +vn 0.0742 0.9910 -0.1112 +vn 0.0946 0.9890 -0.1136 +vn -0.3743 0.9194 -0.1206 +vn -0.3945 0.8822 -0.2570 +vn -0.3281 0.7794 -0.5338 +vn -0.7844 0.5884 0.1963 +vn -0.8698 -0.4681 -0.1562 +vn -0.9816 0.0000 -0.1910 +vn -0.5598 0.8213 -0.1101 +vn -0.5278 0.8414 -0.1165 +vn -0.5268 0.7379 -0.4219 +vn -0.6388 0.7598 -0.1209 +vn -0.6677 0.7330 -0.1299 +vn 0.1610 0.9678 -0.1934 +vn -0.0399 0.9931 -0.1099 +vn 0.0000 0.9931 -0.1169 +vn 0.0226 0.9933 -0.1130 +vn -0.1790 0.9839 0.0000 +vn -0.3164 0.9486 0.0000 +vn -0.2269 0.9663 -0.1213 +vn -0.1778 0.9776 -0.1129 +vn -0.2684 0.9559 -0.1188 +usemtl None +s off +f 396/374/528 389/375/528 401/376/528 +f 376/377/529 375/378/529 379/379/529 +f 378/380/530 375/378/530 380/381/530 +f 376/377/531 379/379/531 381/382/531 +f 375/378/530 378/380/530 382/383/530 +f 379/379/529 375/378/529 382/383/529 +f 378/380/532 379/379/532 382/383/532 +f 375/378/533 376/377/533 383/384/533 +f 381/382/531 379/379/531 384/385/531 +f 380/381/530 375/378/530 386/386/530 +f 375/378/533 383/384/533 386/386/533 +f 381/382/531 384/385/531 387/387/531 +f 374/388/534 385/389/534 389/375/534 +f 378/380/530 380/381/530 390/390/530 +f 389/375/535 385/389/535 390/390/535 +f 380/381/536 389/375/536 390/390/536 +f 376/377/531 381/382/531 391/391/531 +f 385/389/537 374/388/537 392/392/537 +f 387/387/531 384/385/531 392/392/531 +f 381/382/538 387/387/538 393/393/538 +f 388/394/539 381/382/539 393/393/539 +f 379/379/532 378/380/532 394/395/532 +f 384/385/531 379/379/531 394/395/531 +f 380/381/530 386/386/530 395/396/530 +f 386/386/540 383/384/540 395/396/540 +f 377/397/541 388/394/541 395/396/541 +f 388/394/542 380/381/542 395/396/542 +f 391/391/543 377/397/543 395/396/543 +f 383/384/544 391/391/544 395/396/544 +f 374/388/545 389/375/545 396/374/545 +f 392/392/546 374/388/546 396/374/546 +f 387/387/547 392/392/547 396/374/547 +f 378/380/548 390/390/548 397/398/548 +f 394/395/549 378/380/549 397/398/549 +f 384/385/550 394/395/550 397/398/550 +f 390/390/551 385/389/551 398/399/551 +f 385/389/552 392/392/552 398/399/552 +f 392/392/553 384/385/553 398/399/553 +f 397/398/554 390/390/554 398/399/554 +f 384/385/555 397/398/555 398/399/555 +f 383/384/533 376/377/533 399/400/533 +f 376/377/531 391/391/531 399/400/531 +f 391/391/556 383/384/556 399/400/556 +f 388/394/541 377/397/541 400/401/541 +f 381/382/557 388/394/557 400/401/557 +f 391/391/558 381/382/558 400/401/558 +f 377/397/559 391/391/559 400/401/559 +f 380/381/560 388/394/560 401/376/560 +f 389/375/561 380/381/561 401/376/561 +f 393/393/562 387/387/562 401/376/562 +f 388/394/563 393/393/563 401/376/563 +f 387/387/564 396/374/564 401/376/564 +o Bowl_hull_12 +v -0.034927 0.013366 -0.034266 +v -0.024585 0.028023 -0.035128 +v -0.024585 0.028023 -0.033404 +v -0.017255 0.027590 -0.033404 +v -0.030619 0.011211 -0.050214 +v -0.022428 0.027590 -0.050214 +v -0.030619 0.011211 -0.033404 +v -0.017255 0.027590 -0.050214 +v -0.030619 0.018109 -0.050214 +v -0.029754 0.022847 -0.033404 +v -0.033635 0.011211 -0.049352 +v -0.035362 0.011211 -0.033404 +v -0.025879 0.024572 -0.049352 +v -0.017255 0.028023 -0.050214 +v -0.032341 0.018972 -0.033835 +v -0.032772 0.013798 -0.050214 +v -0.017255 0.028023 -0.033404 +v -0.027598 0.025434 -0.033835 +v -0.028031 0.021985 -0.049783 +v -0.021998 0.028023 -0.049783 +v -0.025449 0.027590 -0.033835 +v -0.033635 0.016385 -0.034266 +vt 0.143011 0.846124 +vt 0.023982 0.871770 +vt 0.095341 0.692248 +vt 1.000000 0.025744 +vt 0.595145 0.000000 +vt 0.261942 1.000000 +vt 0.261942 1.000000 +vt 1.000000 0.025744 +vt 0.714272 0.025744 +vt 0.261942 0.589663 +vt 0.309710 0.307850 +vt 0.095341 1.000000 +vt 0.000000 1.000000 +vt 0.595145 0.000000 +vt 1.000000 0.000000 +vt 0.166797 0.538371 +vt 1.000000 0.000000 +vt 0.428739 0.153974 +vt 0.523688 0.205266 +vt 0.404855 0.359142 +vt 0.738058 0.000000 +vt 0.547475 0.025744 +vn -0.9134 0.3910 -0.1129 +vn 0.0000 -0.0000 1.0000 +vn 0.7748 -0.6322 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.9821 0.1553 -0.1063 +vn -0.0000 1.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn -0.8201 0.5604 -0.1158 +vn -0.8239 0.3456 0.4491 +vn -0.4987 0.2403 0.8328 +vn -0.9530 0.2776 -0.1213 +vn -0.2679 -0.2230 -0.9373 +vn -0.7534 0.6466 -0.1194 +vn -0.4538 0.3920 -0.8003 +vn -0.6495 0.6148 -0.4475 +vn -0.7726 0.6246 -0.1141 +vn -0.0614 0.7344 -0.6759 +vn -0.4482 0.8939 0.0000 +vn -0.5777 0.5769 0.5775 +vn -0.6706 0.7314 -0.1237 +vn -0.5807 0.5792 0.5721 +vn -0.7032 0.7013 -0.1169 +vn -0.5606 0.8222 -0.0990 +vn -0.6424 0.7572 -0.1184 +vn -0.8543 0.3657 0.3693 +vn -0.8803 0.4598 -0.1168 +vn -0.8882 0.4436 -0.1200 +usemtl None +s off +f 417/402/565 402/403/565 423/404/565 +f 405/405/566 404/406/566 408/407/566 +f 406/408/567 405/405/567 408/407/567 +f 405/405/567 406/408/567 409/409/567 +f 406/408/568 407/410/568 409/409/568 +f 407/410/568 406/408/568 410/411/568 +f 408/407/566 404/406/566 411/412/566 +f 406/408/569 408/407/569 412/413/569 +f 408/407/566 411/412/566 413/414/566 +f 402/403/570 412/413/570 413/414/570 +f 412/413/569 408/407/569 413/414/569 +f 403/415/571 404/406/571 415/416/571 +f 405/405/572 409/409/572 415/416/572 +f 409/409/568 407/410/568 415/416/568 +f 411/412/573 410/411/573 416/417/573 +f 402/403/574 413/414/574 416/417/574 +f 413/414/575 411/412/575 416/417/575 +f 410/411/568 406/408/568 417/402/568 +f 412/413/576 402/403/576 417/402/576 +f 406/408/577 412/413/577 417/402/577 +f 404/406/566 405/405/566 418/418/566 +f 415/416/571 404/406/571 418/418/571 +f 405/405/572 415/416/572 418/418/572 +f 419/419/578 414/420/578 420/421/578 +f 407/410/579 410/411/579 420/421/579 +f 410/411/573 411/412/573 420/421/573 +f 414/420/580 407/410/580 420/421/580 +f 411/412/581 419/419/581 420/421/581 +f 403/415/571 415/416/571 421/422/571 +f 415/416/582 407/410/582 421/422/582 +f 404/406/583 403/415/583 422/423/583 +f 411/412/584 404/406/584 422/423/584 +f 407/410/585 414/420/585 422/423/585 +f 419/419/586 411/412/586 422/423/586 +f 414/420/587 419/419/587 422/423/587 +f 403/415/588 421/422/588 422/423/588 +f 421/422/589 407/410/589 422/423/589 +f 402/403/590 416/417/590 423/404/590 +f 416/417/591 410/411/591 423/404/591 +f 410/411/592 417/402/592 423/404/592 +o Bowl_hull_13 +v -0.034930 -0.007758 -0.047627 +v -0.033637 0.011205 -0.050214 +v -0.030620 0.011205 -0.050214 +v -0.035361 0.011205 -0.033404 +v -0.030620 -0.011640 -0.033404 +v -0.037085 -0.004739 -0.033404 +v -0.030620 -0.011640 -0.050214 +v -0.030620 0.011205 -0.033404 +v -0.035361 -0.011640 -0.033404 +v -0.035361 0.002154 -0.050214 +v -0.037085 0.004739 -0.033835 +v -0.030189 0.002583 -0.033404 +v -0.033637 -0.011206 -0.050214 +v -0.030189 -0.002585 -0.050214 +v -0.035361 -0.002153 -0.050214 +v -0.034930 0.006895 -0.049352 +v -0.036223 0.009480 -0.033835 +v -0.036223 -0.009482 -0.033835 +v -0.030189 -0.002585 -0.033404 +v -0.030189 0.002583 -0.050214 +v -0.037085 -0.002153 -0.035128 +v -0.033637 -0.011640 -0.049352 +v -0.034930 -0.006895 -0.049352 +vt 0.981008 0.000000 +vt 1.000000 0.051292 +vt 0.792266 0.051292 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 0.697895 1.000000 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 0.396182 0.000000 +vt 0.283015 0.974354 +vt 0.377386 1.000000 +vt 0.603622 0.000000 +vt 0.584728 0.000000 +vt 0.188644 0.051292 +vt 0.075477 0.974354 +vt 0.905531 0.974354 +vt 0.603622 1.000000 +vt 0.377386 0.000000 +vt 0.584728 0.897416 +vt 0.830054 0.153876 +vn -0.9565 -0.2606 -0.1311 +vn 0.0000 1.0000 -0.0000 +vn 0.0000 -0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.3873 0.0419 0.9210 +vn 0.9988 0.0500 0.0000 +vn 0.9989 -0.0476 0.0000 +vn -0.8652 0.1648 -0.4735 +vn -0.9863 0.1118 -0.1215 +vn -0.9778 0.1778 -0.1111 +vn -0.8815 0.4634 -0.0904 +vn -0.6140 0.1117 0.7813 +vn -0.9570 0.2624 -0.1235 +vn -0.7848 -0.1961 0.5879 +vn 1.0000 0.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.9940 0.0202 -0.1078 +vn -0.9907 -0.0755 -0.1132 +vn -0.9935 0.0000 -0.1136 +vn -0.1274 -0.8860 -0.4458 +vn -0.9567 -0.2641 -0.1227 +vn -0.9171 -0.3862 -0.0992 +vn -0.9867 -0.1113 -0.1183 +vn -0.8653 -0.1648 -0.4733 +vn -0.9632 -0.2405 -0.1204 +vn -0.9796 -0.1681 -0.1097 +vn -0.9566 -0.2606 -0.1305 +usemtl None +s off +f 436/424/593 445/425/593 446/426/593 +f 426/427/594 425/428/594 427/429/594 +f 428/430/595 427/429/595 429/431/595 +f 425/428/596 426/427/596 430/432/596 +f 426/427/594 427/429/594 431/433/594 +f 427/429/595 428/430/595 431/433/595 +f 428/430/595 429/431/595 432/434/595 +f 430/432/597 428/430/597 432/434/597 +f 425/428/596 430/432/596 433/435/596 +f 429/431/598 427/429/598 434/436/598 +f 426/427/599 431/433/599 435/437/599 +f 431/433/595 428/430/595 435/437/595 +f 433/435/596 430/432/596 436/424/596 +f 430/432/596 426/427/596 437/438/596 +f 428/430/600 430/432/600 437/438/600 +f 433/435/596 436/424/596 438/439/596 +f 425/428/601 433/435/601 439/440/601 +f 433/435/602 434/436/602 439/440/602 +f 439/440/603 434/436/603 440/441/603 +f 427/429/604 425/428/604 440/441/604 +f 434/436/605 427/429/605 440/441/605 +f 425/428/606 439/440/606 440/441/606 +f 432/434/607 429/431/607 441/442/607 +f 435/437/595 428/430/595 442/443/595 +f 428/430/600 437/438/600 442/443/600 +f 437/438/608 435/437/608 442/443/608 +f 426/427/599 435/437/599 443/444/599 +f 437/438/596 426/427/596 443/444/596 +f 435/437/608 437/438/608 443/444/608 +f 429/431/609 434/436/609 444/445/609 +f 434/436/610 433/435/610 444/445/610 +f 438/439/611 429/431/611 444/445/611 +f 433/435/612 438/439/612 444/445/612 +f 430/432/597 432/434/597 445/425/597 +f 436/424/613 430/432/613 445/425/613 +f 441/442/614 424/446/614 445/425/614 +f 432/434/615 441/442/615 445/425/615 +f 429/431/616 438/439/616 446/426/616 +f 438/439/617 436/424/617 446/426/617 +f 424/446/618 441/442/618 446/426/618 +f 441/442/619 429/431/619 446/426/619 +f 445/425/620 424/446/620 446/426/620 +o Bowl_hull_14 +v 0.065950 -0.047426 0.045491 +v 0.040084 -0.043974 0.008851 +v 0.040515 -0.043974 0.008851 +v 0.040084 -0.072859 0.049372 +v 0.065950 -0.043974 0.050231 +v 0.040084 -0.068112 0.049801 +v 0.040084 -0.044407 0.016180 +v 0.056896 -0.061216 0.049801 +v 0.070693 -0.043974 0.049801 +v 0.040515 -0.046994 0.011866 +v 0.047413 -0.068112 0.048509 +v 0.049138 -0.044407 0.019198 +v 0.063364 -0.054322 0.049368 +v 0.047844 -0.068547 0.050235 +v 0.040515 -0.058201 0.027386 +v 0.051727 -0.065527 0.049372 +v 0.058621 -0.059061 0.048938 +v 0.067242 -0.049581 0.050231 +v 0.040084 -0.068547 0.050235 +v 0.057758 -0.044407 0.030833 +v 0.040084 -0.043974 0.015317 +v 0.042241 -0.070269 0.046779 +v 0.044395 -0.044407 0.013162 +v 0.054313 -0.060786 0.045920 +v 0.069830 -0.045702 0.049368 +v 0.040084 -0.072859 0.050235 +v 0.054313 -0.043977 0.026097 +v 0.040084 -0.051738 0.018335 +v 0.041810 -0.053890 0.022646 +v 0.040515 -0.072859 0.049372 +v 0.060344 -0.057769 0.050235 +v 0.065087 -0.044407 0.041180 +v 0.066813 -0.050010 0.049368 +v 0.058621 -0.057339 0.046783 +v 0.070693 -0.044407 0.050231 +v 0.041810 -0.044836 0.010573 +vt 0.895742 0.464859 +vt 0.072834 0.014096 +vt 0.041605 0.056382 +vt 0.000000 0.014096 +vt 0.000000 0.000000 +vt 0.999902 0.845047 +vt 0.979148 0.000000 +vt 0.989525 0.000000 +vt 0.177092 0.000000 +vt 0.989525 1.000000 +vt 0.989525 0.549237 +vt 1.000000 0.253524 +vt 0.979148 0.380384 +vt 0.958297 0.239428 +vt 0.979050 0.760572 +vt 0.968673 0.605619 +vt 1.000000 0.000000 +vt 0.250024 0.295811 +vt 0.531180 0.577428 +vt 0.156241 0.000000 +vt 0.447871 0.014096 +vt 0.916495 0.070478 +vt 1.000000 0.000000 +vt 0.416740 0.464859 +vt 0.104161 0.140857 +vt 0.229173 0.000000 +vt 0.333333 0.056382 +vt 0.979148 0.014096 +vt 1.000000 0.661903 +vt 0.999902 0.887236 +vt 0.885365 0.845047 +vt 0.781204 0.816856 +vt 0.979050 0.971809 +vt 0.979050 0.873238 +vt 0.916593 0.605619 +vt 0.999902 1.000000 +vn 0.5802 -0.6456 -0.4965 +vn 0.0000 1.0000 0.0000 +vn -1.0000 -0.0000 0.0000 +vn -0.6112 0.6469 0.4561 +vn 0.0000 -0.7065 -0.7078 +vn 0.6271 -0.7659 0.1420 +vn 0.5328 -0.7793 -0.3298 +vn 0.6909 -0.6660 -0.2812 +vn -0.5567 0.5861 0.5887 +vn 0.6711 -0.5499 -0.4972 +vn -0.5176 0.7649 0.3835 +vn 0.4704 -0.7299 -0.4960 +vn 0.5895 -0.6602 -0.4654 +vn 0.5583 -0.6653 -0.4957 +vn 0.5902 -0.6593 -0.4658 +vn 0.0000 0.0000 1.0000 +vn 0.0026 1.0000 -0.0019 +vn 0.7980 -0.1170 -0.5912 +vn 0.6157 0.6151 -0.4925 +vn 0.7167 0.4112 -0.5632 +vn -0.7036 -0.5498 -0.4501 +vn -0.5039 -0.7141 -0.4859 +vn 0.1346 -0.8033 -0.5801 +vn 0.4864 -0.7083 -0.5115 +vn 0.5141 -0.6997 -0.4961 +vn 0.5171 -0.6978 -0.4957 +vn 0.5479 -0.6733 -0.4965 +vn 0.5074 -0.7969 -0.3279 +vn 0.0000 -0.8320 -0.5547 +vn 0.4678 -0.7613 -0.4491 +vn 0.3835 -0.7684 -0.5123 +vn 0.0000 -1.0000 0.0000 +vn 0.4720 -0.8494 0.2360 +vn 0.7021 -0.6734 -0.2313 +vn 0.5033 -0.5838 0.6371 +vn 0.7608 -0.6408 0.1028 +vn -0.0002 0.0004 1.0000 +vn 0.7022 -0.5094 -0.4974 +vn 0.7135 -0.4987 -0.4922 +vn 0.8119 -0.2766 -0.5141 +vn 0.6834 0.5567 -0.4723 +vn 0.8041 0.1706 -0.5695 +vn 0.7787 -0.6228 -0.0764 +vn 0.7008 -0.5117 -0.4971 +vn 0.6784 -0.5426 -0.4954 +vn 0.7133 -0.4995 -0.4917 +vn 0.8132 -0.5694 -0.1202 +vn 0.6421 -0.5853 -0.4951 +vn 0.6419 -0.5991 -0.4786 +vn 0.6317 -0.5955 -0.4963 +vn 0.6076 -0.6205 -0.4958 +vn 0.0641 0.7031 0.7082 +vn 0.8703 -0.3470 -0.3496 +vn 0.8319 -0.5549 0.0009 +vn 0.0000 0.0003 1.0000 +vn 0.0028 -0.0019 1.0000 +vn 0.4259 -0.6392 -0.6403 +vn 0.7043 -0.2609 -0.6602 +vn 0.6006 -0.6273 -0.4958 +vn 0.5990 -0.6289 -0.4957 +usemtl None +s off +f 470/447/621 456/448/621 482/449/621 +f 449/450/622 448/451/622 451/452/622 +f 448/451/623 450/453/623 452/454/623 +f 448/451/623 452/454/623 453/455/623 +f 452/454/624 451/452/624 453/455/624 +f 449/450/622 451/452/622 455/456/622 +f 448/451/625 449/450/625 456/448/625 +f 454/457/626 460/458/626 462/459/626 +f 460/458/627 457/460/627 462/459/627 +f 459/461/628 454/457/628 463/462/628 +f 451/452/629 452/454/629 465/463/629 +f 452/454/623 450/453/623 465/463/623 +f 459/461/630 458/464/630 466/465/630 +f 451/452/622 448/451/622 467/466/622 +f 448/451/623 453/455/623 467/466/623 +f 453/455/631 451/452/631 467/466/631 +f 461/467/632 457/460/632 468/468/632 +f 454/457/633 462/459/633 470/447/633 +f 462/459/634 456/448/634 470/447/634 +f 463/462/635 454/457/635 470/447/635 +f 465/463/623 450/453/623 472/469/623 +f 460/458/636 465/463/636 472/469/636 +f 449/450/637 455/456/637 473/470/637 +f 466/465/638 458/464/638 473/470/638 +f 469/471/639 449/450/639 473/470/639 +f 458/464/640 469/471/640 473/470/640 +f 450/453/623 448/451/623 474/472/623 +f 448/451/641 456/448/641 474/472/641 +f 461/467/642 450/453/642 474/472/642 +f 456/448/643 461/467/643 474/472/643 +f 461/467/644 456/448/644 475/473/644 +f 457/460/645 461/467/645 475/473/645 +f 462/459/646 457/460/646 475/473/646 +f 456/448/647 462/459/647 475/473/647 +f 457/460/648 460/458/648 476/474/648 +f 450/453/649 461/467/649 476/474/649 +f 468/468/650 457/460/650 476/474/650 +f 461/467/651 468/468/651 476/474/651 +f 472/469/652 450/453/652 476/474/652 +f 460/458/653 472/469/653 476/474/653 +f 454/457/654 459/461/654 477/475/654 +f 460/458/655 454/457/655 477/475/655 +f 459/461/656 464/476/656 477/475/656 +f 451/452/657 465/463/657 477/475/657 +f 465/463/636 460/458/636 477/475/636 +f 447/477/658 466/465/658 478/478/658 +f 471/479/659 447/477/659 478/478/659 +f 455/456/660 471/479/660 478/478/660 +f 473/470/661 455/456/661 478/478/661 +f 466/465/662 473/470/662 478/478/662 +f 464/476/663 459/461/663 479/480/663 +f 466/465/664 447/477/664 479/480/664 +f 459/461/665 466/465/665 479/480/665 +f 447/477/666 471/479/666 479/480/666 +f 471/479/667 464/476/667 479/480/667 +f 458/464/668 459/461/668 480/481/668 +f 459/461/669 463/462/669 480/481/669 +f 469/471/670 458/464/670 480/481/670 +f 463/462/671 469/471/671 480/481/671 +f 455/456/672 451/452/672 481/482/672 +f 471/479/673 455/456/673 481/482/673 +f 464/476/674 471/479/674 481/482/674 +f 451/452/675 477/475/675 481/482/675 +f 477/475/676 464/476/676 481/482/676 +f 456/448/677 449/450/677 482/449/677 +f 449/450/678 469/471/678 482/449/678 +f 469/471/679 463/462/679 482/449/679 +f 463/462/680 470/447/680 482/449/680 +o Bowl_hull_15 +v 0.012061 -0.035350 -0.034266 +v 0.024133 -0.028455 -0.033404 +v 0.024133 -0.028455 -0.035128 +v 0.005163 -0.032333 -0.033404 +v 0.023700 -0.022419 -0.050214 +v 0.006027 -0.034918 -0.050214 +v 0.023700 -0.022419 -0.033404 +v 0.018096 -0.030608 -0.050214 +v 0.005163 -0.032333 -0.050214 +v 0.005163 -0.036644 -0.033404 +v 0.024133 -0.026300 -0.049352 +v 0.018956 -0.032333 -0.033404 +v 0.013786 -0.032763 -0.050214 +v 0.024133 -0.022419 -0.033404 +v 0.009475 -0.036212 -0.033835 +v 0.005163 -0.034918 -0.050214 +v 0.014648 -0.034488 -0.033835 +v 0.021113 -0.028885 -0.048489 +v 0.011633 -0.033625 -0.049783 +v 0.024133 -0.022419 -0.050214 +v 0.021544 -0.030608 -0.034266 +v 0.005596 -0.036644 -0.035559 +v 0.024133 -0.025868 -0.050214 +v 0.008615 -0.034488 -0.049783 +v 0.015079 -0.032333 -0.049352 +vt 0.500000 0.974354 +vt 0.454581 0.000000 +vt 0.522709 0.051292 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 0.977193 1.000000 +vt 0.977193 0.000000 +vt 0.045517 0.000000 +vt 0.681774 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 0.897416 +vt 1.000000 0.051292 +vt 0.727095 1.000000 +vt 1.000000 1.000000 +vt 0.227291 0.974354 +vt 0.000000 0.000000 +vt 0.363645 0.948708 +vt 0.840838 0.102584 +vt 0.341034 0.025646 +vt 1.000000 0.000000 +vt 0.863547 0.948708 +vt 0.022807 0.871770 +vt 1.000000 0.000000 +vt 0.181969 0.025646 +vn 0.3829 -0.9164 -0.1167 +vn 0.0000 -0.0000 1.0000 +vn -0.4716 0.8818 0.0000 +vn 0.0000 0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.1319 -0.4222 0.8969 +vn 0.3161 -0.9487 0.0000 +vn 0.1687 -0.5064 0.8456 +vn 0.6266 -0.7706 -0.1168 +vn 0.5855 -0.7691 -0.2563 +vn 0.2970 -0.9481 -0.1136 +vn 0.3310 -0.9368 -0.1133 +vn 0.3488 -0.9299 -0.1163 +vn 0.6394 -0.7689 0.0000 +vn 0.5880 -0.7851 0.1946 +vn 0.5246 -0.8438 -0.1134 +vn 0.6127 -0.7821 -0.1133 +vn 0.5420 -0.8322 -0.1172 +vn 0.1585 -0.9811 -0.1108 +vn 0.1016 -0.9946 0.0204 +vn 0.0000 -0.9931 -0.1169 +vn -0.4534 -0.8867 -0.0910 +vn 0.5746 -0.7318 -0.3664 +vn 0.2249 -0.8096 -0.5422 +vn 0.1815 -0.9766 -0.1153 +vn 0.2412 -0.8432 -0.4804 +vn 0.2731 -0.9547 -0.1179 +vn 0.4684 -0.8762 -0.1139 +vn 0.4365 -0.8727 -0.2187 +vn 0.4535 -0.8844 -0.1103 +usemtl None +s off +f 499/483/681 495/484/681 507/485/681 +f 486/486/682 484/487/682 489/488/682 +f 487/489/683 486/486/683 489/488/683 +f 488/490/684 487/489/684 490/491/684 +f 486/486/683 487/489/683 491/492/683 +f 487/489/684 488/490/684 491/492/684 +f 484/487/682 486/486/682 492/493/682 +f 486/486/685 491/492/685 492/493/685 +f 484/487/686 485/494/686 493/495/686 +f 484/487/682 492/493/682 494/496/682 +f 488/490/684 490/491/684 495/484/684 +f 489/488/682 484/487/682 496/497/682 +f 487/489/687 489/488/687 496/497/687 +f 484/487/686 493/495/686 496/497/686 +f 494/496/688 492/493/688 497/498/688 +f 491/492/684 488/490/684 498/499/684 +f 492/493/685 491/492/685 498/499/685 +f 497/498/689 483/500/689 499/483/689 +f 494/496/690 497/498/690 499/483/690 +f 493/495/691 485/494/691 500/501/691 +f 490/491/692 493/495/692 500/501/692 +f 483/500/693 497/498/693 501/502/693 +f 499/483/694 483/500/694 501/502/694 +f 495/484/695 499/483/695 501/502/695 +f 490/491/684 487/489/684 502/503/684 +f 487/489/687 496/497/687 502/503/687 +f 496/497/686 493/495/686 502/503/686 +f 485/494/696 484/487/696 503/504/696 +f 484/487/697 494/496/697 503/504/697 +f 494/496/698 490/491/698 503/504/698 +f 500/501/699 485/494/699 503/504/699 +f 490/491/700 500/501/700 503/504/700 +f 488/490/701 497/498/701 504/505/701 +f 497/498/702 492/493/702 504/505/702 +f 498/499/703 488/490/703 504/505/703 +f 492/493/704 498/499/704 504/505/704 +f 493/495/705 490/491/705 505/506/705 +f 490/491/684 502/503/684 505/506/684 +f 502/503/686 493/495/686 505/506/686 +f 488/490/706 495/484/706 506/507/706 +f 497/498/707 488/490/707 506/507/707 +f 495/484/708 501/502/708 506/507/708 +f 501/502/709 497/498/709 506/507/709 +f 490/491/710 494/496/710 507/485/710 +f 495/484/711 490/491/711 507/485/711 +f 494/496/712 499/483/712 507/485/712 +o Bowl_hull_16 +v 0.032323 -0.018968 -0.033404 +v 0.032753 -0.003020 -0.050214 +v 0.034909 -0.003020 -0.050214 +v 0.024133 -0.025434 -0.050214 +v 0.032323 -0.003453 -0.033404 +v 0.024133 -0.021986 -0.033404 +v 0.037065 -0.003020 -0.033404 +v 0.032753 -0.013797 -0.050214 +v 0.024565 -0.028020 -0.033404 +v 0.024133 -0.021986 -0.050214 +v 0.028014 -0.021986 -0.050214 +v 0.036201 -0.009488 -0.033835 +v 0.034909 -0.006901 -0.049352 +v 0.027583 -0.025434 -0.033835 +v 0.032323 -0.003453 -0.050214 +v 0.024565 -0.025864 -0.049352 +v 0.034477 -0.014659 -0.033835 +v 0.031461 -0.016812 -0.049352 +v 0.024133 -0.028020 -0.033404 +v 0.037065 -0.004315 -0.034266 +v 0.034047 -0.010349 -0.049783 +v 0.030599 -0.021552 -0.034266 +v 0.035339 -0.003453 -0.049783 +v 0.032753 -0.003020 -0.033404 +v 0.030170 -0.018968 -0.049783 +v 0.025428 -0.027587 -0.033835 +v 0.025859 -0.024570 -0.049783 +vt 0.896535 0.974354 +vt 0.982674 0.974354 +vt 0.861981 0.025646 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.896535 0.000000 +vt 0.637921 1.000000 +vt 0.017326 1.000000 +vt 0.758614 1.000000 +vt 0.000000 1.000000 +vt 0.431089 0.000000 +vt 1.000000 1.000000 +vt 0.758614 0.000000 +vt 0.758614 0.000000 +vt 0.258712 0.974354 +vt 0.017326 0.000000 +vt 0.465544 0.974354 +vt 0.551684 0.051292 +vt 1.000000 1.000000 +vt 0.913763 0.051292 +vt 0.051782 0.948708 +vt 0.155247 0.051292 +vt 0.293168 0.025646 +vt 0.741288 0.948708 +vt 0.017326 0.025646 +vt 0.000000 1.000000 +vt 0.637921 0.025646 +vn 0.7021 -0.7029 -0.1140 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 1.0000 0.0000 +vn -0.9147 0.4042 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.3745 -0.1113 0.9205 +vn 0.4390 -0.3762 0.8159 +vn -0.7094 0.7049 0.0000 +vn 0.5075 -0.1692 0.8448 +vn 0.8847 -0.4532 -0.1091 +vn 0.9003 -0.4194 -0.1168 +vn -0.5625 -0.8172 -0.1257 +vn 0.0000 -0.9910 -0.1340 +vn 0.9660 -0.1433 0.2151 +vn 0.9788 -0.1725 -0.1103 +vn 0.5771 -0.1154 -0.8085 +vn 0.9667 -0.2269 -0.1183 +vn 0.9346 -0.3362 -0.1161 +vn 0.9429 -0.3144 -0.1104 +vn 0.7850 -0.5884 0.1937 +vn 0.7790 -0.6174 -0.1095 +vn 0.7524 0.6516 -0.0965 +vn 0.9918 0.0708 -0.1064 +vn 0.9836 -0.1374 -0.1170 +vn 0.6398 -0.1199 -0.7592 +vn 0.8819 -0.1653 -0.4415 +vn -0.7093 0.7049 0.0000 +vn 0.6687 -0.3871 -0.6349 +vn 0.8444 -0.4466 -0.2958 +vn 0.8622 -0.4937 -0.1133 +vn 0.8434 -0.5257 -0.1109 +vn 0.8159 -0.5662 -0.1169 +vn 0.5783 -0.5790 0.5748 +vn 0.3957 -0.9101 -0.1230 +vn 0.6825 -0.7213 -0.1180 +vn 0.4332 -0.4876 -0.7580 +vn 0.7532 -0.6474 -0.1165 +vn 0.4767 -0.6671 -0.5725 +usemtl None +s off +f 521/508/713 533/509/713 534/510/713 +f 509/511/714 510/512/714 511/513/714 +f 508/514/715 512/515/715 513/516/715 +f 510/512/716 509/511/716 514/517/716 +f 512/515/715 508/514/715 514/517/715 +f 511/513/714 510/512/714 515/518/714 +f 508/514/715 513/516/715 516/519/715 +f 509/511/714 511/513/714 517/520/714 +f 513/516/717 512/515/717 517/520/717 +f 511/513/718 513/516/718 517/520/718 +f 511/513/714 515/518/714 518/521/714 +f 514/517/719 508/514/719 519/522/719 +f 508/514/720 516/519/720 521/508/720 +f 512/515/721 509/511/721 522/523/721 +f 509/511/714 517/520/714 522/523/714 +f 517/520/717 512/515/717 522/523/717 +f 519/522/722 508/514/722 524/524/722 +f 524/524/723 508/514/723 525/525/723 +f 515/518/724 524/524/724 525/525/724 +f 513/516/718 511/513/718 526/526/718 +f 516/519/715 513/516/715 526/526/715 +f 511/513/725 523/527/725 526/526/725 +f 523/527/726 516/519/726 526/526/726 +f 514/517/727 519/522/727 527/528/727 +f 519/522/728 520/529/728 527/528/728 +f 515/518/729 510/512/729 528/530/729 +f 520/529/730 519/522/730 528/530/730 +f 524/524/731 515/518/731 528/530/731 +f 519/522/732 524/524/732 528/530/732 +f 508/514/733 521/508/733 529/531/733 +f 521/508/734 518/521/734 529/531/734 +f 510/512/735 514/517/735 530/532/735 +f 514/517/736 527/528/736 530/532/736 +f 527/528/737 520/529/737 530/532/737 +f 528/530/738 510/512/738 530/532/738 +f 520/529/739 528/530/739 530/532/739 +f 509/511/740 512/515/740 531/533/740 +f 514/517/716 509/511/716 531/533/716 +f 512/515/715 514/517/715 531/533/715 +f 518/521/741 515/518/741 532/534/741 +f 515/518/742 525/525/742 532/534/742 +f 525/525/743 508/514/743 532/534/743 +f 508/514/744 529/531/744 532/534/744 +f 529/531/745 518/521/745 532/534/745 +f 521/508/746 516/519/746 533/509/746 +f 516/519/747 523/527/747 533/509/747 +f 533/509/748 523/527/748 534/510/748 +f 511/513/749 518/521/749 534/510/749 +f 518/521/750 521/508/750 534/510/750 +f 523/527/751 511/513/751 534/510/751 +o Bowl_hull_17 +v -0.040537 0.051736 0.018334 +v -0.069415 0.046132 0.049371 +v -0.068554 0.046132 0.048076 +v -0.045711 0.069838 0.049371 +v -0.040107 0.068115 0.049801 +v -0.040104 0.045698 0.017904 +v -0.065105 0.045698 0.050235 +v -0.057349 0.060785 0.049801 +v -0.046141 0.046132 0.017470 +v -0.040107 0.072858 0.050235 +v -0.040104 0.045698 0.011003 +v -0.063814 0.053031 0.048507 +v -0.054333 0.063372 0.049371 +v -0.069415 0.045698 0.050235 +v -0.040968 0.072427 0.048941 +v -0.064244 0.045698 0.049371 +v -0.057349 0.046132 0.032124 +v -0.059932 0.055617 0.046352 +v -0.061226 0.056909 0.050235 +v -0.040968 0.046562 0.011867 +v -0.050023 0.066820 0.049371 +v -0.040537 0.059065 0.028680 +v -0.040107 0.068546 0.050235 +v -0.053900 0.056479 0.039885 +v -0.057349 0.045698 0.032124 +v -0.049590 0.067251 0.050235 +v -0.040104 0.059065 0.028680 +v -0.066830 0.049580 0.048937 +v -0.051745 0.047426 0.026095 +vt 0.901038 0.323544 +vt 0.164839 0.794028 +vt 0.384691 0.602839 +vt 0.175901 1.000000 +vt 1.000000 0.147039 +vt 0.000000 1.000000 +vt 0.977976 0.000000 +vt 0.944988 0.029369 +vt 1.000000 0.000000 +vt 1.000000 0.999902 +vt 0.977976 0.808713 +vt 0.967013 0.970534 +vt 0.988939 0.999902 +vt 0.977976 0.176407 +vt 0.955951 0.191092 +vt 0.988939 0.411650 +vt 1.000000 0.279393 +vt 0.186864 0.985218 +vt 0.022024 0.970534 +vt 0.977976 0.514538 +vt 0.977976 0.661576 +vt 0.450568 0.985218 +vt 1.000000 0.999902 +vt 0.736198 0.529320 +vt 0.538371 0.411650 +vt 0.538371 0.411650 +vt 1.000000 0.676358 +vt 0.450568 1.000000 +vt 0.966915 0.088204 +vn -0.6244 0.6032 -0.4962 +vn -0.0000 -1.0000 0.0000 +vn -0.5589 -0.7413 -0.3717 +vn 0.0000 -0.0000 1.0000 +vn -0.4773 0.8784 0.0251 +vn 0.5998 -0.6546 0.4601 +vn 0.5596 -0.6132 0.5575 +vn -0.6539 0.6180 -0.4364 +vn -0.6700 0.6253 -0.4000 +vn -0.7743 0.5656 0.2837 +vn 0.1441 0.7680 -0.6240 +vn -0.7317 -0.0518 -0.6796 +vn -0.5549 0.6672 -0.4968 +vn -0.5426 0.6783 -0.4955 +vn -0.4498 0.7412 -0.4983 +vn -0.5106 0.7016 -0.4971 +vn -0.4981 0.7119 -0.4952 +vn 1.0000 -0.0003 0.0003 +vn 0.5442 -0.5955 0.5910 +vn -0.6083 0.6286 -0.4846 +vn -0.6092 0.6277 -0.4846 +vn -0.6185 0.6099 -0.4956 +vn -0.5917 0.6343 -0.4976 +vn -0.5795 0.6464 -0.4963 +vn -0.4603 -0.8043 -0.3759 +vn -0.5575 -0.7424 -0.3715 +vn -0.7943 0.0000 -0.6075 +vn -0.8183 0.0000 -0.5748 +vn -0.4885 0.8263 0.2803 +vn -0.6404 0.7623 0.0938 +vn -0.5336 0.6003 0.5957 +vn -0.5691 0.8134 -0.1201 +vn -0.6229 0.7786 -0.0757 +vn 1.0000 0.0000 0.0000 +vn 0.6726 0.5902 -0.4463 +vn 0.3624 0.7851 -0.5023 +vn 0.0000 0.8160 -0.5781 +vn 0.0000 0.8348 -0.5505 +vn 1.0000 -0.0002 0.0002 +vn 1.0000 -0.0000 0.0001 +vn -0.7281 0.4850 -0.4843 +vn -0.7162 0.4837 -0.5031 +vn -0.6837 0.5358 -0.4954 +vn -0.7971 0.6026 0.0389 +vn -0.7416 0.6146 -0.2688 +vn -0.6784 0.5202 -0.5189 +vn -0.6640 0.5585 -0.4972 +vn -0.6550 0.5705 -0.4954 +usemtl None +s off +f 552/535/752 543/536/752 563/537/752 +f 540/538/753 541/539/753 545/540/753 +f 536/541/754 537/542/754 548/543/754 +f 541/539/755 544/544/755 548/543/755 +f 545/540/753 541/539/753 548/543/753 +f 538/545/756 544/544/756 549/546/756 +f 540/538/757 539/547/757 550/548/757 +f 541/539/753 540/538/753 550/548/753 +f 539/547/758 541/539/758 550/548/758 +f 546/549/759 542/550/759 552/535/759 +f 542/550/760 546/549/760 553/551/760 +f 536/541/761 548/543/761 553/551/761 +f 548/543/755 544/544/755 553/551/755 +f 535/552/762 545/540/762 554/553/762 +f 545/540/763 543/536/763 554/553/763 +f 547/554/764 535/552/764 554/553/764 +f 535/552/765 547/554/765 555/555/765 +f 538/545/766 549/546/766 556/556/766 +f 535/552/767 555/555/767 556/556/767 +f 555/555/768 538/545/768 556/556/768 +f 539/547/769 540/538/769 557/557/769 +f 541/539/770 539/547/770 557/557/770 +f 544/544/755 541/539/755 557/557/755 +f 542/550/771 547/554/771 558/558/771 +f 552/535/772 542/550/772 558/558/772 +f 543/536/773 552/535/773 558/558/773 +f 554/553/774 543/536/774 558/558/774 +f 547/554/775 554/553/775 558/558/775 +f 543/536/776 545/540/776 559/559/776 +f 548/543/777 537/542/777 559/559/777 +f 545/540/753 548/543/753 559/559/753 +f 551/560/778 543/536/778 559/559/778 +f 537/542/779 551/560/779 559/559/779 +f 544/544/780 538/545/780 560/561/780 +f 547/554/781 542/550/781 560/561/781 +f 542/550/782 553/551/782 560/561/782 +f 553/551/755 544/544/755 560/561/755 +f 538/545/783 555/555/783 560/561/783 +f 555/555/784 547/554/784 560/561/784 +f 540/538/785 545/540/785 561/562/785 +f 545/540/786 535/552/786 561/562/786 +f 549/546/787 544/544/787 561/562/787 +f 535/552/788 556/556/788 561/562/788 +f 556/556/789 549/546/789 561/562/789 +f 557/557/790 540/538/790 561/562/790 +f 544/544/791 557/557/791 561/562/791 +f 537/542/792 536/541/792 562/563/792 +f 551/560/793 537/542/793 562/563/793 +f 546/549/794 551/560/794 562/563/794 +f 536/541/795 553/551/795 562/563/795 +f 553/551/796 546/549/796 562/563/796 +f 543/536/797 551/560/797 563/537/797 +f 551/560/798 546/549/798 563/537/798 +f 546/549/799 552/535/799 563/537/799 +o Bowl_hull_18 +v -0.047003 0.043110 0.014881 +v -0.078037 0.029318 0.049367 +v -0.078037 0.028886 0.049367 +v -0.040969 0.028886 -0.008389 +v -0.040104 0.045266 0.017038 +v -0.069418 0.045697 0.048940 +v -0.073729 0.028886 0.049801 +v -0.040538 0.028886 -0.001492 +v -0.065106 0.045266 0.050235 +v -0.040104 0.045697 0.010574 +v -0.055195 0.029318 0.012731 +v -0.072868 0.039660 0.048506 +v -0.042261 0.031473 -0.004510 +v -0.055195 0.045697 0.028676 +v -0.040104 0.033629 -0.004510 +v -0.073298 0.040092 0.050235 +v -0.065106 0.045697 0.050235 +v -0.047865 0.029318 0.001520 +v -0.073729 0.029318 0.050235 +v -0.040969 0.045266 0.010140 +v -0.075883 0.034060 0.048940 +v -0.040104 0.044403 0.016176 +v -0.062091 0.044834 0.037296 +v -0.040538 0.036647 -0.001064 +v -0.040969 0.045697 0.018333 +v -0.040104 0.028886 -0.002359 +v -0.067695 0.042679 0.043332 +v -0.040969 0.045266 0.018333 +v -0.062091 0.029318 0.023501 +v -0.078037 0.028886 0.050235 +v -0.069849 0.045697 0.050235 +v -0.040104 0.028886 -0.008828 +v -0.055195 0.028886 0.012731 +v -0.042261 0.029318 -0.006666 +v -0.072868 0.028886 0.048506 +v -0.040969 0.032336 -0.005377 +v -0.042692 0.045697 0.012731 +v -0.074160 0.029318 0.042904 +vt 0.978074 0.056779 +vt 0.547377 0.420362 +vt 0.875881 0.102203 +vt 0.985317 0.000000 +vt 0.007439 0.977190 +vt 0.992659 0.113559 +vt 0.124217 0.988546 +vt 0.978074 0.227215 +vt 0.328504 1.000000 +vt 0.634984 0.602154 +vt 0.437940 1.000000 +vt 0.073121 1.000000 +vt 0.970732 0.136270 +vt 1.000000 0.124915 +vt 1.000000 0.340871 +vt 1.000000 0.340871 +vt 0.365016 0.602154 +vt 0.175215 0.795399 +vt 1.000000 0.113559 +vt 0.985317 0.000000 +vt 0.423355 1.000000 +vt 0.780932 0.420362 +vt 0.401429 0.818111 +vt 0.131460 0.988546 +vt 0.321163 0.977190 +vt 0.459867 0.977190 +vt 0.109534 1.000000 +vt 0.883124 0.272638 +vt 0.459867 0.977190 +vt 1.000000 0.000000 +vt 1.000000 0.215859 +vt 0.000000 1.000000 +vt 0.365016 0.602154 +vt 0.036609 0.943123 +vt 0.073121 0.943123 +vt 0.970732 0.136270 +vt 0.058438 0.977190 +vt 0.365016 0.931767 +vn -0.7980 0.3418 -0.4964 +vn 0.0000 -1.0000 -0.0000 +vn -0.0000 1.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn -0.8113 0.4869 -0.3236 +vn 0.0000 0.0000 1.0000 +vn -0.7595 0.4201 -0.4966 +vn -0.9104 0.4066 -0.0764 +vn -0.8449 0.4303 -0.3179 +vn -0.6383 0.6260 -0.4480 +vn -0.6565 0.5680 -0.4964 +vn 0.4252 0.7067 -0.5654 +vn -0.0872 0.7880 -0.6095 +vn 0.5125 0.8568 0.0572 +vn 0.7975 0.0000 0.6034 +vn 0.7883 -0.4718 0.3949 +vn -0.7474 0.4615 -0.4780 +vn -0.7507 0.4369 -0.4956 +vn -0.7171 0.4975 -0.4881 +vn 0.7181 -0.4935 0.4907 +vn 0.7323 -0.3959 0.5541 +vn 0.7171 -0.4985 0.4871 +vn 0.7270 -0.4852 0.4857 +vn 0.8315 0.0000 0.5555 +vn -0.7748 0.3920 -0.4960 +vn -0.7807 0.3821 -0.4945 +vn -1.0000 0.0000 0.0000 +vn -0.9042 0.3824 0.1901 +vn 0.0708 -0.7073 0.7033 +vn -0.8194 0.5043 -0.2725 +vn -0.7633 -0.3910 -0.5142 +vn -0.8369 0.0000 -0.5473 +vn -0.7995 -0.3352 -0.4984 +vn -0.8422 0.0000 -0.5392 +vn -0.8066 -0.2114 -0.5521 +vn -0.7120 0.4966 -0.4964 +vn -0.7252 0.4771 -0.4964 +vn -0.7206 0.4844 -0.4960 +vn 0.7127 -0.5170 0.4741 +vn 0.7067 -0.5401 0.4570 +vn -0.6861 0.5326 -0.4956 +vn -0.6871 0.5312 -0.4957 +vn -0.6605 0.5630 -0.4968 +vn -0.3699 0.6753 -0.6381 +vn -0.3573 0.6143 -0.7035 +vn -0.2566 0.6507 -0.7146 +vn -0.6173 0.5175 -0.5926 +vn -0.6874 0.5137 -0.5135 +vn -0.6149 0.6240 -0.4822 +vn -0.2798 0.8994 -0.3359 +vn -0.6152 0.6117 -0.4974 +vn -0.5993 0.6232 -0.5024 +vn -0.8576 0.0000 -0.5144 +vn -0.8112 0.3245 -0.4865 +vn -0.8171 -0.2722 -0.5082 +usemtl None +s off +f 584/564/800 592/565/800 601/566/800 +f 566/567/801 567/568/801 570/569/801 +f 570/569/801 567/568/801 571/570/801 +f 569/571/802 573/572/802 577/573/802 +f 573/572/803 568/574/803 578/575/803 +f 569/571/804 575/576/804 579/577/804 +f 573/572/802 569/571/802 580/578/802 +f 579/577/805 572/579/805 580/578/805 +f 574/580/806 575/576/806 581/581/806 +f 572/579/805 579/577/805 582/582/805 +f 565/583/807 579/577/807 584/564/807 +f 579/577/808 575/576/808 584/564/808 +f 578/575/803 568/574/803 585/584/803 +f 569/571/809 577/573/809 586/585/809 +f 577/573/810 564/586/810 587/587/810 +f 573/572/811 578/575/811 587/587/811 +f 583/588/812 573/572/812 587/587/812 +f 568/574/813 573/572/813 588/589/813 +f 580/578/814 572/579/814 588/589/814 +f 573/572/802 580/578/802 588/589/802 +f 571/570/801 567/568/801 589/590/801 +f 585/584/815 571/570/815 589/590/815 +f 578/575/803 585/584/803 589/590/803 +f 575/576/816 569/571/816 590/591/816 +f 581/581/817 575/576/817 590/591/817 +f 569/571/818 586/585/818 590/591/818 +f 582/582/819 570/569/819 591/592/819 +f 572/579/820 582/582/820 591/592/820 +f 570/569/821 585/584/821 591/592/821 +f 585/584/822 568/574/822 591/592/822 +f 568/574/823 588/589/823 591/592/823 +f 588/589/814 572/579/814 591/592/814 +f 575/576/824 574/580/824 592/565/824 +f 584/564/825 575/576/825 592/565/825 +f 565/583/826 566/567/826 593/593/826 +f 566/567/801 570/569/801 593/593/801 +f 579/577/827 565/583/827 593/593/827 +f 570/569/828 582/582/828 593/593/828 +f 582/582/805 579/577/805 593/593/805 +f 569/571/829 579/577/829 594/594/829 +f 580/578/802 569/571/802 594/594/802 +f 579/577/805 580/578/805 594/594/805 +f 589/590/801 567/568/801 595/595/801 +f 578/575/803 589/590/803 595/595/803 +f 567/568/801 566/567/801 596/596/801 +f 581/581/830 567/568/830 596/596/830 +f 574/580/831 581/581/831 596/596/831 +f 566/567/832 592/565/832 596/596/832 +f 592/565/833 574/580/833 596/596/833 +f 567/568/834 581/581/834 597/597/834 +f 586/585/835 576/598/835 597/597/835 +f 581/581/836 590/591/836 597/597/836 +f 590/591/837 586/585/837 597/597/837 +f 570/569/801 571/570/801 598/599/801 +f 585/584/838 570/569/838 598/599/838 +f 571/570/839 585/584/839 598/599/839 +f 586/585/840 577/573/840 599/600/840 +f 576/598/841 586/585/841 599/600/841 +f 577/573/842 587/587/842 599/600/842 +f 587/587/843 578/575/843 599/600/843 +f 595/595/844 567/568/844 599/600/844 +f 578/575/845 595/595/845 599/600/845 +f 567/568/846 597/597/846 599/600/846 +f 597/597/847 576/598/847 599/600/847 +f 564/586/848 577/573/848 600/601/848 +f 577/573/802 573/572/802 600/601/802 +f 573/572/849 583/588/849 600/601/849 +f 587/587/850 564/586/850 600/601/850 +f 583/588/851 587/587/851 600/601/851 +f 566/567/852 565/583/852 601/566/852 +f 565/583/853 584/564/853 601/566/853 +f 592/565/854 566/567/854 601/566/854 +o Bowl_hull_19 +v -0.044848 0.027158 -0.004945 +v -0.081920 0.015521 0.049370 +v -0.081920 0.015089 0.049370 +v -0.074160 0.028453 0.050235 +v -0.040968 0.015089 -0.012274 +v -0.040538 0.028453 -0.001928 +v -0.077176 0.015089 0.048934 +v -0.040538 0.015521 -0.020469 +v -0.077176 0.028885 0.047639 +v -0.040538 0.028885 -0.009257 +v -0.079763 0.024142 0.049370 +v -0.040108 0.028885 -0.002793 +v -0.060369 0.028885 0.020482 +v -0.050022 0.015521 -0.004945 +v -0.040108 0.015089 -0.020469 +v -0.041401 0.017678 -0.017873 +v -0.074160 0.028885 0.050235 +v -0.081920 0.015089 0.050235 +v -0.078470 0.028453 0.050235 +v -0.040108 0.015089 -0.013998 +v -0.040538 0.020695 -0.017015 +v -0.079763 0.020695 0.047639 +v -0.078040 0.015089 0.050235 +v -0.040108 0.028885 -0.009257 +v -0.076746 0.025002 0.044629 +v -0.068556 0.026727 0.032123 +v -0.044848 0.015521 -0.013568 +v -0.062518 0.015521 0.016170 +v -0.054332 0.028885 0.011007 +v -0.050022 0.015089 -0.004945 +v -0.073296 0.028453 0.048934 +v -0.042261 0.028885 -0.007097 +v -0.060799 0.028022 0.020482 +vt 0.445184 0.659814 +vt 0.048845 0.989721 +vt 0.579189 0.505140 +vt 0.115897 0.979442 +vt 0.262236 0.989721 +vt 0.981597 0.113461 +vt 0.987764 0.000000 +vt 0.158575 0.989721 +vt 0.963293 0.113461 +vt 0.250000 1.000000 +vt 0.579189 0.515418 +vt 0.000000 1.000000 +vt 1.000000 0.185609 +vt 0.987764 0.000000 +vt 1.000000 0.000000 +vt 0.987764 0.051591 +vt 1.000000 0.185609 +vt 1.000000 0.082526 +vt 0.091523 1.000000 +vt 0.000000 0.989721 +vt 0.036707 0.969065 +vt 0.963293 0.051591 +vt 1.000000 0.092805 +vt 0.158575 1.000000 +vt 0.920713 0.123740 +vt 0.219558 0.762898 +vt 0.743833 0.319628 +vt 0.097592 0.886637 +vt 0.518207 0.464023 +vt 0.219558 0.886637 +vt 0.219558 0.762898 +vt 0.981597 0.206265 +vt 0.189115 0.948507 +vn -0.7778 0.3862 -0.4958 +vn 0.7930 -0.3887 0.4691 +vn -0.0000 -1.0000 0.0000 +vn -0.0000 1.0000 0.0000 +vn 0.8173 0.2378 0.5248 +vn -1.0000 0.0000 0.0000 +vn -0.9630 0.2410 0.1204 +vn 0.0000 0.0000 1.0000 +vn -0.8645 0.3347 -0.3751 +vn -0.0991 0.9884 0.1152 +vn -0.9491 0.2451 0.1980 +vn 0.8381 -0.3506 0.4180 +vn 0.9101 -0.2612 0.3217 +vn 1.0000 0.0000 0.0000 +vn 0.4874 0.4848 -0.7262 +vn -0.7438 0.3711 -0.5559 +vn -0.8733 0.2185 -0.4354 +vn 0.8098 -0.2351 0.5375 +vn 0.0000 0.6877 -0.7260 +vn 0.8935 0.2832 -0.3485 +vn -0.8323 0.2792 -0.4789 +vn -0.8375 0.2451 -0.4884 +vn -0.8351 0.2383 -0.4958 +vn -0.8178 0.2934 -0.4951 +vn -0.8183 0.2906 -0.4959 +vn -0.8128 0.2855 -0.5077 +vn -0.8272 0.2634 -0.4963 +vn -0.8121 0.3066 -0.4965 +vn -0.8634 0.0000 -0.5046 +vn -0.8480 0.1878 -0.4956 +vn -0.8388 0.2236 -0.4964 +vn -0.7586 0.4216 -0.4967 +vn -0.6459 -0.6424 -0.4125 +vn -0.7826 -0.3854 -0.4889 +vn -0.8575 0.0000 -0.5145 +vn -0.8470 -0.1876 -0.4974 +vn -0.8606 0.0000 -0.5093 +vn 0.8167 -0.2372 0.5260 +vn 0.8332 0.0000 0.5530 +vn 0.8397 0.0499 0.5408 +vn -0.7289 0.4603 -0.5068 +vn -0.6729 0.5087 -0.5370 +vn -0.7275 0.4852 -0.4851 +vn -0.7830 0.3900 -0.4846 +vn -0.7867 0.3665 -0.4967 +vn -0.7964 0.3524 -0.4915 +vn -0.8003 0.3374 -0.4957 +vn -0.7775 0.3873 -0.4955 +usemtl None +s off +f 630/602/855 622/603/855 634/604/855 +f 606/605/856 607/606/856 608/607/856 +f 604/608/857 606/605/857 608/607/857 +f 611/609/858 610/610/858 613/611/858 +f 610/610/858 611/609/858 614/612/858 +f 606/605/857 604/608/857 616/613/857 +f 607/606/859 613/611/859 618/614/859 +f 613/611/858 610/610/858 618/614/858 +f 603/615/860 604/608/860 619/616/860 +f 604/608/857 608/607/857 619/616/857 +f 612/617/861 603/615/861 619/616/861 +f 605/618/862 618/614/862 619/616/862 +f 619/616/862 618/614/862 620/619/862 +f 610/610/863 612/617/863 620/619/863 +f 618/614/864 610/610/864 620/619/864 +f 612/617/865 619/616/865 620/619/865 +f 607/606/866 606/605/866 621/620/866 +f 613/611/867 607/606/867 621/620/867 +f 606/605/857 616/613/857 621/620/857 +f 616/613/868 613/611/868 621/620/868 +f 616/613/869 609/621/869 622/603/869 +f 609/621/870 617/622/870 622/603/870 +f 603/615/871 612/617/871 623/623/871 +f 608/607/872 605/618/872 624/624/872 +f 619/616/857 608/607/857 624/624/857 +f 605/618/862 619/616/862 624/624/862 +f 611/609/858 613/611/858 625/625/858 +f 613/611/868 616/613/868 625/625/868 +f 622/603/873 611/609/873 625/625/873 +f 616/613/874 622/603/874 625/625/874 +f 612/617/875 610/610/875 626/626/875 +f 623/623/876 612/617/876 626/626/876 +f 615/627/877 623/623/877 626/626/877 +f 626/626/878 610/610/878 627/628/878 +f 626/626/879 627/628/879 628/629/879 +f 617/622/880 609/621/880 628/629/880 +f 615/627/881 626/626/881 628/629/881 +f 627/628/882 617/622/882 628/629/882 +f 604/608/883 603/615/883 629/630/883 +f 603/615/884 623/623/884 629/630/884 +f 623/623/885 615/627/885 629/630/885 +f 614/612/858 611/609/858 630/602/858 +f 602/631/886 622/603/886 630/602/886 +f 616/613/857 604/608/857 631/632/857 +f 609/621/887 616/613/887 631/632/887 +f 628/629/888 609/621/888 631/632/888 +f 615/627/889 628/629/889 631/632/889 +f 604/608/890 629/630/890 631/632/890 +f 629/630/891 615/627/891 631/632/891 +f 608/607/892 607/606/892 632/633/892 +f 605/618/872 608/607/872 632/633/872 +f 618/614/893 605/618/893 632/633/893 +f 607/606/894 618/614/894 632/633/894 +f 622/603/895 602/631/895 633/634/895 +f 611/609/896 622/603/896 633/634/896 +f 602/631/897 630/602/897 633/634/897 +f 630/602/858 611/609/858 633/634/858 +f 610/610/898 614/612/898 634/604/898 +f 622/603/899 617/622/899 634/604/899 +f 627/628/900 610/610/900 634/604/900 +f 617/622/901 627/628/901 634/604/901 +f 614/612/902 630/602/902 634/604/902 +o Bowl_hull_20 +v -0.040969 0.014656 -0.020462 +v -0.083210 0.003451 0.049363 +v -0.082779 0.006900 0.048935 +v -0.078040 0.014656 0.050235 +v -0.040539 0.000433 -0.017877 +v -0.041399 0.000433 -0.023911 +v -0.079332 0.000433 0.049799 +v -0.040104 0.015086 -0.014000 +v -0.081488 0.015086 0.048507 +v -0.083210 0.000433 0.049363 +v -0.040539 0.007330 -0.024347 +v -0.078471 0.000433 0.048507 +v -0.054764 0.015086 0.002815 +v -0.040539 0.003881 -0.025211 +v -0.081918 0.015086 0.050235 +v -0.040104 0.014656 -0.014000 +v -0.040104 0.015086 -0.020898 +v -0.040104 0.000433 -0.025211 +v -0.078040 0.015086 0.050235 +v -0.076314 0.009914 0.038160 +v -0.083210 0.000433 0.050235 +v -0.042695 0.009482 -0.020034 +v -0.040104 0.000433 -0.018742 +v -0.046573 0.007330 -0.014000 +v -0.048299 0.002157 -0.011844 +v -0.079766 0.000433 0.050235 +v -0.082779 0.000433 0.048507 +v -0.082779 0.009482 0.049363 +v -0.071575 0.005176 0.029106 +v -0.041399 0.011639 -0.021326 +v -0.063381 0.015086 0.017460 +vt 0.371476 0.659912 +vt 0.068618 0.939892 +vt 0.565583 0.460010 +vt 0.017228 0.969946 +vt 0.097200 0.989917 +vt 0.994225 0.089966 +vt 0.988450 0.000000 +vt 1.000000 0.119922 +vt 0.977095 0.109936 +vt 0.977095 0.039941 +vt 0.148590 1.000000 +vt 1.000000 0.029956 +vt 0.148590 1.000000 +vt 0.011453 0.989917 +vt 0.062940 0.979932 +vt 0.057165 1.000000 +vt 0.000000 1.000000 +vt 0.000000 0.989917 +vt 1.000000 0.119922 +vt 0.988450 0.000000 +vt 1.000000 0.000000 +vt 0.085748 1.000000 +vt 0.148590 0.849927 +vt 0.839957 0.159961 +vt 0.177173 0.809887 +vt 1.000000 0.079882 +vt 0.977095 0.009985 +vt 0.982772 0.009985 +vt 0.988450 0.009985 +vt 0.719949 0.269897 +vt 0.051488 0.969946 +vn -0.8432 0.2070 -0.4961 +vn 0.0000 -1.0000 -0.0000 +vn 0.8287 -0.0921 0.5520 +vn 0.0000 1.0000 0.0000 +vn 0.8610 0.0000 0.5085 +vn 0.8577 -0.0875 0.5066 +vn 0.8571 -0.1597 0.4898 +vn -0.5569 0.3633 -0.7469 +vn -0.5507 0.7622 -0.3404 +vn 1.0000 0.0000 0.0000 +vn -0.7055 -0.0889 -0.7031 +vn 0.8877 0.1119 -0.4466 +vn 0.9321 0.1023 -0.3474 +vn 0.0000 0.0000 1.0000 +vn -1.0000 0.0000 0.0000 +vn 0.8835 -0.1481 0.4444 +vn -0.8570 0.1252 -0.4998 +vn -0.8580 0.1337 -0.4959 +vn -0.8615 0.1065 -0.4965 +vn -0.8550 0.1427 -0.4987 +vn -0.8552 0.1497 -0.4963 +vn -0.8660 0.0280 -0.4992 +vn 0.7054 -0.0856 0.7036 +vn -0.8936 0.0000 -0.4490 +vn -0.8684 0.0168 -0.4956 +vn -0.8682 -0.0021 -0.4961 +vn -0.9166 0.0654 -0.3944 +vn -0.9539 0.1835 -0.2376 +vn -0.8616 0.1233 -0.4924 +vn -0.9685 0.0691 0.2394 +vn -0.9186 0.0809 0.3869 +vn -0.8679 0.0469 -0.4945 +vn -0.8644 0.0831 -0.4959 +vn -0.8679 0.0323 -0.4957 +vn -0.8665 0.0519 -0.4964 +vn -0.8646 0.0822 -0.4957 +vn -0.8646 0.0826 -0.4957 +vn -0.7401 0.2806 -0.6112 +vn -0.8285 0.2602 -0.4958 +vn -0.8354 0.1937 -0.5143 +vn -0.8427 0.2088 -0.4963 +vn -0.8498 0.1792 -0.4956 +usemtl None +s off +f 647/635/903 656/636/903 665/637/903 +f 640/638/904 639/639/904 641/640/904 +f 640/638/904 641/640/904 644/641/904 +f 638/642/905 641/640/905 646/643/905 +f 641/640/904 639/639/904 646/643/904 +f 643/644/906 642/645/906 647/635/906 +f 642/645/906 643/644/906 649/646/906 +f 642/645/907 638/642/907 650/647/907 +f 638/642/908 646/643/908 650/647/908 +f 646/643/909 639/639/909 650/647/909 +f 645/648/910 635/649/910 651/650/910 +f 635/649/911 647/635/911 651/650/911 +f 647/635/906 642/645/906 651/650/906 +f 642/645/912 650/647/912 651/650/912 +f 651/650/912 650/647/912 652/651/912 +f 639/639/904 640/638/904 652/651/904 +f 640/638/913 648/652/913 652/651/913 +f 648/652/914 645/648/914 652/651/914 +f 645/648/915 651/650/915 652/651/915 +f 638/642/907 642/645/907 653/653/907 +f 649/646/916 638/642/916 653/653/916 +f 642/645/906 649/646/906 653/653/906 +f 636/654/917 644/641/917 655/655/917 +f 644/641/904 641/640/904 655/655/904 +f 638/642/916 649/646/916 655/655/916 +f 650/647/918 639/639/918 657/656/918 +f 652/651/912 650/647/912 657/656/912 +f 639/639/904 652/651/904 657/656/904 +f 645/648/919 648/652/919 658/657/919 +f 654/658/920 643/644/920 658/657/920 +f 648/652/921 654/658/921 658/657/921 +f 656/636/922 645/648/922 658/657/922 +f 643/644/923 656/636/923 658/657/923 +f 648/652/924 640/638/924 659/659/924 +f 641/640/925 638/642/925 660/660/925 +f 638/642/916 655/655/916 660/660/916 +f 655/655/904 641/640/904 660/660/904 +f 644/641/926 636/654/926 661/661/926 +f 640/638/904 644/641/904 661/661/904 +f 636/654/927 659/659/927 661/661/927 +f 659/659/928 640/638/928 661/661/928 +f 637/662/929 636/654/929 662/663/929 +f 649/646/930 643/644/930 662/663/930 +f 643/644/931 654/658/931 662/663/931 +f 636/654/932 655/655/932 662/663/932 +f 655/655/933 649/646/933 662/663/933 +f 636/654/934 637/662/934 663/664/934 +f 654/658/935 648/652/935 663/664/935 +f 659/659/936 636/654/936 663/664/936 +f 648/652/937 659/659/937 663/664/937 +f 637/662/938 662/663/938 663/664/938 +f 662/663/939 654/658/939 663/664/939 +f 635/649/940 645/648/940 664/665/940 +f 647/635/941 635/649/941 664/665/941 +f 645/648/942 656/636/942 664/665/942 +f 656/636/943 647/635/943 664/665/943 +f 643/644/906 647/635/906 665/637/906 +f 656/636/944 643/644/944 665/637/944 +o Bowl_hull_21 +v -0.030189 0.064663 0.028240 +v -0.039671 0.039663 0.009287 +v -0.039240 0.040096 0.009715 +v -0.020704 0.040096 -0.017020 +v -0.020704 0.076738 0.050235 +v -0.040102 0.072853 0.048931 +v -0.020704 0.040096 -0.009679 +v -0.040102 0.040958 0.003678 +v -0.021137 0.080619 0.049366 +v -0.040102 0.068111 0.049366 +v -0.025016 0.040096 -0.013998 +v -0.040102 0.053033 0.019623 +v -0.021137 0.050872 -0.000193 +v -0.029327 0.078029 0.049366 +v -0.040102 0.073286 0.050235 +v -0.020704 0.080619 0.050235 +v -0.034931 0.040096 -0.003649 +v -0.039240 0.068977 0.050235 +v -0.021566 0.040096 -0.017020 +v -0.021566 0.039663 -0.017020 +v -0.040102 0.039663 0.002816 +v -0.039671 0.040096 0.010143 +v -0.038809 0.059928 0.028240 +v -0.040102 0.040096 0.010143 +v -0.021137 0.059070 0.013171 +v -0.031480 0.076734 0.048503 +v -0.020704 0.075876 0.048938 +v -0.020704 0.039663 -0.010542 +v -0.039671 0.068111 0.049366 +v -0.026309 0.078887 0.048938 +v -0.036224 0.072424 0.045054 +v -0.031049 0.042257 -0.004939 +v -0.038378 0.066820 0.038154 +v -0.020704 0.059070 0.013171 +v -0.020704 0.041391 -0.007527 +v -0.021566 0.076738 0.042901 +v -0.029758 0.078029 0.050235 +v -0.021566 0.046133 -0.007527 +v -0.040102 0.045700 0.009715 +v -0.040102 0.059062 0.028240 +v -0.033636 0.076305 0.049366 +v -0.031049 0.040096 -0.007961 +vt 0.544832 0.673551 +vt 0.179620 0.936668 +vt 0.134691 0.989428 +vt 0.000000 0.989428 +vt 1.000000 0.094753 +vt 0.109143 0.989428 +vt 0.980619 0.189605 +vt 0.307753 0.968383 +vt 0.987079 0.305403 +vt 1.000000 0.179033 +vt 1.000000 0.000000 +vt 1.000000 0.284260 +vt 0.250196 0.726312 +vt 0.000000 0.989428 +vt 0.000000 1.000000 +vt 0.044930 0.989428 +vt 0.294930 1.000000 +vt 0.198806 0.989428 +vt 0.391151 1.000000 +vt 0.397514 0.989428 +vt 0.403876 0.989428 +vt 0.403876 0.989428 +vt 0.448904 0.526136 +vt 0.974256 0.094851 +vt 0.980717 0.115799 +vt 0.096319 1.000000 +vt 0.987079 0.305403 +vt 0.987079 0.063234 +vt 0.987079 0.000000 +vt 0.980717 0.042287 +vt 0.820380 0.336922 +vt 0.672964 0.505188 +vt 0.922964 0.200078 +vt 0.448904 0.526136 +vt 0.141151 0.957811 +vt 0.890955 0.094753 +vt 1.000000 0.063234 +vt 0.141151 0.842013 +vt 0.672964 0.389585 +vt 0.397514 0.852584 +vt 0.672964 0.526331 +vt 0.987079 0.105325 +vn -0.5207 0.6944 -0.4966 +vn 1.0000 0.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn -0.6376 -0.1276 0.7597 +vn 0.0000 0.8421 -0.5393 +vn 0.0000 0.0000 -1.0000 +vn -0.6588 0.0000 -0.7523 +vn -0.7359 0.3753 -0.5635 +vn 0.0000 -1.0000 0.0000 +vn 0.4089 -0.8143 0.4120 +vn -0.6630 -0.7474 0.0442 +vn 0.0000 -0.8923 0.4514 +vn 0.0000 -0.8137 0.5812 +vn -0.3139 0.8093 -0.4965 +vn 0.4639 -0.7526 0.4673 +vn 0.4019 -0.7626 0.5068 +vn 0.4195 -0.8142 0.4013 +vn 0.4250 -0.8090 0.4062 +vn 0.4480 -0.8920 -0.0596 +vn 0.3123 -0.7459 0.5883 +vn 0.0000 -0.7083 0.7059 +vn 0.3249 -0.7696 0.5497 +vn -0.2948 0.9323 -0.2096 +vn -0.3022 0.8230 -0.4811 +vn -0.2981 0.8160 -0.4952 +vn -0.4347 0.7514 -0.4964 +vn -0.4840 0.7283 -0.4852 +vn -0.4520 0.7415 -0.4958 +vn -0.4078 0.7668 -0.4957 +vn -0.4098 0.7664 -0.4947 +vn 0.3654 0.7881 -0.4953 +vn 0.7102 0.6086 -0.3539 +vn 0.0000 0.8524 -0.5229 +vn 0.0000 0.8593 -0.5116 +vn 0.4747 -0.7542 0.4537 +vn 0.4782 -0.7495 0.4578 +vn 1.0000 -0.0002 0.0000 +vn -0.0638 0.8575 -0.5105 +vn -0.2406 0.8392 -0.4878 +vn -0.2562 0.8293 -0.4965 +vn -0.2982 0.9430 -0.1479 +vn -0.2725 0.9525 0.1357 +vn -0.1447 0.8349 -0.5310 +vn -0.3482 0.7954 -0.4960 +vn -0.3393 0.7990 -0.4964 +vn -0.3751 0.7830 -0.4961 +vn -0.3806 0.7803 -0.4963 +vn -0.5971 0.6308 -0.4956 +vn -0.5544 0.6690 -0.4951 +vn -0.4867 0.7269 -0.4845 +vn -0.4830 0.7213 -0.4964 +vn -0.4888 0.7172 -0.4966 +vn -0.5018 0.7087 -0.4959 +vn -0.4367 0.8537 -0.2836 +vn -0.3558 0.7927 -0.4949 +vn -0.3366 0.8414 -0.4228 +vn -0.3613 0.7905 -0.4946 +vn -0.3890 0.7886 -0.4762 +vn -0.3653 0.9131 -0.1812 +vn -0.4161 0.9076 0.0565 +vn -0.5507 0.6716 -0.4957 +vn -0.5785 -0.5754 -0.5782 +vn -0.4967 -0.7439 -0.4472 +vn -0.3675 -0.8643 -0.3434 +vn -0.5030 0.7030 -0.5027 +usemtl None +s off +f 677/666/945 697/667/945 707/668/945 +f 669/669/946 670/670/946 672/671/946 +f 671/672/947 673/673/947 675/674/947 +f 673/673/947 671/672/947 677/666/947 +f 671/672/947 675/674/947 680/675/947 +f 670/670/946 669/669/946 681/676/946 +f 680/675/948 670/670/948 681/676/948 +f 670/670/948 680/675/948 683/677/948 +f 680/675/949 675/674/949 683/677/949 +f 678/678/950 669/669/950 684/679/950 +f 684/679/951 669/669/951 685/680/951 +f 676/681/952 684/679/952 685/680/952 +f 675/674/947 673/673/947 686/682/947 +f 673/673/953 682/683/953 686/682/953 +f 685/680/954 667/684/954 686/682/954 +f 667/684/955 668/685/955 687/686/955 +f 686/682/956 667/684/956 689/687/956 +f 675/674/947 686/682/947 689/687/947 +f 667/684/957 687/686/957 689/687/957 +f 687/686/958 675/674/958 689/687/958 +f 690/688/959 678/678/959 691/689/959 +f 672/671/946 670/670/946 692/690/946 +f 687/686/960 668/685/960 692/690/960 +f 670/670/961 687/686/961 692/690/961 +f 668/685/962 667/684/962 693/691/962 +f 672/671/963 668/685/963 693/691/963 +f 669/669/946 672/671/946 693/691/946 +f 667/684/954 685/680/954 693/691/954 +f 685/680/964 669/669/964 693/691/964 +f 670/670/965 683/677/965 694/692/965 +f 683/677/966 675/674/966 694/692/966 +f 687/686/967 670/670/967 694/692/967 +f 675/674/958 687/686/958 694/692/958 +f 679/693/968 674/694/968 695/695/968 +f 691/689/969 679/693/969 695/695/969 +f 690/688/970 691/689/970 695/695/970 +f 684/679/971 676/681/971 698/696/971 +f 688/697/972 671/672/972 698/696/972 +f 676/681/973 688/697/973 698/696/973 +f 696/698/974 684/679/974 698/696/974 +f 671/672/975 696/698/975 698/696/975 +f 669/669/976 678/678/976 699/699/976 +f 681/676/946 669/669/946 699/699/946 +f 674/694/977 681/676/977 699/699/977 +f 678/678/978 690/688/978 699/699/978 +f 690/688/979 674/694/979 699/699/979 +f 668/685/980 672/671/980 700/700/980 +f 692/690/981 668/685/981 700/700/981 +f 672/671/982 692/690/982 700/700/982 +f 674/694/983 690/688/983 701/701/983 +f 695/695/984 674/694/984 701/701/984 +f 690/688/985 695/695/985 701/701/985 +f 674/694/986 679/693/986 702/702/986 +f 680/675/948 681/676/948 702/702/948 +f 681/676/987 674/694/987 702/702/987 +f 678/678/988 684/679/988 703/703/988 +f 666/704/989 691/689/989 703/703/989 +f 691/689/990 678/678/990 703/703/990 +f 696/698/991 666/704/991 703/703/991 +f 684/679/992 696/698/992 703/703/992 +f 673/673/947 677/666/947 704/705/947 +f 682/683/993 673/673/993 704/705/993 +f 677/666/994 682/683/994 704/705/994 +f 677/666/947 671/672/947 705/706/947 +f 671/672/995 688/697/995 705/706/995 +f 688/697/996 676/681/996 705/706/996 +f 676/681/997 697/667/997 705/706/997 +f 697/667/998 677/666/998 705/706/998 +f 671/672/999 680/675/999 706/707/999 +f 691/689/1000 666/704/1000 706/707/1000 +f 679/693/1001 691/689/1001 706/707/1001 +f 666/704/1002 696/698/1002 706/707/1002 +f 696/698/1003 671/672/1003 706/707/1003 +f 702/702/1004 679/693/1004 706/707/1004 +f 680/675/1005 702/702/1005 706/707/1005 +f 682/683/1006 677/666/1006 707/668/1006 +f 676/681/1007 685/680/1007 707/668/1007 +f 686/682/1008 682/683/1008 707/668/1008 +f 685/680/1009 686/682/1009 707/668/1009 +f 697/667/1010 676/681/1010 707/668/1010 +o Bowl_hull_22 +v -0.013373 0.082336 0.050235 +v -0.009065 0.039663 -0.017450 +v -0.009496 0.039663 -0.017450 +v -0.002167 0.041389 -0.023911 +v -0.001305 0.079318 0.049796 +v -0.020704 0.040528 -0.009250 +v -0.020704 0.040528 -0.017011 +v -0.020704 0.076735 0.050235 +v -0.001305 0.082771 0.048504 +v -0.001305 0.040532 -0.017880 +v -0.020704 0.079753 0.047643 +v -0.011649 0.040097 -0.023481 +v -0.011649 0.081045 0.046774 +v -0.001305 0.039663 -0.025642 +v -0.008201 0.042689 -0.020465 +v -0.019840 0.039667 -0.010973 +v -0.001305 0.078462 0.048504 +v -0.020704 0.060791 0.015735 +v -0.006478 0.082340 0.048073 +v -0.020704 0.039667 -0.017450 +v -0.017686 0.081475 0.049366 +v -0.001305 0.083206 0.050235 +v -0.005616 0.040097 -0.025642 +v -0.020271 0.040528 -0.009250 +v -0.020271 0.076735 0.050235 +v -0.015960 0.041824 -0.018311 +v -0.001305 0.039663 -0.019604 +v -0.020704 0.080614 0.050235 +v -0.001305 0.041389 -0.023911 +v -0.001305 0.079753 0.050235 +v -0.003892 0.083206 0.049366 +v -0.009496 0.042689 -0.020034 +v -0.009496 0.039663 -0.024342 +v -0.020704 0.050011 -0.001919 +v -0.012942 0.082336 0.049366 +v -0.005616 0.046568 -0.014427 +v -0.020704 0.075444 0.040312 +v -0.018115 0.040097 -0.019596 +v -0.001305 0.042250 -0.014858 +vt 0.977193 0.108947 +vt 0.216034 0.980129 +vt 0.142130 0.940583 +vt 0.113743 0.980129 +vt 0.216034 0.980129 +vt 1.000000 0.148590 +vt 0.977193 0.009984 +vt 0.994225 0.089272 +vt 0.102291 0.980031 +vt 0.965838 0.079287 +vt 0.107968 1.000000 +vt 0.107968 1.000000 +vt 0.000000 1.000000 +vt 0.193324 0.999902 +vt 0.545321 0.514781 +vt 0.107968 0.999902 +vt 1.000000 0.019969 +vt 1.000000 0.000000 +vt 0.068226 0.930501 +vt 0.954385 0.049628 +vt 0.000000 0.990016 +vt 1.000000 0.148590 +vt 0.028485 0.990016 +vt 0.096613 0.950372 +vt 0.079581 1.000000 +vt 1.000000 0.059514 +vt 0.988547 0.039742 +vt 0.022807 0.960356 +vt 0.022807 0.960356 +vt 1.000000 0.079287 +vt 0.988547 0.000000 +vt 0.971515 0.019871 +vt 0.073904 0.930501 +vt 0.017130 1.000000 +vt 0.312647 0.762334 +vt 0.988547 0.019969 +vt 0.147807 0.841425 +vt 0.869225 0.178250 +vt 0.079679 0.990016 +vn 0.2200 -0.8469 0.4840 +vn -1.0000 0.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 -1.0000 0.0006 +vn -0.0004 -1.0000 0.0000 +vn -0.6164 -0.7832 0.0822 +vn 0.0000 0.0000 1.0000 +vn -0.1338 0.8578 -0.4962 +vn 0.0000 -0.8542 0.5199 +vn 0.0000 -0.8946 0.4470 +vn 0.2183 -0.8500 0.4793 +vn 0.1242 -0.8476 0.5159 +vn 0.1253 -0.8269 0.5482 +vn -0.2654 0.8261 -0.4972 +vn 0.0003 -1.0000 0.0012 +vn 0.2051 -0.8738 0.4409 +vn -0.2254 0.9597 0.1680 +vn -0.3400 0.8925 -0.2964 +vn 0.0000 0.8682 -0.4962 +vn 0.0000 0.8014 -0.5981 +vn 0.0712 0.7062 -0.7044 +vn 0.1122 -0.7054 0.6998 +vn -0.0193 0.8682 -0.4959 +vn -0.0423 0.8673 -0.4959 +vn -0.0703 0.9754 0.2092 +vn 0.0816 0.9666 -0.2428 +vn -0.1992 0.8452 -0.4959 +vn -0.1650 0.8525 -0.4959 +vn -0.1843 0.8374 -0.5145 +vn -0.1687 0.8451 -0.5073 +vn -0.0848 -0.8409 -0.5344 +vn -0.3310 0.1915 -0.9240 +vn -0.3113 0.8111 -0.4952 +vn -0.1383 0.8572 -0.4961 +vn -0.0970 0.8707 -0.4822 +vn -0.1779 0.9801 -0.0882 +vn -0.1551 0.8545 -0.4957 +vn -0.0864 0.8991 -0.4291 +vn -0.0955 0.9943 -0.0474 +vn -0.0652 0.8657 -0.4964 +vn -0.0918 0.8637 -0.4956 +vn -0.0734 0.8639 -0.4984 +vn -0.1183 0.8601 -0.4962 +vn -0.2471 0.8323 -0.4962 +vn -0.2046 0.8439 -0.4960 +vn -0.2169 0.8405 -0.4965 +vn -0.6315 0.3517 -0.6910 +vn -0.3169 0.7883 -0.5275 +vn -0.3920 -0.6485 -0.6525 +vn -0.3535 -0.7384 -0.5743 +vn -0.3637 0.7887 -0.4956 +vn -0.3421 0.7973 -0.4973 +vn 0.2195 -0.8482 0.4820 +usemtl None +s off +f 724/708/1011 731/709/1011 746/710/1011 +f 714/711/1012 713/712/1012 715/713/1012 +f 716/714/1013 712/715/1013 717/716/1013 +f 714/711/1012 715/713/1012 718/717/1012 +f 709/718/1014 710/719/1014 721/720/1014 +f 716/714/1013 717/716/1013 721/720/1013 +f 710/719/1015 709/718/1015 723/721/1015 +f 717/716/1013 712/715/1013 724/708/1013 +f 714/711/1012 718/717/1012 725/722/1012 +f 713/712/1012 714/711/1012 727/723/1012 +f 710/719/1016 723/721/1016 727/723/1016 +f 723/721/1017 713/712/1017 727/723/1017 +f 708/724/1018 715/713/1018 729/725/1018 +f 712/715/1013 716/714/1013 729/725/1013 +f 722/726/1019 720/727/1019 730/728/1019 +f 715/713/1020 713/712/1020 731/709/1020 +f 713/712/1021 723/721/1021 731/709/1021 +f 723/721/1022 717/716/1022 731/709/1022 +f 731/709/1023 724/708/1023 732/729/1023 +f 724/708/1024 712/715/1024 732/729/1024 +f 729/725/1018 715/713/1018 732/729/1018 +f 715/713/1020 731/709/1020 732/729/1020 +f 725/722/1025 719/730/1025 733/731/1025 +f 709/718/1014 721/720/1014 734/732/1014 +f 721/720/1013 717/716/1013 734/732/1013 +f 723/721/1026 709/718/1026 734/732/1026 +f 717/716/1027 723/721/1027 734/732/1027 +f 715/713/1018 708/724/1018 735/733/1018 +f 718/717/1012 715/713/1012 735/733/1012 +f 708/724/1028 728/734/1028 735/733/1028 +f 728/734/1029 718/717/1029 735/733/1029 +f 711/735/1030 716/714/1030 736/736/1030 +f 716/714/1013 721/720/1013 736/736/1013 +f 730/728/1031 711/735/1031 736/736/1031 +f 721/720/1032 730/728/1032 736/736/1032 +f 712/715/1013 729/725/1013 737/737/1013 +f 732/729/1033 712/715/1033 737/737/1033 +f 729/725/1018 732/729/1018 737/737/1018 +f 716/714/1034 711/735/1034 738/738/1034 +f 711/735/1035 726/739/1035 738/738/1035 +f 708/724/1036 729/725/1036 738/738/1036 +f 729/725/1037 716/714/1037 738/738/1037 +f 718/717/1038 728/734/1038 739/740/1038 +f 728/734/1039 722/726/1039 739/740/1039 +f 730/728/1040 719/730/1040 739/740/1040 +f 722/726/1041 730/728/1041 739/740/1041 +f 721/720/1014 710/719/1014 740/741/1014 +f 710/719/1016 727/723/1016 740/741/1016 +f 730/728/1042 721/720/1042 740/741/1042 +f 719/730/1043 730/728/1043 740/741/1043 +f 714/711/1012 725/722/1012 741/742/1012 +f 725/722/1044 733/731/1044 741/742/1044 +f 720/727/1045 722/726/1045 742/743/1045 +f 726/739/1046 720/727/1046 742/743/1046 +f 728/734/1047 708/724/1047 742/743/1047 +f 722/726/1048 728/734/1048 742/743/1048 +f 738/738/1049 726/739/1049 742/743/1049 +f 708/724/1050 738/738/1050 742/743/1050 +f 726/739/1051 711/735/1051 743/744/1051 +f 720/727/1052 726/739/1052 743/744/1052 +f 711/735/1053 730/728/1053 743/744/1053 +f 730/728/1054 720/727/1054 743/744/1054 +f 725/722/1012 718/717/1012 744/745/1012 +f 719/730/1055 725/722/1055 744/745/1055 +f 718/717/1056 739/740/1056 744/745/1056 +f 739/740/1057 719/730/1057 744/745/1057 +f 727/723/1058 714/711/1058 745/746/1058 +f 733/731/1059 719/730/1059 745/746/1059 +f 719/730/1060 740/741/1060 745/746/1060 +f 740/741/1061 727/723/1061 745/746/1061 +f 714/711/1062 741/742/1062 745/746/1062 +f 741/742/1063 733/731/1063 745/746/1063 +f 717/716/1013 724/708/1013 746/710/1013 +f 731/709/1064 717/716/1064 746/710/1064 +o Bowl_hull_23 +v -0.013374 -0.042685 -0.018306 +v 0.002577 -0.083206 0.050235 +v -0.006045 -0.083206 0.050235 +v -0.012943 -0.077597 0.048935 +v 0.002577 -0.040959 -0.017013 +v 0.002144 -0.041389 -0.023904 +v -0.013374 -0.040098 -0.015293 +v 0.002577 -0.078893 0.049371 +v -0.013374 -0.081475 0.048078 +v -0.006045 -0.040529 -0.024768 +v -0.002598 -0.082771 0.048507 +v -0.012943 -0.042685 -0.010544 +v 0.002577 -0.040098 -0.025211 +v -0.013374 -0.078462 0.050235 +v 0.002577 -0.083206 0.049371 +v -0.013374 -0.040098 -0.021755 +v -0.006476 -0.078893 0.042037 +v -0.002167 -0.041389 -0.023904 +v -0.012512 -0.056911 0.005400 +v -0.012943 -0.082336 0.049371 +v 0.002577 -0.040098 -0.018742 +v 0.002577 -0.079754 0.050235 +v -0.010356 -0.040959 -0.022611 +v 0.002577 -0.067254 0.021337 +v -0.006476 -0.043976 -0.018742 +v -0.013374 -0.082336 0.050235 +v -0.011218 -0.082336 0.048935 +v -0.013374 -0.065528 0.020480 +v 0.002577 -0.040529 -0.025211 +v -0.008200 -0.045702 -0.015293 +v -0.005613 -0.046567 -0.014421 +v -0.012512 -0.040529 -0.014429 +vt 0.085748 0.000000 +vt 0.131460 0.000000 +vt 0.142913 0.009985 +vt 1.000000 1.000000 +vt 0.108653 0.019971 +vt 0.988547 0.899951 +vt 0.091523 0.060010 +vt 0.971417 0.959863 +vt 0.982772 0.869897 +vt 0.194401 0.060010 +vt 0.000000 0.000000 +vt 1.000000 1.000000 +vt 1.000000 0.889966 +vt 0.988547 1.000000 +vt 0.977095 0.989917 +vt 0.045810 0.000000 +vt 0.005873 0.009985 +vt 0.891347 0.899951 +vt 0.017326 0.029956 +vt 1.000000 0.919921 +vt 0.034456 0.019971 +vt 0.405736 0.390015 +vt 0.616973 0.629956 +vt 0.017326 0.029956 +vt 1.000000 0.979834 +vt 0.988547 0.979834 +vt 0.982772 0.979834 +vt 0.085748 0.089966 +vt 0.605619 0.589917 +vt 0.000000 0.009985 +vt 0.131460 0.130005 +vt 0.143011 0.150073 +vn 0.0817 0.9222 0.3779 +vn 1.0000 0.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0577 0.8610 0.5054 +vn 0.1096 0.8630 0.4932 +vn 0.0000 0.0000 1.0000 +vn 0.0528 0.8231 0.5654 +vn -0.2004 0.8449 0.4959 +vn -0.3609 0.8048 0.4712 +vn 0.0000 -1.0000 0.0000 +vn -0.0300 -0.9535 -0.2998 +vn -0.0000 1.0000 0.0000 +vn -0.0625 0.9554 -0.2886 +vn -0.0401 -0.8674 -0.4960 +vn 0.0573 0.7072 0.7046 +vn -0.3702 -0.7431 -0.5574 +vn -0.3611 -0.4568 -0.8130 +vn -0.2266 -0.8388 -0.4951 +vn 0.0096 -0.8691 -0.4945 +vn -0.0017 -0.8682 -0.4962 +vn 0.0000 -0.8681 -0.4963 +vn -0.1176 -0.9913 -0.0586 +vn -0.5966 -0.7453 -0.2976 +vn -0.0649 -0.9294 -0.3633 +vn -0.0680 -0.8732 -0.4827 +vn -0.0797 -0.9456 -0.3154 +vn -0.1252 -0.8593 -0.4959 +vn -0.2553 -0.8331 -0.4907 +vn -0.2235 -0.8439 -0.4877 +vn -0.0513 0.0000 -0.9987 +vn 0.0000 -0.8351 -0.5500 +vn -0.0323 -0.7768 -0.6289 +vn 0.2161 -0.8467 -0.4861 +vn -0.1660 -0.8491 -0.5014 +vn -0.1797 -0.8488 -0.4972 +vn -0.1430 -0.8546 -0.4992 +vn -0.1330 -0.8581 -0.4959 +vn -0.1677 -0.8518 -0.4963 +vn -0.1480 -0.8558 -0.4957 +vn -0.0659 -0.8655 -0.4966 +vn -0.0800 -0.8623 -0.5000 +vn -0.0877 -0.8619 -0.4994 +vn -0.0942 -0.8633 -0.4957 +vn -0.1052 -0.8620 -0.4959 +vn -0.0450 0.8755 0.4810 +vn 0.1089 0.8639 0.4917 +vn 0.1014 0.8905 0.4436 +usemtl None +s off +f 767/747/1065 753/748/1065 778/749/1065 +f 748/750/1066 751/751/1066 754/752/1066 +f 753/748/1067 747/753/1067 755/754/1067 +f 750/755/1068 754/752/1068 758/756/1068 +f 754/752/1069 751/751/1069 758/756/1069 +f 751/751/1066 748/750/1066 759/757/1066 +f 749/758/1070 748/750/1070 760/759/1070 +f 754/752/1071 750/755/1071 760/759/1071 +f 753/748/1067 755/754/1067 760/759/1067 +f 750/755/1072 758/756/1072 760/759/1072 +f 758/756/1073 753/748/1073 760/759/1073 +f 748/750/1074 749/758/1074 761/760/1074 +f 749/758/1075 757/761/1075 761/760/1075 +f 759/757/1066 748/750/1066 761/760/1066 +f 747/753/1067 753/748/1067 762/762/1067 +f 753/748/1076 759/757/1076 762/762/1076 +f 759/757/1077 756/763/1077 762/762/1077 +f 757/761/1078 763/764/1078 764/765/1078 +f 751/751/1066 759/757/1066 767/747/1066 +f 759/757/1076 753/748/1076 767/747/1076 +f 748/750/1066 754/752/1066 768/766/1066 +f 760/759/1070 748/750/1070 768/766/1070 +f 754/752/1079 760/759/1079 768/766/1079 +f 747/753/1080 762/762/1080 769/767/1080 +f 762/762/1081 756/763/1081 769/767/1081 +f 765/768/1082 747/753/1082 769/767/1082 +f 761/760/1083 757/761/1083 770/769/1083 +f 759/757/1066 761/760/1066 770/769/1066 +f 757/761/1084 764/765/1084 770/769/1084 +f 764/765/1085 752/770/1085 770/769/1085 +f 749/758/1070 760/759/1070 772/771/1070 +f 760/759/1067 755/754/1067 772/771/1067 +f 766/772/1086 749/758/1086 772/771/1086 +f 755/754/1087 766/772/1087 772/771/1087 +f 757/761/1088 749/758/1088 773/773/1088 +f 763/764/1089 757/761/1089 773/773/1089 +f 749/758/1090 766/772/1090 773/773/1090 +f 766/772/1091 771/774/1091 773/773/1091 +f 755/754/1067 747/753/1067 774/775/1067 +f 747/753/1092 765/768/1092 774/775/1092 +f 766/772/1093 755/754/1093 774/775/1093 +f 756/763/1094 759/757/1094 775/776/1094 +f 752/770/1095 764/765/1095 775/776/1095 +f 764/765/1096 756/763/1096 775/776/1096 +f 770/769/1097 752/770/1097 775/776/1097 +f 759/757/1066 770/769/1066 775/776/1066 +f 769/767/1098 756/763/1098 776/777/1098 +f 765/768/1099 769/767/1099 776/777/1099 +f 756/763/1100 771/774/1100 776/777/1100 +f 771/774/1101 766/772/1101 776/777/1101 +f 774/775/1102 765/768/1102 776/777/1102 +f 766/772/1103 774/775/1103 776/777/1103 +f 764/765/1104 763/764/1104 777/778/1104 +f 756/763/1105 764/765/1105 777/778/1105 +f 771/774/1106 756/763/1106 777/778/1106 +f 763/764/1107 773/773/1107 777/778/1107 +f 773/773/1108 771/774/1108 777/778/1108 +f 753/748/1109 758/756/1109 778/749/1109 +f 758/756/1110 751/751/1110 778/749/1110 +f 751/751/1111 767/747/1111 778/749/1111 +o Bowl_hull_24 +v -0.038377 0.028020 -0.013569 +v -0.009063 0.039229 -0.018312 +v -0.009063 0.039229 -0.018744 +v -0.039671 0.006898 -0.018312 +v -0.039671 0.039229 0.008847 +v -0.023292 0.037936 -0.018744 +v -0.040103 0.039659 0.002376 +v -0.040103 0.018973 -0.018744 +v -0.030186 0.032763 -0.018744 +v -0.020703 0.039662 -0.018312 +v -0.040103 0.006898 -0.018744 +v -0.040103 0.039659 0.008847 +v -0.009063 0.039662 -0.018312 +v -0.032774 0.039659 -0.006671 +v -0.040103 0.034918 -0.003660 +v -0.034928 0.027590 -0.018744 +v -0.040103 0.025435 -0.013569 +v -0.037945 0.039659 -0.000641 +v -0.032774 0.030175 -0.018744 +v -0.037945 0.023280 -0.018744 +v -0.027597 0.036211 -0.017018 +v -0.025443 0.039229 -0.014863 +vt 0.052663 0.541601 +vt 0.105325 0.402897 +vt 0.013215 0.472298 +vt 0.013215 1.000000 +vt 0.013215 1.000000 +vt 1.000000 0.013900 +vt 0.013215 0.013900 +vt 0.631461 0.000000 +vt 0.210552 0.319499 +vt 0.000000 0.625000 +vt 1.000000 0.000000 +vt 0.000098 0.000000 +vt 0.000098 0.000000 +vt 0.000000 1.000000 +vt 0.144773 0.000000 +vt 0.368442 0.166699 +vt 0.355325 0.055599 +vt 0.434221 0.000000 +vt 0.000098 0.069499 +vt 0.000098 0.236100 +vt 0.289546 0.236100 +vt 0.500000 0.069499 +vn -0.4880 0.7105 -0.5071 +vn 0.7262 -0.6875 0.0000 +vn 0.5620 -0.5320 0.6333 +vn 0.0000 0.0000 -1.0000 +vn -0.0253 0.2784 -0.9601 +vn 0.5854 -0.5620 -0.5844 +vn -1.0000 -0.0000 0.0000 +vn -0.5395 -0.5416 0.6447 +vn -0.0002 1.0000 0.0000 +vn -0.6081 -0.5114 0.6072 +vn 1.0000 0.0000 0.0000 +vn 0.6637 0.0000 0.7480 +vn 0.0000 0.7064 -0.7078 +vn 0.5493 0.5515 0.6278 +vn 0.0000 1.0000 0.0001 +vn -0.6770 0.5435 -0.4963 +vn -0.7344 0.4903 -0.4692 +vn -0.0007 1.0000 -0.0005 +vn -0.5771 0.6497 -0.4948 +vn -0.0015 1.0000 -0.0013 +vn -0.6537 0.5952 -0.4674 +vn -0.6284 0.6008 -0.4942 +vn -0.6661 0.5551 -0.4982 +vn -0.6136 0.6137 -0.4968 +vn -0.7045 0.4931 -0.5104 +vn -0.7804 0.3908 -0.4881 +vn -0.7201 0.4807 -0.5004 +vn -0.4923 0.6560 -0.5721 +vn -0.5542 0.6660 -0.4992 +vn -0.5054 0.7105 -0.4896 +vn -0.4256 0.7611 -0.4894 +vn -0.3275 0.8818 -0.3394 +usemtl None +s off +f 784/779/1112 799/780/1112 800/781/1112 +f 781/782/1113 780/783/1113 782/784/1113 +f 782/784/1114 780/783/1114 783/785/1114 +f 784/779/1115 781/782/1115 786/786/1115 +f 784/779/1115 786/786/1115 787/787/1115 +f 781/782/1116 784/779/1116 788/788/1116 +f 781/782/1117 782/784/1117 789/789/1117 +f 786/786/1115 781/782/1115 789/789/1115 +f 785/790/1118 786/786/1118 789/789/1118 +f 782/784/1119 783/785/1119 790/791/1119 +f 788/788/1120 785/790/1120 790/791/1120 +f 789/789/1121 782/784/1121 790/791/1121 +f 785/790/1118 789/789/1118 790/791/1118 +f 780/783/1122 781/782/1122 791/792/1122 +f 783/785/1123 780/783/1123 791/792/1123 +f 781/782/1124 788/788/1124 791/792/1124 +f 790/791/1125 783/785/1125 791/792/1125 +f 788/788/1126 790/791/1126 791/792/1126 +f 786/786/1118 785/790/1118 793/793/1118 +f 787/787/1115 786/786/1115 794/794/1115 +f 779/795/1127 793/793/1127 794/794/1127 +f 793/793/1128 779/795/1128 795/796/1128 +f 786/786/1118 793/793/1118 795/796/1118 +f 785/790/1129 788/788/1129 796/797/1129 +f 792/798/1130 787/787/1130 796/797/1130 +f 788/788/1131 792/798/1131 796/797/1131 +f 793/793/1132 785/790/1132 796/797/1132 +f 793/793/1133 796/797/1133 797/799/1133 +f 787/787/1115 794/794/1115 797/799/1115 +f 794/794/1134 793/793/1134 797/799/1134 +f 796/797/1135 787/787/1135 797/799/1135 +f 779/795/1136 794/794/1136 798/800/1136 +f 794/794/1115 786/786/1115 798/800/1115 +f 786/786/1137 795/796/1137 798/800/1137 +f 795/796/1138 779/795/1138 798/800/1138 +f 784/779/1139 787/787/1139 799/780/1139 +f 787/787/1140 792/798/1140 799/780/1140 +f 799/780/1141 792/798/1141 800/781/1141 +f 788/788/1142 784/779/1142 800/781/1142 +f 792/798/1143 788/788/1143 800/781/1143 +o Bowl_hull_25 +v 0.012492 0.077167 0.040309 +v 0.013355 0.040094 -0.015285 +v 0.013355 0.040959 -0.013565 +v -0.001301 0.040094 -0.018742 +v -0.001301 0.078462 0.048507 +v -0.001301 0.041394 -0.023904 +v -0.001301 0.082771 0.048507 +v 0.013355 0.078458 0.050235 +v 0.013355 0.040529 -0.021755 +v 0.006026 0.040529 -0.024775 +v 0.013355 0.082336 0.049799 +v 0.004301 0.083201 0.049371 +v -0.001301 0.083201 0.050235 +v 0.012923 0.076302 0.046778 +v 0.012923 0.053032 -0.001062 +v -0.001301 0.040094 -0.025211 +v 0.003439 0.041820 -0.023047 +v 0.009042 0.080619 0.045486 +v 0.012923 0.040959 -0.013565 +v -0.001301 0.079754 0.050235 +v -0.001301 0.042250 -0.014850 +v 0.013355 0.040094 -0.021755 +v 0.002577 0.067254 0.021337 +v 0.008611 0.043115 -0.019598 +v 0.013355 0.076302 0.039017 +v 0.013355 0.082336 0.050235 +v 0.010336 0.040959 -0.022619 +v 0.006456 0.043976 -0.018742 +vt 0.868442 0.139990 +vt 0.851312 0.160059 +vt 0.085748 0.909936 +vt 0.085748 1.000000 +vt 0.977095 0.109936 +vt 0.017326 0.969848 +vt 0.977095 0.009985 +vt 0.154366 0.979931 +vt 0.131558 1.000000 +vt 1.000000 0.110034 +vt 0.045810 0.989917 +vt 0.994225 0.020069 +vt 1.000000 0.000000 +vt 0.988547 0.000000 +vt 0.954190 0.160059 +vt 0.000000 1.000000 +vt 0.005775 0.989917 +vt 0.028681 0.959961 +vt 0.937060 0.059912 +vt 0.154366 0.979931 +vt 1.000000 0.079980 +vt 0.137334 0.949975 +vt 0.045810 1.000000 +vt 0.616973 0.369946 +vt 0.320086 0.699853 +vt 0.074393 0.929907 +vt 1.000000 0.020069 +vt 0.034358 0.979931 +vn 0.1200 0.8602 -0.4957 +vn -1.0000 0.0000 0.0000 +vn 1.0000 -0.0000 0.0000 +vn -0.0372 0.9697 -0.2415 +vn 0.2421 -0.8365 0.4917 +vn -0.0632 -0.8431 0.5340 +vn 0.0000 -1.0000 0.0000 +vn -0.0001 0.7091 -0.7051 +vn 0.0292 0.8212 -0.5700 +vn 0.0657 0.8660 -0.4957 +vn 0.1393 0.8642 -0.4834 +vn 0.1060 0.8828 -0.4576 +vn 0.0000 -0.8934 0.4492 +vn -0.1006 -0.8988 0.4266 +vn 0.0000 -0.8629 0.5054 +vn -0.0695 -0.8608 0.5042 +vn -0.0706 -0.7991 0.5971 +vn 0.0000 0.0000 1.0000 +vn -0.1223 -0.8681 0.4810 +vn -0.1227 -0.8616 0.4925 +vn 0.3810 0.0000 -0.9246 +vn 0.0750 -0.9451 -0.3179 +vn -0.0019 0.8682 -0.4961 +vn 0.0096 0.8689 -0.4949 +vn 0.0118 0.8677 -0.4970 +vn 0.0447 0.8671 -0.4960 +vn 0.1748 0.8507 -0.4958 +vn 0.1420 0.8638 -0.4834 +vn 0.5418 0.7243 -0.4264 +vn 0.0951 0.9955 0.0000 +vn 0.0550 0.9325 0.3569 +vn 0.2952 0.6324 -0.7162 +vn 0.2600 0.8288 -0.4954 +vn 0.1692 0.8453 -0.5069 +vn 0.1886 0.8470 -0.4970 +vn 0.0966 0.8612 -0.4990 +vn 0.0910 0.8634 -0.4962 +vn 0.1172 0.8606 -0.4957 +vn 0.1433 0.8549 -0.4987 +vn 0.1446 0.8560 -0.4963 +usemtl None +s off +f 801/801/1144 825/802/1144 828/803/1144 +f 804/804/1145 805/805/1145 806/806/1145 +f 806/806/1145 805/805/1145 807/807/1145 +f 803/808/1146 802/809/1146 808/810/1146 +f 808/810/1146 802/809/1146 809/811/1146 +f 808/810/1146 809/811/1146 811/812/1146 +f 807/807/1145 805/805/1145 813/813/1145 +f 812/814/1147 807/807/1147 813/813/1147 +f 803/808/1148 808/810/1148 814/815/1148 +f 808/810/1149 805/805/1149 814/815/1149 +f 802/809/1150 804/804/1150 816/816/1150 +f 804/804/1145 806/806/1145 816/816/1145 +f 806/806/1151 810/817/1151 816/816/1151 +f 810/817/1152 806/806/1152 817/818/1152 +f 817/818/1153 812/814/1153 818/819/1153 +f 811/812/1154 801/801/1154 818/819/1154 +f 812/814/1155 811/812/1155 818/819/1155 +f 802/809/1156 803/808/1156 819/820/1156 +f 804/804/1157 802/809/1157 819/820/1157 +f 803/808/1158 814/815/1158 819/820/1158 +f 814/815/1159 805/805/1159 819/820/1159 +f 805/805/1160 808/810/1160 820/821/1160 +f 813/813/1145 805/805/1145 820/821/1145 +f 808/810/1161 813/813/1161 820/821/1161 +f 805/805/1145 804/804/1145 821/822/1145 +f 804/804/1162 819/820/1162 821/822/1162 +f 819/820/1163 805/805/1163 821/822/1163 +f 809/811/1146 802/809/1146 822/823/1146 +f 810/817/1164 809/811/1164 822/823/1164 +f 802/809/1150 816/816/1150 822/823/1150 +f 816/816/1165 810/817/1165 822/823/1165 +f 806/806/1166 807/807/1166 823/824/1166 +f 807/807/1167 812/814/1167 823/824/1167 +f 817/818/1168 806/806/1168 823/824/1168 +f 812/814/1169 817/818/1169 823/824/1169 +f 815/825/1170 824/826/1170 825/802/1170 +f 801/801/1171 811/812/1171 825/802/1171 +f 811/812/1146 809/811/1146 825/802/1146 +f 809/811/1172 815/825/1172 825/802/1172 +f 808/810/1146 811/812/1146 826/827/1146 +f 811/812/1173 812/814/1173 826/827/1173 +f 812/814/1174 813/813/1174 826/827/1174 +f 813/813/1161 808/810/1161 826/827/1161 +f 809/811/1175 810/817/1175 827/828/1175 +f 815/825/1176 809/811/1176 827/828/1176 +f 810/817/1177 824/826/1177 827/828/1177 +f 824/826/1178 815/825/1178 827/828/1178 +f 810/817/1179 817/818/1179 828/803/1179 +f 817/818/1180 818/819/1180 828/803/1180 +f 818/819/1181 801/801/1181 828/803/1181 +f 824/826/1182 810/817/1182 828/803/1182 +f 825/802/1183 824/826/1183 828/803/1183 +o Bowl_hull_26 +v 0.013787 0.064667 0.019187 +v 0.025857 0.040094 -0.005807 +v 0.025857 0.040532 -0.004939 +v 0.025857 0.078461 0.048077 +v 0.013356 0.078032 0.049800 +v 0.013356 0.040528 -0.021331 +v 0.025857 0.040962 -0.011846 +v 0.013356 0.040528 -0.013996 +v 0.025857 0.075011 0.049800 +v 0.013356 0.081912 0.048939 +v 0.016803 0.040958 -0.019173 +v 0.024994 0.040094 -0.005807 +v 0.025857 0.059067 0.016175 +v 0.022838 0.080181 0.049366 +v 0.014217 0.045268 -0.013569 +v 0.024563 0.075440 0.050235 +v 0.015943 0.081912 0.050235 +v 0.022838 0.040528 -0.015292 +v 0.014217 0.040094 -0.021331 +v 0.025857 0.079325 0.050235 +v 0.018961 0.080181 0.047643 +v 0.025857 0.069403 0.032988 +v 0.025857 0.040094 -0.012273 +v 0.013356 0.040094 -0.014858 +v 0.013356 0.078461 0.050235 +v 0.013787 0.054323 0.001520 +v 0.022838 0.074577 0.039881 +v 0.015080 0.081478 0.048504 +v 0.025425 0.050016 0.001527 +v 0.013356 0.076738 0.047643 +v 0.014217 0.041387 -0.020035 +v 0.013356 0.048719 -0.007965 +v 0.019821 0.040962 -0.017009 +vt 0.319401 0.762725 +vt 0.084377 0.989624 +vt 0.060395 0.979248 +vt 0.229052 0.989526 +vt 0.216915 1.000000 +vt 0.969851 0.082518 +vt 0.132537 0.979248 +vt 0.993931 0.092796 +vt 0.000000 0.989624 +vt 0.102486 0.989624 +vt 0.993931 0.165035 +vt 0.981891 0.000000 +vt 0.216915 1.000000 +vt 0.524080 0.546300 +vt 1.000000 0.154757 +vt 0.030149 0.979346 +vt 0.000000 1.000000 +vt 1.000000 0.061864 +vt 0.987862 0.041406 +vt 1.000000 0.000000 +vt 0.759006 0.299139 +vt 0.126566 1.000000 +vt 0.090446 1.000000 +vt 1.000000 0.082518 +vt 0.566171 0.412392 +vt 0.963782 0.041406 +vt 0.319303 0.659749 +vt 0.855325 0.175411 +vt 0.108457 0.876272 +vt 0.975822 0.010376 +vt 0.963782 0.123727 +vt 0.018109 0.969068 +vt 0.186766 0.793755 +vn 0.3939 0.7733 -0.4968 +vn 1.0000 0.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0000 -0.8929 0.4502 +vn -0.1017 -0.8418 0.5302 +vn -0.1063 -0.8414 0.5299 +vn -0.2115 -0.8274 0.5202 +vn 0.3349 0.6650 -0.6676 +vn 0.0000 -1.0000 0.0000 +vn 0.5220 0.3641 -0.7713 +vn 0.3470 0.8707 -0.3485 +vn 0.2880 -0.0959 0.9528 +vn 0.2518 0.9649 0.0752 +vn 0.0000 0.0000 1.0000 +vn 0.3226 0.8064 -0.4957 +vn 0.6928 0.3186 -0.6470 +vn 0.3897 -0.7729 -0.5007 +vn -0.3302 -0.8431 0.4245 +vn -0.4490 -0.8915 -0.0598 +vn -0.1882 -0.6981 0.6908 +vn -0.4246 0.3183 0.8476 +vn 0.1878 0.8476 -0.4963 +vn 0.2203 0.8401 -0.4957 +vn 0.2635 0.8305 -0.4907 +vn 0.2822 0.8225 -0.4938 +vn 0.2283 0.8377 -0.4962 +vn 0.2234 0.8392 -0.4958 +vn 0.0914 0.8621 -0.4984 +vn 0.1911 0.9254 -0.3274 +vn 0.1568 0.9367 -0.3131 +vn 0.1745 0.8508 -0.4956 +vn 0.1955 0.8766 -0.4398 +vn 0.6270 0.6543 -0.4228 +vn 0.4522 0.7452 -0.4900 +vn -1.0000 0.0001 0.0000 +vn -0.3211 -0.8123 0.4870 +vn -0.3622 -0.8037 0.4721 +vn 0.3327 0.6688 -0.6648 +vn 0.3007 0.8144 -0.4963 +vn 0.2781 0.8227 -0.4958 +vn 0.2656 0.8266 -0.4961 +vn -0.2139 0.8438 -0.4922 +vn -0.1005 0.8586 -0.5027 +vn 0.1069 0.8539 -0.5093 +vn -0.0646 0.8509 -0.5214 +vn 0.0866 0.8542 -0.5127 +vn 0.3552 0.7919 -0.4967 +vn 0.4478 0.6390 -0.6255 +vn 0.3721 0.7847 -0.4958 +usemtl None +s off +f 857/829/1184 846/830/1184 861/831/1184 +f 831/832/1185 830/833/1185 832/834/1185 +f 832/834/1185 830/833/1185 835/835/1185 +f 833/836/1186 834/837/1186 836/838/1186 +f 831/832/1185 832/834/1185 837/839/1185 +f 834/837/1186 833/836/1186 838/840/1186 +f 830/833/1187 831/832/1187 840/841/1187 +f 832/834/1185 835/835/1185 841/842/1185 +f 831/832/1188 837/839/1188 844/843/1188 +f 840/841/1189 831/832/1189 844/843/1189 +f 833/836/1190 840/841/1190 844/843/1190 +f 834/837/1191 839/844/1191 847/845/1191 +f 830/833/1192 840/841/1192 847/845/1192 +f 839/844/1193 846/830/1193 847/845/1193 +f 837/839/1185 832/834/1185 848/846/1185 +f 832/834/1194 842/847/1194 848/846/1194 +f 844/843/1195 837/839/1195 848/846/1195 +f 842/847/1196 845/848/1196 848/846/1196 +f 845/848/1197 844/843/1197 848/846/1197 +f 832/834/1185 841/842/1185 850/849/1185 +f 841/842/1198 839/844/1198 850/849/1198 +f 835/835/1185 830/833/1185 851/850/1185 +f 846/830/1199 835/835/1199 851/850/1199 +f 830/833/1192 847/845/1192 851/850/1192 +f 847/845/1200 846/830/1200 851/850/1200 +f 836/838/1186 834/837/1186 852/851/1186 +f 840/841/1201 836/838/1201 852/851/1201 +f 834/837/1202 847/845/1202 852/851/1202 +f 847/845/1192 840/841/1192 852/851/1192 +f 838/840/1186 833/836/1186 853/852/1186 +f 833/836/1203 844/843/1203 853/852/1203 +f 844/843/1197 845/848/1197 853/852/1197 +f 845/848/1204 838/840/1204 853/852/1204 +f 829/853/1205 849/854/1205 854/855/1205 +f 849/854/1206 842/847/1206 854/855/1206 +f 842/847/1207 832/834/1207 855/856/1207 +f 832/834/1208 850/849/1208 855/856/1208 +f 843/857/1209 854/855/1209 855/856/1209 +f 854/855/1210 842/847/1210 855/856/1210 +f 829/853/1211 838/840/1211 856/858/1211 +f 845/848/1212 842/847/1212 856/858/1212 +f 838/840/1213 845/848/1213 856/858/1213 +f 849/854/1214 829/853/1214 856/858/1214 +f 842/847/1215 849/854/1215 856/858/1215 +f 841/842/1216 835/835/1216 857/829/1216 +f 835/835/1217 846/830/1217 857/829/1217 +f 833/836/1218 836/838/1218 858/859/1218 +f 840/841/1219 833/836/1219 858/859/1219 +f 836/838/1220 840/841/1220 858/859/1220 +f 839/844/1221 834/837/1221 859/860/1221 +f 850/849/1222 839/844/1222 859/860/1222 +f 855/856/1223 850/849/1223 859/860/1223 +f 843/857/1224 855/856/1224 859/860/1224 +f 838/840/1225 829/853/1225 860/861/1225 +f 834/837/1186 838/840/1186 860/861/1186 +f 829/853/1226 854/855/1226 860/861/1226 +f 854/855/1227 843/857/1227 860/861/1227 +f 859/860/1228 834/837/1228 860/861/1228 +f 843/857/1229 859/860/1229 860/861/1229 +f 839/844/1230 841/842/1230 861/831/1230 +f 846/830/1231 839/844/1231 861/831/1231 +f 841/842/1232 857/829/1232 861/831/1232 +o Bowl_hull_27 +v 0.027151 0.046562 -0.002360 +v 0.043964 0.040094 0.014886 +v 0.043531 0.040094 0.014886 +v 0.025857 0.078894 0.050235 +v 0.043964 0.070269 0.048503 +v 0.025857 0.075013 0.050235 +v 0.025857 0.040094 -0.005374 +v 0.043964 0.040531 0.007989 +v 0.043531 0.066387 0.050235 +v 0.026289 0.040960 -0.011415 +v 0.030600 0.077599 0.049372 +v 0.043531 0.053463 0.023934 +v 0.025857 0.062077 0.021345 +v 0.038360 0.073288 0.048071 +v 0.034049 0.040527 -0.004080 +v 0.043964 0.070698 0.050235 +v 0.025857 0.040094 -0.011846 +v 0.026289 0.055620 0.011009 +v 0.040945 0.058203 0.027811 +v 0.026720 0.078461 0.048509 +v 0.025857 0.040531 -0.004511 +v 0.042668 0.040094 0.014029 +v 0.043964 0.066387 0.050235 +v 0.043964 0.040094 0.007989 +v 0.042238 0.069407 0.045489 +v 0.028014 0.041389 -0.009257 +v 0.043964 0.047857 0.017043 +v 0.034480 0.075442 0.048509 +v 0.040084 0.073288 0.050235 +v 0.026289 0.062077 0.021345 +v 0.043964 0.062077 0.036434 +v 0.033188 0.043117 -0.001497 +v 0.026289 0.049581 0.001523 +v 0.025857 0.078028 0.047646 +v 0.040084 0.041389 0.004112 +v 0.025857 0.049581 0.001523 +vt 0.368148 0.599843 +vt 0.215348 0.755482 +vt 0.215348 0.755482 +vt 1.000000 0.100039 +vt 1.000000 0.000000 +vt 0.104248 1.000000 +vt 0.430599 1.000000 +vt 0.430599 1.000000 +vt 0.972103 0.222298 +vt 0.319499 0.988743 +vt 1.000000 0.322337 +vt 0.534652 0.433438 +vt 1.000000 0.211237 +vt 0.000000 1.000000 +vt 0.006950 0.977682 +vt 0.125098 0.988841 +vt 0.986100 0.033379 +vt 0.972201 0.011159 +vt 0.118148 0.988743 +vt 0.416797 1.000000 +vt 1.000000 0.322337 +vt 0.319499 1.000000 +vt 0.152800 0.833301 +vt 0.965153 0.144479 +vt 0.923551 0.244518 +vt 0.638802 0.533281 +vt 0.041699 0.966621 +vt 0.465348 0.799922 +vt 0.576351 0.655442 +vt 0.972201 0.088978 +vt 1.000000 0.144479 +vt 0.534652 0.433438 +vt 0.777702 0.433438 +vt 0.166699 0.922083 +vt 0.958301 0.022318 +vt 0.257048 0.966621 +vn 0.0000 0.8436 -0.5370 +vn -1.0000 0.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn 1.0000 -0.0000 0.0000 +vn 0.0000 -0.8024 0.5968 +vn -0.3646 -0.7471 0.5557 +vn 0.0000 0.0000 1.0000 +vn 0.6874 0.0185 -0.7261 +vn 0.2409 0.9630 -0.1211 +vn -0.4622 -0.7912 0.4005 +vn -0.4798 -0.7322 0.4834 +vn -0.5206 -0.7224 0.4550 +vn 0.7727 0.0000 -0.6348 +vn 0.3468 -0.8829 -0.3166 +vn 0.4269 0.7563 -0.4957 +vn 0.4459 0.7600 -0.4728 +vn 0.4752 0.7271 -0.4956 +vn 0.4428 0.7430 -0.5018 +vn 0.5772 0.5784 -0.5765 +vn 0.4568 0.7382 -0.4965 +vn 0.5726 0.6532 -0.4954 +vn 0.3780 0.7818 -0.4958 +vn 0.3118 0.7912 0.5261 +vn 0.4627 0.8061 -0.3689 +vn 0.5438 0.8146 -0.2019 +vn 0.4182 0.8641 -0.2799 +vn 0.4267 0.8380 -0.3402 +vn 0.0000 0.8481 -0.5298 +vn 0.2921 0.8169 -0.4974 +vn 0.3354 0.8013 -0.4954 +vn 0.3495 0.7947 -0.4964 +vn 0.5260 0.6917 -0.4949 +vn 0.4935 0.7196 -0.4885 +vn 0.4822 0.7236 -0.4939 +vn 0.7176 0.5617 -0.4119 +vn 0.5444 0.6761 -0.4965 +vn 0.5256 0.6918 -0.4952 +vn 0.5102 0.7023 -0.4965 +vn 0.5307 0.6804 -0.5054 +vn 0.3850 0.7680 -0.5118 +vn 0.4229 0.7584 -0.4959 +vn 0.3826 0.7794 -0.4962 +vn -0.1566 0.9366 -0.3133 +vn 0.0000 0.8550 -0.5186 +vn 0.0878 0.8524 -0.5155 +vn 0.6553 0.5296 -0.5386 +vn 0.6250 0.6069 -0.4910 +vn 0.5822 0.6438 -0.4967 +vn -0.7260 0.5609 -0.3980 +vn -0.1151 0.8403 -0.5297 +vn 0.0000 0.8322 -0.5545 +usemtl None +s off +f 879/862/1233 894/863/1233 897/864/1233 +f 867/865/1234 865/866/1234 868/867/1234 +f 863/868/1235 864/869/1235 868/867/1235 +f 866/870/1236 863/868/1236 869/871/1236 +f 864/869/1237 863/868/1237 870/872/1237 +f 867/865/1238 864/869/1238 870/872/1238 +f 865/866/1239 867/865/1239 870/872/1239 +f 868/867/1234 865/866/1234 874/873/1234 +f 863/868/1236 866/870/1236 877/874/1236 +f 865/866/1239 870/872/1239 877/874/1239 +f 863/868/1235 868/867/1235 878/875/1235 +f 868/867/1234 874/873/1234 878/875/1234 +f 871/876/1240 876/877/1240 878/875/1240 +f 865/866/1241 872/878/1241 881/879/1241 +f 867/865/1234 868/867/1234 882/880/1234 +f 882/880/1242 868/867/1242 883/881/1242 +f 864/869/1243 867/865/1243 883/881/1243 +f 868/867/1235 864/869/1235 883/881/1235 +f 867/865/1244 882/880/1244 883/881/1244 +f 870/872/1237 863/868/1237 884/882/1237 +f 863/868/1236 877/874/1236 884/882/1236 +f 877/874/1239 870/872/1239 884/882/1239 +f 869/871/1236 863/868/1236 885/883/1236 +f 876/877/1245 869/871/1245 885/883/1245 +f 863/868/1235 878/875/1235 885/883/1235 +f 878/875/1246 876/877/1246 885/883/1246 +f 862/884/1247 875/885/1247 886/886/1247 +f 875/885/1248 866/870/1248 886/886/1248 +f 886/886/1249 880/887/1249 887/888/1249 +f 871/876/1250 862/884/1250 887/888/1250 +f 876/877/1251 871/876/1251 887/888/1251 +f 862/884/1252 886/886/1252 887/888/1252 +f 866/870/1236 869/871/1236 888/889/1236 +f 876/877/1253 873/890/1253 888/889/1253 +f 875/885/1254 879/862/1254 889/891/1254 +f 872/878/1255 865/866/1255 890/892/1255 +f 866/870/1256 875/885/1256 890/892/1256 +f 877/874/1257 866/870/1257 890/892/1257 +f 865/866/1239 877/874/1239 890/892/1239 +f 889/891/1258 872/878/1258 890/892/1258 +f 875/885/1259 889/891/1259 890/892/1259 +f 879/862/1260 874/873/1260 891/893/1260 +f 881/879/1261 872/878/1261 891/893/1261 +f 872/878/1262 889/891/1262 891/893/1262 +f 889/891/1263 879/862/1263 891/893/1263 +f 873/890/1264 880/887/1264 892/894/1264 +f 886/886/1265 866/870/1265 892/894/1265 +f 880/887/1266 886/886/1266 892/894/1266 +f 866/870/1236 888/889/1236 892/894/1236 +f 888/889/1267 873/890/1267 892/894/1267 +f 873/890/1268 876/877/1268 893/895/1268 +f 880/887/1269 873/890/1269 893/895/1269 +f 887/888/1270 880/887/1270 893/895/1270 +f 876/877/1271 887/888/1271 893/895/1271 +f 862/884/1272 871/876/1272 894/863/1272 +f 875/885/1273 862/884/1273 894/863/1273 +f 879/862/1274 875/885/1274 894/863/1274 +f 874/873/1234 865/866/1234 895/896/1234 +f 865/866/1275 881/879/1275 895/896/1275 +f 891/893/1276 874/873/1276 895/896/1276 +f 881/879/1277 891/893/1277 895/896/1277 +f 869/871/1278 876/877/1278 896/897/1278 +f 888/889/1279 869/871/1279 896/897/1279 +f 876/877/1280 888/889/1280 896/897/1280 +f 878/875/1234 874/873/1234 897/864/1234 +f 871/876/1281 878/875/1281 897/864/1281 +f 874/873/1282 879/862/1282 897/864/1282 +f 894/863/1283 871/876/1283 897/864/1283 +o Bowl_hull_28 +v 0.050000 0.056043 0.034706 +v 0.072849 0.040094 0.050235 +v 0.072849 0.040528 0.050235 +v 0.044396 0.040094 0.008851 +v 0.043964 0.065097 0.048934 +v 0.044396 0.040094 0.016180 +v 0.068537 0.040094 0.050235 +v 0.044396 0.070703 0.049801 +v 0.063363 0.054323 0.049372 +v 0.059051 0.040528 0.028682 +v 0.044396 0.042251 0.010573 +v 0.053450 0.064234 0.050235 +v 0.043964 0.055608 0.027823 +v 0.069829 0.045700 0.049372 +v 0.043964 0.066392 0.050235 +v 0.051725 0.065529 0.049372 +v 0.043964 0.040525 0.016180 +v 0.058618 0.059060 0.048938 +v 0.053020 0.040528 0.020057 +v 0.044396 0.055608 0.027823 +v 0.072416 0.040957 0.048938 +v 0.043964 0.070703 0.050235 +v 0.066812 0.050011 0.049372 +v 0.043964 0.040525 0.008851 +v 0.044396 0.065960 0.042468 +v 0.064225 0.053460 0.050235 +v 0.045691 0.040525 0.010148 +v 0.065517 0.040094 0.038162 +v 0.044396 0.049151 0.019198 +v 0.053020 0.052169 0.033422 +v 0.047413 0.068114 0.048509 +v 0.054312 0.060786 0.045920 +vt 0.593735 0.605521 +vt 0.250024 0.704092 +vt 0.895742 0.324002 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 0.177092 1.000000 +vt 1.000000 0.985807 +vt 1.000000 1.000000 +vt 1.000000 0.211335 +vt 0.968576 0.183144 +vt 1.000000 0.140857 +vt 0.458443 0.493148 +vt 0.989525 0.000000 +vt 0.979148 0.169049 +vt 0.177092 0.985905 +vt 0.979148 0.535141 +vt 0.968673 0.380384 +vt 0.624767 0.478955 +vt 0.458443 0.493148 +vt 0.968673 0.971809 +vt 0.979148 0.816856 +vt 0.479197 0.985807 +vt 1.000000 0.000000 +vt 0.979148 0.675998 +vt 0.270778 0.985807 +vt 0.000000 0.985905 +vt 0.812335 0.154953 +vt 1.000000 0.563332 +vt 0.031326 0.985905 +vt 0.041605 0.929522 +vt 0.708272 1.000000 +vt 0.958297 0.084573 +vn 0.5978 0.6298 -0.4960 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn -0.6043 -0.5647 0.5621 +vn -1.0000 -0.0000 0.0000 +vn 0.5781 0.8134 0.0646 +vn -0.7062 -0.7080 -0.0000 +vn -0.6457 -0.6108 0.4582 +vn -0.6315 -0.6331 0.4476 +vn 0.7068 0.7074 -0.0056 +vn 0.6565 0.7156 -0.2388 +vn 0.5577 0.6655 -0.4961 +vn 0.9486 0.0000 -0.3165 +vn 0.8656 0.4839 -0.1289 +vn 0.7411 0.4498 -0.4985 +vn 0.4911 0.7202 0.4901 +vn 0.7118 0.4980 -0.4953 +vn 0.7091 0.5014 -0.4958 +vn 0.6785 0.5429 -0.4949 +vn 0.0000 0.8166 -0.5772 +vn -0.4780 0.7375 -0.4770 +vn -0.6831 0.6057 -0.4080 +vn 0.7071 0.7071 0.0005 +vn 0.7688 0.5127 0.3822 +vn 0.7716 0.6173 -0.1538 +vn 0.8084 0.5656 0.1630 +vn 0.6812 -0.5313 -0.5037 +vn 0.6706 0.5515 -0.4961 +vn 0.5143 0.5156 -0.6853 +vn 0.5038 0.5435 -0.6714 +vn 0.5665 -0.7158 -0.4082 +vn 0.7836 -0.2927 -0.5479 +vn 0.8064 -0.3315 -0.4897 +vn 0.8018 0.2669 -0.5347 +vn 0.5589 0.6638 -0.4969 +vn 0.0000 0.8005 -0.5993 +vn -0.5323 0.6610 -0.5288 +vn -0.5865 0.6340 -0.5040 +vn 0.6369 0.5927 -0.4930 +vn 0.6415 0.5859 -0.4951 +vn 0.6310 0.5959 -0.4968 +vn 0.6037 0.6225 -0.4980 +vn 0.5335 0.7823 -0.3216 +vn 0.5173 0.6969 -0.4968 +vn 0.4385 0.7546 -0.4881 +vn 0.4969 0.7087 -0.5009 +vn 0.5580 0.6653 -0.4960 +vn 0.5902 0.6601 -0.4647 +vn 0.5894 0.6375 -0.4963 +vn 0.5993 0.6288 -0.4955 +usemtl None +s off +f 927/898/1284 926/899/1284 929/900/1284 +f 901/901/1285 899/902/1285 903/903/1285 +f 899/902/1286 900/904/1286 904/905/1286 +f 903/903/1285 899/902/1285 904/905/1285 +f 904/905/1286 900/904/1286 909/906/1286 +f 902/907/1287 904/905/1287 912/908/1287 +f 904/905/1286 909/906/1286 912/908/1286 +f 910/909/1288 902/907/1288 912/908/1288 +f 905/910/1289 909/906/1289 913/911/1289 +f 901/901/1290 903/903/1290 914/912/1290 +f 904/905/1291 902/907/1291 914/912/1291 +f 903/903/1292 904/905/1292 914/912/1292 +f 902/907/1288 910/909/1288 914/912/1288 +f 909/906/1293 906/913/1293 915/914/1293 +f 913/911/1294 909/906/1294 915/914/1294 +f 913/911/1295 898/915/1295 917/916/1295 +f 900/904/1296 899/902/1296 918/917/1296 +f 911/918/1297 900/904/1297 918/917/1297 +f 907/919/1298 911/918/1298 918/917/1298 +f 909/906/1299 905/910/1299 919/920/1299 +f 912/908/1286 909/906/1286 919/920/1286 +f 910/909/1288 912/908/1288 919/920/1288 +f 911/918/1300 907/919/1300 920/921/1300 +f 907/919/1301 916/922/1301 920/921/1301 +f 916/922/1302 906/913/1302 920/921/1302 +f 901/901/1290 914/912/1290 921/923/1290 +f 914/912/1288 910/909/1288 921/923/1288 +f 917/916/1303 910/909/1303 922/924/1303 +f 919/920/1304 905/910/1304 922/924/1304 +f 910/909/1305 919/920/1305 922/924/1305 +f 909/906/1286 900/904/1286 923/925/1286 +f 906/913/1306 909/906/1306 923/925/1306 +f 900/904/1307 911/918/1307 923/925/1307 +f 920/921/1308 906/913/1308 923/925/1308 +f 911/918/1309 920/921/1309 923/925/1309 +f 916/922/1310 901/901/1310 924/926/1310 +f 906/913/1311 916/922/1311 924/926/1311 +f 901/901/1312 921/923/1312 924/926/1312 +f 921/923/1313 908/927/1313 924/926/1313 +f 899/902/1285 901/901/1285 925/928/1285 +f 901/901/1314 916/922/1314 925/928/1314 +f 916/922/1315 907/919/1315 925/928/1315 +f 918/917/1316 899/902/1316 925/928/1316 +f 907/919/1317 918/917/1317 925/928/1317 +f 917/916/1318 898/915/1318 926/899/1318 +f 910/909/1319 917/916/1319 926/899/1319 +f 908/927/1320 921/923/1320 926/899/1320 +f 921/923/1321 910/909/1321 926/899/1321 +f 915/914/1322 906/913/1322 927/898/1322 +f 906/913/1323 924/926/1323 927/898/1323 +f 924/926/1324 908/927/1324 927/898/1324 +f 908/927/1325 926/899/1325 927/898/1325 +f 905/910/1326 913/911/1326 928/929/1326 +f 913/911/1327 917/916/1327 928/929/1327 +f 922/924/1328 905/910/1328 928/929/1328 +f 917/916/1329 922/924/1329 928/929/1329 +f 898/915/1330 913/911/1330 929/900/1330 +f 913/911/1331 915/914/1331 929/900/1331 +f 926/899/1332 898/915/1332 929/900/1332 +f 915/914/1333 927/898/1333 929/900/1333 +o Bowl_hull_29 +v 0.020251 -0.046997 -0.007096 +v 0.006026 -0.083197 0.050235 +v 0.002577 -0.083197 0.050235 +v 0.021115 -0.075875 0.048935 +v 0.002577 -0.039667 -0.019173 +v 0.003440 -0.040532 -0.025204 +v 0.021115 -0.039667 -0.010542 +v 0.002577 -0.078888 0.049366 +v 0.021115 -0.080614 0.049366 +v 0.013354 -0.040097 -0.022612 +v 0.014216 -0.078893 0.043758 +v 0.021115 -0.039667 -0.017011 +v 0.020683 -0.040097 -0.009681 +v 0.004302 -0.083197 0.049366 +v 0.002577 -0.039667 -0.025642 +v 0.009476 -0.042684 -0.020027 +v 0.020251 -0.076732 0.050235 +v 0.009476 -0.082771 0.049366 +v 0.021115 -0.059067 0.013158 +v 0.005594 -0.040102 -0.025642 +v 0.002577 -0.083197 0.049366 +v 0.021115 -0.040528 -0.016588 +v 0.021115 -0.080614 0.050235 +v 0.003440 -0.079319 0.050235 +v 0.002577 -0.041824 -0.023050 +v 0.018095 -0.074580 0.037720 +v 0.020683 -0.067249 0.026512 +v 0.004302 -0.045706 -0.016157 +v 0.010770 -0.040097 -0.023904 +v 0.009044 -0.078888 0.042473 +v 0.010770 -0.039667 -0.023904 +v 0.016371 -0.081475 0.048935 +v 0.016803 -0.040958 -0.019165 +v 0.008182 -0.050445 -0.007104 +vt 0.897709 0.901018 +vt 0.000000 0.009986 +vt 0.244323 0.247601 +vt 0.085258 0.000000 +vt 1.000000 1.000000 +vt 0.988547 0.901018 +vt 0.199002 0.000000 +vt 0.982870 0.831799 +vt 0.988547 0.940670 +vt 0.113743 0.000000 +vt 0.210356 0.009889 +vt 1.000000 1.000000 +vt 0.988547 1.000000 +vt 0.000000 0.000000 +vt 1.000000 0.851478 +vt 0.988547 0.990210 +vt 0.511355 0.445663 +vt 0.005775 0.019875 +vt 0.988547 1.000000 +vt 0.039937 0.009889 +vt 0.119323 0.019777 +vt 0.244420 0.168396 +vt 1.000000 0.940670 +vt 1.000000 0.910907 +vt 0.034162 0.049540 +vt 0.687353 0.633640 +vt 0.835063 0.802036 +vt 0.125000 0.138731 +vt 0.074002 0.069317 +vt 0.022905 0.009889 +vt 0.914644 0.901116 +vt 0.022905 0.000000 +vt 0.982870 0.960446 +vt 0.085356 0.029665 +vn 0.1112 -0.8612 -0.4960 +vn -1.0000 -0.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.1829 0.8398 0.5112 +vn -0.1722 0.9130 0.3698 +vn -0.2331 0.8440 0.4830 +vn 0.0000 -1.0000 -0.0000 +vn 0.0000 -0.0000 1.0000 +vn -0.0617 0.8517 0.5203 +vn -0.1287 0.8465 0.5166 +vn 0.0810 -0.9837 -0.1608 +vn -0.0732 -0.5078 -0.8584 +vn 0.5578 -0.3663 -0.7448 +vn 0.4779 -0.7455 -0.4646 +vn 0.7653 0.1703 0.6208 +vn 0.1659 -0.9690 0.1832 +vn 0.1822 -0.9833 0.0000 +vn -0.6639 0.1479 0.7331 +vn -0.1281 0.8322 0.5395 +vn -0.4070 -0.7022 -0.5842 +vn 0.0000 -0.8683 -0.4961 +vn 0.2725 -0.8243 -0.4963 +vn 0.4242 -0.7782 -0.4631 +vn 0.2322 -0.8377 -0.4943 +vn 0.0707 -0.8630 -0.5003 +vn 0.0481 -0.8651 -0.4993 +vn 0.0308 -0.8675 -0.4964 +vn 0.1709 -0.8450 -0.5068 +vn 0.2009 -0.8445 -0.4964 +vn 0.2264 -0.8383 -0.4960 +vn 0.2484 -0.8316 -0.4967 +vn 0.1218 -0.8615 -0.4929 +vn 0.0714 -0.8671 -0.4929 +vn 0.0667 -0.8660 -0.4955 +vn 0.0990 -0.8626 -0.4962 +vn 0.4267 0.6386 -0.6404 +vn 0.1183 0.8215 -0.5578 +vn 0.4473 0.0000 -0.8944 +vn 0.3184 0.0000 -0.9480 +vn 0.1711 -0.8513 -0.4960 +vn 0.1820 -0.9824 -0.0410 +vn 0.1320 -0.8640 -0.4860 +vn 0.1985 -0.8482 -0.4910 +vn 0.1755 -0.8504 -0.4959 +vn 0.3178 -0.8085 -0.4953 +vn 0.2924 -0.8171 -0.4968 +vn 0.3759 -0.7813 -0.4983 +vn 0.4237 -0.6831 -0.5948 +vn 0.1607 -0.8532 -0.4963 +vn 0.1517 -0.8540 -0.4977 +vn 0.1224 -0.8599 -0.4955 +usemtl None +s off +f 959/930/1334 949/931/1334 963/932/1334 +f 934/933/1335 932/934/1335 937/935/1335 +f 936/936/1336 933/937/1336 938/938/1336 +f 934/933/1337 936/936/1337 941/939/1337 +f 936/936/1336 938/938/1336 941/939/1336 +f 933/937/1338 936/936/1338 942/940/1338 +f 936/936/1339 934/933/1339 942/940/1339 +f 934/933/1340 937/935/1340 942/940/1340 +f 931/941/1341 932/934/1341 943/942/1341 +f 932/934/1335 934/933/1335 944/943/1335 +f 934/933/1337 941/939/1337 944/943/1337 +f 932/934/1342 931/941/1342 946/944/1342 +f 933/937/1343 942/940/1343 946/944/1343 +f 942/940/1344 937/935/1344 946/944/1344 +f 931/941/1345 943/942/1345 947/945/1345 +f 941/939/1336 938/938/1336 948/946/1336 +f 935/947/1346 944/943/1346 949/931/1346 +f 943/942/1341 932/934/1341 950/948/1341 +f 932/934/1335 944/943/1335 950/948/1335 +f 939/949/1347 941/939/1347 951/950/1347 +f 948/946/1348 930/951/1348 951/950/1348 +f 941/939/1336 948/946/1336 951/950/1336 +f 938/938/1336 933/937/1336 952/952/1336 +f 946/944/1342 931/941/1342 952/952/1342 +f 933/937/1349 946/944/1349 952/952/1349 +f 931/941/1350 947/945/1350 952/952/1350 +f 947/945/1351 938/938/1351 952/952/1351 +f 937/935/1352 932/934/1352 953/953/1352 +f 932/934/1342 946/944/1342 953/953/1342 +f 946/944/1353 937/935/1353 953/953/1353 +f 944/943/1354 935/947/1354 954/954/1354 +f 943/942/1355 950/948/1355 954/954/1355 +f 950/948/1335 944/943/1335 954/954/1335 +f 939/949/1356 948/946/1356 956/955/1356 +f 948/946/1357 938/938/1357 956/955/1357 +f 938/938/1358 955/956/1358 956/955/1358 +f 935/947/1359 949/931/1359 957/957/1359 +f 954/954/1360 935/947/1360 957/957/1360 +f 943/942/1361 954/954/1361 957/957/1361 +f 945/958/1362 949/931/1362 958/959/1362 +f 955/956/1363 945/958/1363 958/959/1363 +f 956/955/1364 955/956/1364 958/959/1364 +f 939/949/1365 956/955/1365 958/959/1365 +f 940/960/1366 947/945/1366 959/930/1366 +f 947/945/1367 943/942/1367 959/930/1367 +f 943/942/1368 957/957/1368 959/930/1368 +f 957/957/1369 949/931/1369 959/930/1369 +f 941/939/1370 939/949/1370 960/961/1370 +f 944/943/1337 941/939/1337 960/961/1337 +f 949/931/1371 944/943/1371 960/961/1371 +f 939/949/1372 958/959/1372 960/961/1372 +f 958/959/1373 949/931/1373 960/961/1373 +f 940/960/1374 945/958/1374 961/962/1374 +f 938/938/1375 947/945/1375 961/962/1375 +f 947/945/1376 940/960/1376 961/962/1376 +f 955/956/1377 938/938/1377 961/962/1377 +f 945/958/1378 955/956/1378 961/962/1378 +f 930/951/1379 948/946/1379 962/963/1379 +f 948/946/1380 939/949/1380 962/963/1380 +f 951/950/1381 930/951/1381 962/963/1381 +f 939/949/1382 951/950/1382 962/963/1382 +f 945/958/1383 940/960/1383 963/932/1383 +f 949/931/1384 945/958/1384 963/932/1384 +f 940/960/1385 959/930/1385 963/932/1385 +o Bowl_hull_30 +v 0.036202 0.028019 -0.016586 +v 0.006457 0.040094 -0.018744 +v 0.006457 0.040094 -0.018309 +v 0.039221 0.009053 -0.018312 +v 0.039221 0.039662 0.008847 +v 0.020257 0.039659 -0.018744 +v 0.039653 0.040094 0.001944 +v 0.039653 0.020265 -0.018744 +v 0.030164 0.032762 -0.018744 +v 0.006457 0.039659 -0.018309 +v 0.039653 0.009053 -0.018744 +v 0.024991 0.040094 -0.013999 +v 0.039653 0.040094 0.008847 +v 0.039653 0.032762 -0.006671 +v 0.031458 0.040094 -0.007533 +v 0.033183 0.029745 -0.018744 +v 0.025852 0.036211 -0.018744 +v 0.018964 0.040094 -0.018744 +v 0.039221 0.025002 -0.015295 +v 0.006457 0.039659 -0.018744 +v 0.036202 0.025865 -0.018744 +vt 0.986981 0.486198 +vt 1.000000 0.638802 +vt 0.896045 0.458399 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 0.415720 0.013998 +vt 0.714174 0.236198 +vt 0.000000 0.013998 +vt 0.986981 1.000000 +vt 0.986981 0.013900 +vt 1.000000 1.000000 +vt 0.558340 0.000000 +vt 1.000000 0.000000 +vt 1.000000 0.236198 +vt 0.753132 0.000000 +vt 0.805110 0.333399 +vt 0.896045 0.388998 +vt 0.584280 0.125098 +vt 0.376762 0.000000 +vt 0.000000 0.013998 +vn 0.7255 0.4471 -0.5232 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.5269 -0.5641 0.6357 +vn -0.6381 0.0000 0.7699 +vn 1.0000 0.0000 0.0000 +vn 0.5523 -0.5533 0.6235 +vn -0.5347 0.5356 0.6536 +vn 0.5986 -0.5322 0.5987 +vn 0.5716 0.6550 -0.4943 +vn 0.6129 0.6132 -0.4984 +vn 0.6703 0.5511 -0.4969 +vn 0.6495 0.5791 -0.4928 +vn 0.4496 0.7295 -0.5154 +vn 0.5396 0.6747 -0.5035 +vn 0.4948 0.7144 -0.4948 +vn 0.2952 0.8788 -0.3750 +vn 0.7124 0.5036 -0.4888 +vn 0.8824 0.3269 -0.3384 +vn -0.6826 -0.7308 0.0000 +vn -0.5611 -0.6086 -0.5611 +vn 0.6729 0.5235 -0.5226 +vn 0.7104 0.4981 -0.4972 +usemtl None +s off +f 982/964/1386 971/965/1386 984/966/1386 +f 965/967/1387 966/968/1387 970/969/1387 +f 965/967/1388 969/970/1388 971/965/1388 +f 971/965/1388 969/970/1388 972/971/1388 +f 966/968/1389 965/967/1389 973/972/1389 +f 967/973/1390 968/974/1390 973/972/1390 +f 968/974/1391 966/968/1391 973/972/1391 +f 965/967/1388 971/965/1388 974/975/1388 +f 971/965/1392 970/969/1392 974/975/1392 +f 965/967/1387 970/969/1387 975/976/1387 +f 968/974/1393 967/973/1393 976/977/1393 +f 966/968/1394 968/974/1394 976/977/1394 +f 970/969/1387 966/968/1387 976/977/1387 +f 967/973/1395 974/975/1395 976/977/1395 +f 974/975/1392 970/969/1392 976/977/1392 +f 970/969/1392 971/965/1392 977/978/1392 +f 970/969/1396 972/971/1396 978/979/1396 +f 975/976/1387 970/969/1387 978/979/1387 +f 972/971/1397 970/969/1397 979/980/1397 +f 971/965/1388 972/971/1388 979/980/1388 +f 977/978/1398 964/981/1398 979/980/1398 +f 970/969/1399 977/978/1399 979/980/1399 +f 972/971/1388 969/970/1388 980/982/1388 +f 969/970/1400 975/976/1400 980/982/1400 +f 978/979/1401 972/971/1401 980/982/1401 +f 975/976/1402 978/979/1402 980/982/1402 +f 969/970/1388 965/967/1388 981/983/1388 +f 965/967/1387 975/976/1387 981/983/1387 +f 975/976/1403 969/970/1403 981/983/1403 +f 964/981/1404 977/978/1404 982/964/1404 +f 977/978/1405 971/965/1405 982/964/1405 +f 973/972/1389 965/967/1389 983/984/1389 +f 967/973/1406 973/972/1406 983/984/1406 +f 974/975/1407 967/973/1407 983/984/1407 +f 965/967/1388 974/975/1388 983/984/1388 +f 979/980/1408 964/981/1408 984/966/1408 +f 971/965/1388 979/980/1388 984/966/1388 +f 964/981/1409 982/964/1409 984/966/1409 +o Bowl_hull_31 +v 0.048278 0.040094 0.013159 +v 0.039653 0.019401 -0.018744 +v 0.039653 0.018969 -0.018744 +v 0.081036 0.018969 0.049370 +v 0.040086 0.039662 0.010141 +v 0.073278 0.040094 0.049796 +v 0.077159 0.018969 0.050228 +v 0.040086 0.018969 -0.010979 +v 0.068104 0.040094 0.049364 +v 0.077159 0.027594 0.046784 +v 0.040086 0.040094 0.002815 +v 0.040086 0.019401 -0.018744 +v 0.041379 0.028886 -0.008393 +v 0.076725 0.032761 0.049370 +v 0.068104 0.040094 0.041606 +v 0.055606 0.019831 0.006698 +v 0.039653 0.040094 0.009284 +v 0.068967 0.039232 0.050235 +v 0.080177 0.023280 0.050228 +v 0.073711 0.037507 0.048074 +v 0.076296 0.018969 0.048938 +v 0.058191 0.039662 0.026515 +v 0.040086 0.025005 -0.013997 +v 0.080177 0.021990 0.048938 +v 0.039653 0.037507 -0.000635 +v 0.040086 0.031469 -0.007529 +v 0.039653 0.018969 -0.011843 +v 0.068104 0.039662 0.049364 +v 0.073278 0.040094 0.050228 +v 0.069397 0.018969 0.029540 +v 0.040516 0.022850 -0.015294 +v 0.052588 0.021556 0.002815 +v 0.040086 0.037507 -0.000635 +v 0.067242 0.019831 0.026089 +v 0.053018 0.040094 0.019621 +v 0.051296 0.018969 -0.000635 +v 0.081036 0.018969 0.050228 +v 0.068967 0.034918 0.038587 +vt 0.050020 0.020852 +vt 0.874902 0.687518 +vt 0.831147 0.708370 +vt 0.000000 0.000000 +vt 0.987471 1.000000 +vt 0.999902 0.906314 +vt 0.112569 0.010475 +vt 0.993637 0.812531 +vt 0.462510 0.208419 +vt 0.987373 0.687518 +vt 0.312549 0.010475 +vt 0.000000 0.000000 +vt 0.000000 0.010475 +vt 0.406323 0.000000 +vt 0.418755 0.010475 +vt 0.987471 0.895840 +vt 0.968677 0.823005 +vt 0.981206 0.885463 +vt 0.656128 0.447969 +vt 0.068814 0.010475 +vt 0.150059 0.041703 +vt 0.949980 0.906314 +vt 0.981206 0.979246 +vt 0.999902 0.979246 +vt 0.262529 0.000000 +vt 0.162588 0.010475 +vt 0.100039 0.000000 +vt 0.987373 0.687518 +vt 1.000000 0.708370 +vt 0.999902 0.812531 +vt 0.699980 0.718747 +vt 0.312549 0.312580 +vt 0.368833 0.385511 +vt 0.262529 0.010475 +vt 0.649961 0.666667 +vt 0.556186 0.322956 +vt 0.262529 0.281351 +vt 0.999902 1.000000 +vn 0.7623 0.4162 -0.4957 +vn -0.0000 -1.0000 0.0000 +vn -0.0000 1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.7742 0.3139 0.5496 +vn 0.8173 0.4079 -0.4071 +vn 0.7571 0.4452 -0.4782 +vn -0.7685 -0.3807 0.5142 +vn -0.7569 -0.4668 0.4574 +vn 0.7346 0.4631 -0.4958 +vn 0.0000 0.6463 -0.7630 +vn 0.7265 0.4750 -0.4965 +vn 0.8511 0.2903 -0.4374 +vn 0.9433 0.2346 -0.2347 +vn 0.9042 0.3019 -0.3020 +vn -0.9665 0.2483 -0.0648 +vn -0.8137 0.4111 -0.4110 +vn -0.8115 0.4133 -0.4131 +vn 0.6853 0.5152 -0.5148 +vn -0.8128 -0.4161 0.4077 +vn -0.9032 -0.3036 0.3036 +vn -0.7723 -0.3149 0.5517 +vn -0.8137 0.0000 0.5813 +vn -0.7476 -0.3024 0.5913 +vn -0.7104 0.0000 0.7038 +vn 0.9050 0.4255 0.0000 +vn -0.1267 0.6393 0.7584 +vn 0.8362 0.3431 0.4279 +vn 0.0014 0.0006 1.0000 +vn 0.7442 0.4470 -0.4963 +vn 0.6847 0.4711 -0.5561 +vn 0.8091 0.3159 -0.4955 +vn 0.7957 0.3473 -0.4962 +vn 0.8127 0.3055 -0.4961 +vn 0.8134 0.2952 -0.5012 +vn 0.6038 0.6378 -0.4782 +vn 0.0000 0.8001 -0.5999 +vn 0.0000 0.7523 -0.6589 +vn 0.6572 0.5670 -0.4966 +vn 0.8266 0.2662 -0.4959 +vn 0.8303 0.2572 -0.4944 +vn 0.8505 0.1706 -0.4976 +vn 0.8552 0.1291 -0.5019 +vn 0.7034 0.5092 -0.4959 +vn 0.6300 0.6452 -0.4323 +vn 0.6752 0.5467 -0.4953 +vn 0.6984 0.5156 -0.4964 +vn 0.6429 -0.6448 -0.4134 +vn 0.8376 0.1846 -0.5141 +vn 0.8541 0.0883 -0.5125 +vn 0.8545 0.0848 -0.5126 +vn 0.0000 -0.0003 1.0000 +vn 0.9807 0.1954 0.0000 +vn 0.0008 0.0002 1.0000 +vn 0.7895 0.3619 -0.4957 +vn 0.7886 0.3659 -0.4942 +vn 0.7629 0.4158 -0.4950 +vn 0.7701 0.4007 -0.4964 +usemtl None +s off +f 1015/985/1410 999/986/1410 1022/987/1410 +f 987/988/1411 988/989/1411 991/990/1411 +f 987/988/1411 991/990/1411 992/991/1411 +f 990/992/1412 985/993/1412 993/994/1412 +f 993/994/1412 985/993/1412 995/995/1412 +f 987/988/1413 986/996/1413 996/997/1413 +f 985/993/1412 990/992/1412 999/986/1412 +f 986/996/1414 987/988/1414 1001/998/1414 +f 989/999/1415 993/994/1415 1001/998/1415 +f 993/994/1412 995/995/1412 1001/998/1412 +f 990/992/1416 998/1000/1416 1004/1001/1416 +f 999/986/1417 990/992/1417 1004/1001/1417 +f 991/990/1418 989/999/1418 1005/1002/1418 +f 989/999/1419 992/991/1419 1005/1002/1419 +f 992/991/1411 991/990/1411 1005/1002/1411 +f 1006/1003/1420 999/986/1420 1007/1004/1420 +f 996/997/1421 986/996/1421 1007/1004/1421 +f 997/1005/1422 1006/1003/1422 1007/1004/1422 +f 994/1006/1423 998/1000/1423 1008/1007/1423 +f 1003/1008/1424 988/989/1424 1008/1007/1424 +f 998/1000/1425 1003/1008/1425 1008/1007/1425 +f 986/996/1414 1001/998/1414 1009/1009/1414 +f 1001/998/1426 995/995/1426 1009/1009/1426 +f 1007/1004/1427 986/996/1427 1009/1009/1427 +f 1007/1004/1428 1009/1009/1428 1010/1010/1428 +f 997/1005/1429 1007/1004/1429 1010/1010/1429 +f 987/988/1411 992/991/1411 1011/1011/1411 +f 992/991/1430 989/999/1430 1011/1011/1430 +f 1001/998/1414 987/988/1414 1011/1011/1414 +f 989/999/1431 1001/998/1431 1011/1011/1431 +f 989/999/1432 991/990/1432 1012/1012/1432 +f 993/994/1433 989/999/1433 1012/1012/1433 +f 991/990/1434 1002/1013/1434 1012/1012/1434 +f 1002/1013/1435 993/994/1435 1012/1012/1435 +f 990/992/1412 993/994/1412 1013/1014/1412 +f 998/1000/1436 990/992/1436 1013/1014/1436 +f 993/994/1437 1002/1013/1437 1013/1014/1437 +f 1003/1008/1438 998/1000/1438 1013/1014/1438 +f 1002/1013/1439 1003/1008/1439 1013/1014/1439 +f 988/989/1411 987/988/1411 1014/1015/1411 +f 1007/1004/1440 999/986/1440 1015/985/1440 +f 996/997/1441 1007/1004/1441 1015/985/1441 +f 998/1000/1442 994/1006/1442 1016/1016/1442 +f 996/997/1443 998/1000/1443 1016/1016/1443 +f 994/1006/1444 1000/1017/1444 1016/1016/1444 +f 1000/1017/1445 996/997/1445 1016/1016/1445 +f 995/995/1446 985/993/1446 1017/1018/1446 +f 1009/1009/1447 995/995/1447 1017/1018/1447 +f 1010/1010/1448 1009/1009/1448 1017/1018/1448 +f 985/993/1449 1010/1010/1449 1017/1018/1449 +f 1000/1017/1450 994/1006/1450 1018/1019/1450 +f 994/1006/1451 1008/1007/1451 1018/1019/1451 +f 1008/1007/1452 988/989/1452 1018/1019/1452 +f 988/989/1453 1014/1015/1453 1018/1019/1453 +f 985/993/1412 999/986/1412 1019/1020/1412 +f 1006/1003/1454 997/1005/1454 1019/1020/1454 +f 999/986/1455 1006/1003/1455 1019/1020/1455 +f 1010/1010/1456 985/993/1456 1019/1020/1456 +f 997/1005/1457 1010/1010/1457 1019/1020/1457 +f 987/988/1458 996/997/1458 1020/1021/1458 +f 996/997/1459 1000/1017/1459 1020/1021/1459 +f 1014/1015/1411 987/988/1411 1020/1021/1411 +f 1000/1017/1460 1018/1019/1460 1020/1021/1460 +f 1018/1019/1461 1014/1015/1461 1020/1021/1461 +f 991/990/1411 988/989/1411 1021/1022/1411 +f 1002/1013/1462 991/990/1462 1021/1022/1462 +f 988/989/1463 1003/1008/1463 1021/1022/1463 +f 1003/1008/1464 1002/1013/1464 1021/1022/1464 +f 998/1000/1465 996/997/1465 1022/987/1465 +f 1004/1001/1466 998/1000/1466 1022/987/1466 +f 999/986/1467 1004/1001/1467 1022/987/1467 +f 996/997/1468 1015/985/1468 1022/987/1468 +o Bowl_hull_32 +v 0.043967 0.017242 -0.013996 +v 0.039654 0.005606 -0.025642 +v 0.039654 0.000433 -0.025642 +v 0.083196 0.004314 0.049366 +v 0.040084 0.018535 -0.011411 +v 0.078452 0.000433 0.048504 +v 0.081039 0.018969 0.049366 +v 0.077160 0.018969 0.050235 +v 0.040519 0.000433 -0.017873 +v 0.083196 0.000433 0.049366 +v 0.040084 0.018969 -0.018735 +v 0.040084 0.005606 -0.025642 +v 0.082330 0.012931 0.049366 +v 0.041380 0.000433 -0.023911 +v 0.041380 0.010775 -0.021757 +v 0.039654 0.018969 -0.012273 +v 0.065951 0.018969 0.023504 +v 0.079743 0.000433 0.050235 +v 0.082330 0.013794 0.050235 +v 0.076295 0.017242 0.040312 +v 0.039654 0.000433 -0.019604 +v 0.081900 0.008625 0.047643 +v 0.041811 0.003452 -0.023050 +v 0.077160 0.018535 0.050235 +v 0.040519 0.007761 -0.024342 +v 0.039654 0.018104 -0.012273 +v 0.040084 0.013363 -0.022619 +v 0.039654 0.018104 -0.019604 +v 0.083196 0.000433 0.050235 +v 0.051724 0.018969 -0.000204 +v 0.077591 0.003020 0.039450 +v 0.067673 0.011207 0.023504 +v 0.081039 0.018969 0.050235 +v 0.043537 0.006038 -0.019604 +v 0.081039 0.018535 0.048935 +v 0.082761 0.000433 0.048504 +vt 0.022807 0.039644 +vt 0.857870 0.871280 +vt 0.977193 0.990016 +vt 0.000000 0.000000 +vt 0.977193 0.891053 +vt 0.102388 0.019871 +vt 0.988547 1.000000 +vt 1.000000 0.861394 +vt 0.988547 0.950470 +vt 0.091034 0.009886 +vt 0.000000 0.000000 +vt 0.000000 0.009886 +vt 0.176194 0.000000 +vt 0.187549 0.009886 +vt 0.647709 0.603954 +vt 1.000000 0.920713 +vt 0.988547 0.980129 +vt 1.000000 0.980129 +vt 0.988547 1.000000 +vt 0.051194 0.039644 +vt 0.869225 0.841523 +vt 0.079581 0.000000 +vt 0.965838 0.970243 +vt 0.034162 0.049530 +vt 1.000000 0.861394 +vt 0.017130 0.019871 +vt 0.176194 0.000000 +vt 0.153485 0.099060 +vt 0.039839 0.009886 +vt 0.079581 0.000000 +vt 1.000000 1.000000 +vt 0.335258 0.277212 +vt 0.647709 0.643500 +vt 1.000000 0.950470 +vt 0.079581 0.089174 +vt 0.982870 0.950470 +vn 0.8682 -0.0013 -0.4961 +vn 0.0000 -1.0000 -0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.7068 -0.0588 -0.7050 +vn -1.0000 0.0000 0.0000 +vn -0.8452 0.1685 0.5072 +vn 0.9574 0.2048 -0.2035 +vn 0.9901 0.0994 -0.0988 +vn -0.0000 0.0000 1.0000 +vn 0.8414 0.2151 -0.4957 +vn 0.8906 0.0894 -0.4459 +vn 0.8441 0.0324 -0.5352 +vn 0.8662 0.0622 -0.4958 +vn -0.8518 -0.1097 0.5123 +vn -0.8569 0.0000 0.5154 +vn -0.7963 -0.1136 0.5942 +vn 0.8485 0.1833 -0.4964 +vn -0.8526 -0.1493 0.5008 +vn -0.8514 -0.1959 0.4866 +vn -0.8946 -0.0000 0.4470 +vn -0.8794 -0.1824 0.4397 +vn 0.7825 0.3546 -0.5119 +vn 0.0000 0.3631 -0.9317 +vn 0.8310 0.2508 -0.4965 +vn 0.7019 0.2587 -0.6637 +vn 0.8124 0.2281 -0.5366 +vn -0.8695 0.4906 -0.0579 +vn -0.8348 0.2395 -0.4958 +vn 0.4574 0.5064 -0.7310 +vn 1.0000 0.0000 0.0000 +vn 0.9588 0.0621 0.2773 +vn 0.7739 0.4061 -0.4861 +vn 0.8203 0.2833 -0.4968 +vn 0.8263 0.2670 -0.4959 +vn 0.8671 0.0457 -0.4961 +vn 0.8678 0.0180 -0.4967 +vn 0.8546 0.1572 -0.4949 +vn 0.8613 0.1122 -0.4956 +vn 0.8531 0.1621 -0.4959 +vn 0.9702 0.2421 0.0000 +vn 0.8618 0.0900 -0.4992 +vn 0.8641 0.0845 -0.4962 +vn 0.8570 0.1281 -0.4991 +vn 0.8613 0.1119 -0.4957 +vn 0.8573 0.1363 -0.4964 +vn 0.9569 0.2047 -0.2060 +vn 0.7724 0.4476 -0.4506 +vn 0.8548 0.1590 -0.4941 +vn 0.8411 0.2173 -0.4953 +vn 0.8928 0.0000 -0.4505 +vn 0.8698 0.0121 -0.4932 +usemtl None +s off +f 1036/1023/1469 1053/1024/1469 1058/1025/1469 +f 1025/1026/1470 1028/1027/1470 1031/1028/1470 +f 1028/1027/1470 1025/1026/1470 1032/1029/1470 +f 1030/1030/1471 1029/1031/1471 1033/1032/1471 +f 1025/1026/1472 1024/1033/1472 1034/1034/1472 +f 1032/1029/1470 1025/1026/1470 1036/1023/1470 +f 1025/1026/1473 1034/1034/1473 1036/1023/1473 +f 1024/1033/1474 1025/1026/1474 1038/1035/1474 +f 1027/1036/1475 1030/1030/1475 1038/1035/1475 +f 1030/1030/1471 1033/1032/1471 1038/1035/1471 +f 1033/1032/1471 1029/1031/1471 1039/1037/1471 +f 1028/1027/1470 1032/1029/1470 1040/1038/1470 +f 1035/1039/1476 1029/1031/1476 1041/1040/1476 +f 1026/1041/1477 1035/1039/1477 1041/1040/1477 +f 1030/1030/1478 1040/1038/1478 1041/1040/1478 +f 1037/1042/1479 1039/1037/1479 1042/1043/1479 +f 1025/1026/1470 1031/1028/1470 1043/1044/1470 +f 1038/1035/1474 1025/1026/1474 1043/1044/1474 +f 1035/1039/1480 1026/1041/1480 1044/1045/1480 +f 1036/1023/1481 1034/1034/1481 1045/1046/1481 +f 1044/1045/1482 1026/1041/1482 1045/1046/1482 +f 1027/1036/1483 1028/1027/1483 1046/1047/1483 +f 1030/1030/1484 1027/1036/1484 1046/1047/1484 +f 1028/1027/1485 1040/1038/1485 1046/1047/1485 +f 1040/1038/1478 1030/1030/1478 1046/1047/1478 +f 1037/1042/1486 1042/1043/1486 1047/1048/1486 +f 1028/1027/1487 1027/1036/1487 1048/1049/1487 +f 1031/1028/1488 1028/1027/1488 1048/1049/1488 +f 1027/1036/1489 1038/1035/1489 1048/1049/1489 +f 1043/1044/1490 1031/1028/1490 1048/1049/1490 +f 1038/1035/1474 1043/1044/1474 1048/1049/1474 +f 1033/1032/1491 1023/1050/1491 1049/1051/1491 +f 1034/1034/1492 1024/1033/1492 1049/1051/1492 +f 1039/1037/1493 1037/1042/1493 1049/1051/1493 +f 1047/1048/1494 1034/1034/1494 1049/1051/1494 +f 1037/1042/1495 1047/1048/1495 1049/1051/1495 +f 1024/1033/1474 1038/1035/1474 1050/1052/1474 +f 1038/1035/1496 1033/1032/1496 1050/1052/1496 +f 1049/1051/1497 1024/1033/1497 1050/1052/1497 +f 1033/1032/1498 1049/1051/1498 1050/1052/1498 +f 1032/1029/1499 1026/1041/1499 1051/1053/1499 +f 1040/1038/1470 1032/1029/1470 1051/1053/1470 +f 1026/1041/1500 1041/1040/1500 1051/1053/1500 +f 1041/1040/1478 1040/1038/1478 1051/1053/1478 +f 1023/1050/1501 1033/1032/1501 1052/1054/1501 +f 1033/1032/1471 1039/1037/1471 1052/1054/1471 +f 1049/1051/1502 1023/1050/1502 1052/1054/1502 +f 1039/1037/1503 1049/1051/1503 1052/1054/1503 +f 1045/1046/1504 1026/1041/1504 1053/1024/1504 +f 1036/1023/1505 1045/1046/1505 1053/1024/1505 +f 1042/1043/1506 1035/1039/1506 1054/1055/1506 +f 1035/1039/1507 1044/1045/1507 1054/1055/1507 +f 1047/1048/1508 1042/1043/1508 1054/1055/1508 +f 1029/1031/1471 1030/1030/1471 1055/1056/1471 +f 1041/1040/1509 1029/1031/1509 1055/1056/1509 +f 1030/1030/1478 1041/1040/1478 1055/1056/1478 +f 1045/1046/1510 1034/1034/1510 1056/1057/1510 +f 1044/1045/1511 1045/1046/1511 1056/1057/1511 +f 1034/1034/1512 1047/1048/1512 1056/1057/1512 +f 1054/1055/1513 1044/1045/1513 1056/1057/1513 +f 1047/1048/1514 1054/1055/1514 1056/1057/1514 +f 1029/1031/1515 1035/1039/1515 1057/1058/1515 +f 1039/1037/1516 1029/1031/1516 1057/1058/1516 +f 1035/1039/1517 1042/1043/1517 1057/1058/1517 +f 1042/1043/1518 1039/1037/1518 1057/1058/1518 +f 1026/1041/1519 1032/1029/1519 1058/1025/1519 +f 1032/1029/1470 1036/1023/1470 1058/1025/1470 +f 1053/1024/1520 1026/1041/1520 1058/1025/1520 +o Bowl_hull_33 +v -0.050883 -0.019831 -0.001059 +v -0.083211 0.000431 0.049363 +v -0.083211 -0.003452 0.049363 +v -0.076746 -0.019399 0.049794 +v -0.039678 0.000431 -0.019604 +v -0.040539 -0.003881 -0.025204 +v -0.039678 -0.019831 -0.011412 +v -0.078472 0.000431 0.048502 +v -0.080194 -0.019831 0.048071 +v -0.040108 -0.012501 -0.023050 +v -0.041400 0.000431 -0.023911 +v -0.081920 -0.015519 0.049363 +v -0.039678 -0.019831 -0.018311 +v -0.039678 -0.019399 -0.011412 +v -0.077176 -0.019831 0.050232 +v -0.082781 -0.009486 0.049363 +v -0.042691 -0.008193 -0.020465 +v -0.040539 0.000431 -0.017873 +v -0.079763 0.000431 0.050232 +v -0.039678 0.000431 -0.025642 +v -0.081059 -0.019831 0.050232 +v -0.083211 0.000431 0.050232 +v -0.075024 -0.019399 0.039017 +v -0.040969 -0.019831 -0.017019 +v -0.040108 -0.005606 -0.025642 +v -0.063384 -0.019831 0.019626 +v -0.064245 -0.003881 0.016172 +v -0.042691 -0.009486 -0.020035 +v -0.076315 -0.009914 0.038156 +v -0.039678 -0.009486 -0.024342 +v -0.082781 -0.001727 0.048502 +v -0.048300 -0.002159 -0.011843 +v -0.082781 -0.006900 0.048932 +v -0.040969 -0.014655 -0.020465 +v -0.082781 -0.010347 0.050232 +v -0.040969 -0.019399 -0.009258 +v -0.041400 -0.011640 -0.021327 +vt 0.073904 0.930781 +vt 0.000000 0.990112 +vt 0.056872 0.960446 +vt 0.079581 1.000000 +vt 0.988547 0.000000 +vt 0.977193 0.108870 +vt 0.324002 0.742608 +vt 0.187549 1.000000 +vt 0.971515 0.069317 +vt 0.022807 0.960446 +vt 0.096613 1.000000 +vt 0.187549 1.000000 +vt 0.994225 0.148522 +vt 1.000000 0.138633 +vt 0.102388 0.980223 +vt 1.000000 0.079205 +vt 0.000000 1.000000 +vt 0.005775 0.980223 +vt 0.988547 0.029665 +vt 1.000000 0.049442 +vt 1.000000 0.000000 +vt 0.988547 0.000000 +vt 0.852193 0.188075 +vt 0.113645 0.970335 +vt 0.034162 0.990112 +vt 0.068226 0.930781 +vt 0.596613 0.455453 +vt 0.988547 0.009888 +vt 0.840838 0.158410 +vt 0.017130 1.000000 +vt 0.977193 0.009888 +vt 0.551096 0.435677 +vt 0.181872 0.801939 +vt 0.982870 0.009888 +vt 0.068226 0.970335 +vt 1.000000 0.009888 +vt 0.215936 0.970335 +vn -0.8348 -0.1907 -0.5165 +vn 0.0000 1.0000 0.0000 +vn -0.0000 -1.0000 -0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.8128 -0.3081 0.4944 +vn 0.8805 0.1810 0.4381 +vn 0.8515 0.1955 0.4866 +vn 0.7967 0.1081 0.5946 +vn 0.6674 0.0852 0.7398 +vn -0.7071 0.0697 -0.7036 +vn -0.8984 -0.2519 -0.3597 +vn 0.0000 -0.0000 1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.8483 -0.1917 -0.4936 +vn -0.6331 -0.4461 -0.6326 +vn -0.8575 -0.1365 -0.4961 +vn -0.6201 0.0442 -0.7833 +vn -0.8103 -0.3378 -0.4789 +vn -0.8523 -0.1653 -0.4962 +vn -0.8483 -0.1860 -0.4957 +vn -0.8457 -0.1686 -0.5062 +vn -0.8616 -0.1230 -0.4924 +vn -0.8580 -0.1337 -0.4960 +vn -0.8636 -0.0895 -0.4962 +vn 0.6824 -0.3681 -0.6315 +vn -0.3265 -0.3326 -0.8847 +vn 0.8767 -0.0625 -0.4770 +vn -0.8945 0.0000 -0.4470 +vn -0.8683 0.0246 -0.4955 +vn -0.8680 -0.0309 -0.4956 +vn -0.8680 -0.0284 -0.4958 +vn -0.8658 -0.0230 -0.4999 +vn -0.8664 -0.0534 -0.4964 +vn -0.8682 0.0014 -0.4961 +vn -0.9172 -0.0654 -0.3929 +vn -0.8676 -0.0465 -0.4952 +vn -0.8657 -0.0671 -0.4960 +vn -0.8646 -0.0825 -0.4956 +vn -0.8645 -0.0814 -0.4959 +vn -0.8015 -0.3314 -0.4978 +vn -0.7437 -0.3704 -0.5565 +vn -0.8197 -0.2874 -0.4954 +vn -0.8266 -0.2652 -0.4964 +vn -0.9804 -0.1399 -0.1386 +vn -0.9950 -0.0710 -0.0703 +vn -0.9801 -0.1779 0.0881 +vn -0.9837 -0.0393 0.1756 +vn 0.8550 -0.0266 0.5180 +vn 0.8503 0.1076 0.5152 +vn 0.8576 0.0000 0.5142 +vn 0.8511 0.1232 0.5103 +vn -0.8292 -0.1967 -0.5232 +vn -0.8306 -0.2525 -0.4964 +vn -0.8350 -0.2382 -0.4959 +vn -0.8429 -0.2076 -0.4964 +usemtl None +s off +f 1086/1059/1521 1083/1060/1521 1095/1061/1521 +f 1063/1062/1522 1060/1063/1522 1066/1064/1522 +f 1059/1065/1523 1065/1066/1523 1067/1067/1523 +f 1060/1063/1522 1063/1062/1522 1069/1068/1522 +f 1065/1066/1523 1059/1065/1523 1071/1069/1523 +f 1063/1062/1524 1065/1066/1524 1071/1069/1524 +f 1065/1066/1524 1063/1062/1524 1072/1070/1524 +f 1065/1066/1525 1062/1071/1525 1073/1072/1525 +f 1067/1067/1523 1065/1066/1523 1073/1072/1523 +f 1063/1062/1522 1066/1064/1522 1076/1073/1522 +f 1072/1070/1526 1063/1062/1526 1076/1073/1526 +f 1066/1064/1527 1072/1070/1527 1076/1073/1527 +f 1066/1064/1522 1060/1063/1522 1077/1074/1522 +f 1062/1071/1528 1066/1064/1528 1077/1074/1528 +f 1073/1072/1529 1062/1071/1529 1077/1074/1529 +f 1069/1068/1522 1063/1062/1522 1078/1075/1522 +f 1064/1076/1530 1069/1068/1530 1078/1075/1530 +f 1063/1062/1524 1071/1069/1524 1078/1075/1524 +f 1070/1077/1531 1067/1067/1531 1079/1078/1531 +f 1067/1067/1523 1073/1072/1523 1079/1078/1523 +f 1073/1072/1532 1077/1074/1532 1079/1078/1532 +f 1079/1078/1532 1077/1074/1532 1080/1079/1532 +f 1060/1063/1533 1061/1080/1533 1080/1079/1533 +f 1077/1074/1522 1060/1063/1522 1080/1079/1522 +f 1067/1067/1534 1070/1077/1534 1081/1081/1534 +f 1071/1069/1523 1059/1065/1523 1082/1082/1523 +f 1068/1083/1535 1071/1069/1535 1082/1082/1535 +f 1075/1084/1536 1070/1077/1536 1083/1060/1536 +f 1064/1076/1537 1078/1075/1537 1083/1060/1537 +f 1059/1065/1523 1067/1067/1523 1084/1085/1523 +f 1067/1067/1538 1081/1081/1538 1084/1085/1538 +f 1070/1077/1539 1075/1084/1539 1086/1059/1539 +f 1081/1081/1540 1070/1077/1540 1086/1059/1540 +f 1075/1084/1541 1083/1060/1541 1086/1059/1541 +f 1070/1077/1542 1074/1086/1542 1087/1087/1542 +f 1083/1060/1543 1070/1077/1543 1087/1087/1543 +f 1064/1076/1544 1083/1060/1544 1087/1087/1544 +f 1071/1069/1545 1068/1083/1545 1088/1088/1545 +f 1078/1075/1524 1071/1069/1524 1088/1088/1524 +f 1068/1083/1546 1083/1060/1546 1088/1088/1546 +f 1083/1060/1547 1078/1075/1547 1088/1088/1547 +f 1061/1080/1548 1060/1063/1548 1089/1089/1548 +f 1060/1063/1549 1069/1068/1549 1089/1089/1549 +f 1085/1090/1550 1061/1080/1550 1089/1089/1550 +f 1085/1090/1551 1089/1089/1551 1090/1091/1551 +f 1069/1068/1552 1064/1076/1552 1090/1091/1552 +f 1064/1076/1553 1085/1090/1553 1090/1091/1553 +f 1089/1089/1554 1069/1068/1554 1090/1091/1554 +f 1074/1086/1555 1061/1080/1555 1091/1092/1555 +f 1061/1080/1556 1085/1090/1556 1091/1092/1556 +f 1085/1090/1557 1064/1076/1557 1091/1092/1557 +f 1087/1087/1558 1074/1086/1558 1091/1092/1558 +f 1064/1076/1559 1087/1087/1559 1091/1092/1559 +f 1082/1082/1560 1059/1065/1560 1092/1093/1560 +f 1068/1083/1561 1082/1082/1561 1092/1093/1561 +f 1059/1065/1562 1084/1085/1562 1092/1093/1562 +f 1084/1085/1563 1068/1083/1563 1092/1093/1563 +f 1074/1086/1564 1070/1077/1564 1093/1094/1564 +f 1061/1080/1565 1074/1086/1565 1093/1094/1565 +f 1070/1077/1566 1079/1078/1566 1093/1094/1566 +f 1079/1078/1532 1080/1079/1532 1093/1094/1532 +f 1080/1079/1567 1061/1080/1567 1093/1094/1567 +f 1062/1071/1568 1065/1066/1568 1094/1095/1568 +f 1066/1064/1569 1062/1071/1569 1094/1095/1569 +f 1065/1066/1570 1072/1070/1570 1094/1095/1570 +f 1072/1070/1571 1066/1064/1571 1094/1095/1571 +f 1083/1060/1572 1068/1083/1572 1095/1061/1572 +f 1068/1083/1573 1084/1085/1573 1095/1061/1573 +f 1084/1085/1574 1081/1081/1574 1095/1061/1574 +f 1081/1081/1575 1086/1059/1575 1095/1061/1575 +o Bowl_hull_34 +v -0.046143 -0.039229 0.009282 +v -0.080629 -0.019833 0.048934 +v -0.080629 -0.020266 0.048934 +v -0.040106 -0.020266 -0.017882 +v -0.040106 -0.039660 0.010142 +v -0.072867 -0.040092 0.048934 +v -0.076748 -0.020266 0.050235 +v -0.039673 -0.019833 -0.010981 +v -0.068125 -0.039660 0.049368 +v -0.039673 -0.040092 0.002814 +v -0.077610 -0.030608 0.049368 +v -0.040106 -0.025438 -0.013568 +v -0.068987 -0.040092 0.050235 +v -0.056491 -0.020266 0.008422 +v -0.059938 -0.040092 0.029538 +v -0.075882 -0.019833 0.048508 +v -0.039673 -0.019833 -0.017882 +v -0.078039 -0.029749 0.050235 +v -0.070282 -0.032762 0.039020 +v -0.039673 -0.040092 0.009282 +v -0.040106 -0.031039 -0.007960 +v -0.042263 -0.021128 -0.014001 +v -0.076748 -0.025008 0.044627 +v -0.073296 -0.040092 0.050235 +v -0.080629 -0.019833 0.050235 +v -0.040968 -0.040092 0.003675 +v -0.050453 -0.020266 -0.001493 +v -0.071144 -0.039229 0.045487 +v -0.055196 -0.039660 0.022211 +v -0.050453 -0.019833 -0.001493 +v -0.060796 -0.038367 0.029105 +v -0.041830 -0.025008 -0.011408 +v -0.074158 -0.034918 0.046781 +v -0.068125 -0.020266 0.027811 +v -0.039673 -0.031039 -0.007960 +v -0.040106 -0.034918 -0.003646 +v -0.049591 -0.040092 0.014883 +vt 0.208986 0.989428 +vt 0.398786 0.842013 +vt 0.481010 0.757831 +vt 0.411413 0.989428 +vt 1.000000 0.094753 +vt 0.987275 0.305305 +vt 1.000000 0.284260 +vt 0.980912 0.189507 +vt 0.303837 1.000000 +vt 0.696163 0.505188 +vt 0.974648 0.115897 +vt 0.101312 1.000000 +vt 0.980912 0.000000 +vt 0.000000 1.000000 +vt 0.063332 0.989428 +vt 0.000000 0.989428 +vt 0.980912 0.000000 +vt 0.987275 0.073708 +vt 1.000000 0.063234 +vt 0.398786 1.000000 +vt 0.917678 0.094753 +vt 0.386159 0.589370 +vt 1.000000 0.179033 +vt 1.000000 0.000000 +vt 0.316464 0.968383 +vt 0.240603 0.736785 +vt 0.835356 0.252643 +vt 0.056969 0.936766 +vt 0.930305 0.231597 +vt 0.145654 0.989428 +vt 0.588587 0.620987 +vt 0.240603 0.736785 +vt 0.689800 0.484240 +vt 0.095047 0.947337 +vt 0.949295 0.157987 +vt 0.670811 0.305305 +vt 0.145654 1.000000 +vn -0.6685 -0.5535 -0.4968 +vn 0.7714 0.3184 0.5510 +vn 0.6240 0.2443 0.7423 +vn 0.0000 -1.0000 0.0000 +vn 0.7607 0.4275 0.4885 +vn 0.0000 1.0000 0.0000 +vn 0.7531 0.4719 0.4584 +vn 1.0000 0.0000 0.0000 +vn 0.5388 -0.5396 -0.6469 +vn -0.9411 -0.2825 -0.1859 +vn 0.0000 -0.0000 1.0000 +vn 0.9037 0.3028 0.3027 +vn 0.7701 -0.3231 0.5501 +vn 0.7404 -0.4135 0.5300 +vn -0.8433 -0.2657 -0.4672 +vn -0.8172 -0.2939 -0.4957 +vn -0.8626 -0.4183 -0.2846 +vn -0.9084 -0.4165 -0.0369 +vn -1.0000 0.0000 0.0000 +vn 0.1059 0.9508 0.2912 +vn -0.9641 -0.2518 0.0837 +vn -0.8146 -0.3005 -0.4961 +vn -0.7997 -0.3386 -0.4958 +vn -0.8127 -0.2762 -0.5131 +vn -0.7950 -0.3483 -0.4966 +vn -0.7280 -0.4843 -0.4853 +vn -0.7102 -0.4981 -0.4975 +vn -0.6408 0.6417 -0.4215 +vn -0.8541 0.0000 -0.5201 +vn -0.8456 0.0000 -0.5339 +vn -0.7281 -0.4840 -0.4854 +vn -0.7221 -0.4821 -0.4962 +vn -0.7217 -0.4833 -0.4956 +vn -0.7466 -0.4261 -0.5109 +vn -0.7480 -0.4246 -0.5101 +vn -0.7614 -0.4169 -0.4965 +vn -0.7480 -0.4412 -0.4957 +vn -0.7367 -0.4593 -0.4963 +vn -0.8110 -0.3855 -0.4400 +vn -0.7988 -0.3431 -0.4943 +vn -0.7780 -0.3859 -0.4958 +vn -0.7773 -0.3971 -0.4881 +vn -0.7746 -0.3929 -0.4956 +vn -0.8605 0.0000 -0.5094 +vn -0.8365 -0.2348 -0.4952 +vn -0.8288 -0.2563 -0.4973 +vn -0.8284 0.2606 -0.4957 +vn -0.8446 0.1729 -0.5068 +vn 0.7463 -0.4412 -0.4983 +vn 0.0000 -0.7075 -0.7067 +vn 0.0000 -0.7436 -0.6686 +vn -0.6347 -0.5939 -0.4944 +vn -0.3747 -0.7358 -0.5641 +vn 0.4103 -0.6982 -0.5866 +vn -0.6215 -0.6206 -0.4782 +vn -0.6335 -0.6314 -0.4472 +vn -0.6889 -0.5289 -0.4957 +vn -0.6692 -0.5526 -0.4969 +usemtl None +s off +f 1131/1096/1576 1096/1097/1576 1132/1098/1576 +f 1100/1099/1577 1102/1100/1577 1104/1101/1577 +f 1104/1101/1578 1102/1100/1578 1108/1102/1578 +f 1101/1103/1579 1105/1104/1579 1108/1102/1579 +f 1105/1104/1579 1101/1103/1579 1110/1105/1579 +f 1102/1100/1580 1100/1099/1580 1111/1106/1580 +f 1103/1107/1581 1097/1108/1581 1111/1106/1581 +f 1100/1099/1582 1103/1107/1582 1111/1106/1582 +f 1097/1108/1581 1103/1107/1581 1112/1109/1581 +f 1103/1107/1583 1105/1104/1583 1112/1109/1583 +f 1107/1110/1584 1099/1111/1584 1112/1109/1584 +f 1098/1112/1585 1106/1113/1585 1113/1114/1585 +f 1108/1102/1586 1102/1100/1586 1113/1114/1586 +f 1103/1107/1587 1100/1099/1587 1115/1115/1587 +f 1100/1099/1588 1104/1101/1588 1115/1115/1588 +f 1105/1104/1583 1103/1107/1583 1115/1115/1583 +f 1104/1101/1589 1108/1102/1589 1115/1115/1589 +f 1108/1102/1579 1105/1104/1579 1115/1115/1579 +f 1106/1113/1590 1098/1112/1590 1118/1116/1590 +f 1109/1117/1591 1106/1113/1591 1118/1116/1591 +f 1106/1113/1592 1101/1103/1592 1119/1118/1592 +f 1101/1103/1579 1108/1102/1579 1119/1118/1579 +f 1113/1114/1593 1106/1113/1593 1119/1118/1593 +f 1108/1102/1586 1113/1114/1586 1119/1118/1586 +f 1097/1108/1594 1098/1112/1594 1120/1119/1594 +f 1111/1106/1581 1097/1108/1581 1120/1119/1581 +f 1102/1100/1595 1111/1106/1595 1120/1119/1595 +f 1098/1112/1596 1113/1114/1596 1120/1119/1596 +f 1113/1114/1586 1102/1100/1586 1120/1119/1586 +f 1105/1104/1579 1110/1105/1579 1121/1120/1579 +f 1106/1113/1597 1109/1117/1597 1122/1121/1597 +f 1114/1122/1598 1106/1113/1598 1122/1121/1598 +f 1099/1111/1599 1117/1123/1599 1122/1121/1599 +f 1117/1123/1600 1114/1122/1600 1122/1121/1600 +f 1110/1105/1601 1101/1103/1601 1123/1124/1601 +f 1107/1110/1602 1116/1125/1602 1124/1126/1602 +f 1097/1108/1581 1112/1109/1581 1125/1127/1581 +f 1112/1109/1603 1099/1111/1603 1125/1127/1603 +f 1122/1121/1604 1109/1117/1604 1125/1127/1604 +f 1099/1111/1605 1122/1121/1605 1125/1127/1605 +f 1110/1105/1606 1123/1124/1606 1126/1128/1606 +f 1107/1110/1607 1124/1126/1607 1126/1128/1607 +f 1124/1126/1608 1110/1105/1608 1126/1128/1608 +f 1099/1111/1609 1107/1110/1609 1127/1129/1609 +f 1117/1123/1610 1099/1111/1610 1127/1129/1610 +f 1123/1124/1611 1117/1123/1611 1127/1129/1611 +f 1126/1128/1612 1123/1124/1612 1127/1129/1612 +f 1107/1110/1613 1126/1128/1613 1127/1129/1613 +f 1101/1103/1614 1106/1113/1614 1128/1130/1614 +f 1106/1113/1615 1114/1122/1615 1128/1130/1615 +f 1114/1122/1616 1117/1123/1616 1128/1130/1616 +f 1123/1124/1617 1101/1103/1617 1128/1130/1617 +f 1117/1123/1618 1123/1124/1618 1128/1130/1618 +f 1098/1112/1619 1097/1108/1619 1129/1131/1619 +f 1118/1116/1620 1098/1112/1620 1129/1131/1620 +f 1109/1117/1621 1118/1116/1621 1129/1131/1621 +f 1097/1108/1622 1125/1127/1622 1129/1131/1622 +f 1125/1127/1623 1109/1117/1623 1129/1131/1623 +f 1112/1109/1583 1105/1104/1583 1130/1132/1583 +f 1107/1110/1624 1112/1109/1624 1130/1132/1624 +f 1116/1125/1625 1107/1110/1625 1130/1132/1625 +f 1116/1125/1626 1130/1132/1626 1131/1096/1626 +f 1121/1120/1627 1096/1097/1627 1131/1096/1627 +f 1105/1104/1628 1121/1120/1628 1131/1096/1628 +f 1130/1132/1629 1105/1104/1629 1131/1096/1629 +f 1096/1097/1630 1121/1120/1630 1132/1098/1630 +f 1121/1120/1579 1110/1105/1579 1132/1098/1579 +f 1110/1105/1631 1124/1126/1631 1132/1098/1631 +f 1124/1126/1632 1116/1125/1632 1132/1098/1632 +f 1116/1125/1633 1131/1096/1633 1132/1098/1633 +o Bowl_hull_35 +v 0.037064 -0.024576 -0.018744 +v 0.040084 -0.039663 0.008847 +v 0.040084 -0.039663 0.002376 +v 0.009043 -0.039663 -0.018744 +v 0.039652 -0.006898 -0.018312 +v 0.020255 -0.039663 -0.018744 +v 0.040084 -0.019406 -0.018744 +v 0.009043 -0.039230 -0.018309 +v 0.039652 -0.039227 0.008847 +v 0.030163 -0.032764 -0.018744 +v 0.040084 -0.006898 -0.018744 +v 0.029732 -0.039230 -0.010552 +v 0.040084 -0.031468 -0.007533 +v 0.033184 -0.029743 -0.018744 +v 0.037924 -0.039663 -0.000641 +v 0.025855 -0.036209 -0.018744 +v 0.040084 -0.037504 -0.000641 +v 0.040084 -0.025003 -0.014001 +v 0.032752 -0.039663 -0.006669 +v 0.039652 -0.006898 -0.018744 +vt 0.000000 0.986100 +vt 0.000000 1.000000 +vt 0.000000 0.986100 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 1.000000 0.361198 +vt 0.539546 0.902702 +vt 0.381754 1.000000 +vt 0.986785 0.000000 +vt 0.986688 0.986100 +vt 0.789448 0.680403 +vt 0.749902 1.000000 +vt 0.697240 0.777702 +vt 1.000000 0.930403 +vt 0.894577 0.541601 +vt 0.986785 0.666503 +vt 0.934123 1.000000 +vt 0.552565 1.000000 +vt 1.000000 0.763802 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn -0.5313 -0.6003 0.5978 +vn -0.5620 0.5321 0.6333 +vn 0.5452 0.5393 0.6419 +vn -0.5548 -0.5488 0.6254 +vn 0.6082 0.5113 0.6072 +vn 0.6903 -0.5184 -0.5047 +vn 0.4576 -0.7418 -0.4902 +vn 0.5393 -0.6746 -0.5041 +vn 0.6137 -0.6135 -0.4969 +vn 0.6616 -0.5641 -0.4940 +vn 0.6306 -0.6312 -0.4516 +vn 0.6134 -0.6139 -0.4969 +vn 0.7420 -0.4334 -0.5115 +vn 0.7107 -0.4975 -0.4973 +vn 0.3677 -0.8485 -0.3805 +vn 0.5475 -0.6706 -0.5005 +vn 0.5769 -0.6498 -0.4949 +vn -0.6043 0.5646 -0.5622 +vn -0.7262 0.6875 0.0000 +usemtl None +s off +f 1137/1133/1634 1143/1134/1634 1152/1135/1634 +f 1135/1136/1635 1134/1137/1635 1136/1138/1635 +f 1135/1136/1635 1136/1138/1635 1138/1139/1635 +f 1136/1138/1636 1133/1140/1636 1138/1139/1636 +f 1134/1137/1637 1135/1136/1637 1139/1141/1637 +f 1133/1140/1636 1136/1138/1636 1139/1141/1636 +f 1136/1138/1638 1134/1137/1638 1140/1142/1638 +f 1137/1133/1639 1140/1142/1639 1141/1143/1639 +f 1134/1137/1640 1137/1133/1640 1141/1143/1640 +f 1140/1142/1641 1134/1137/1641 1141/1143/1641 +f 1138/1139/1636 1133/1140/1636 1142/1144/1636 +f 1137/1133/1642 1134/1137/1642 1143/1134/1642 +f 1134/1137/1637 1139/1141/1637 1143/1134/1637 +f 1139/1141/1636 1136/1138/1636 1143/1134/1636 +f 1139/1141/1637 1135/1136/1637 1145/1145/1637 +f 1142/1144/1636 1133/1140/1636 1146/1146/1636 +f 1133/1140/1643 1145/1145/1643 1146/1146/1643 +f 1135/1136/1635 1138/1139/1635 1147/1147/1635 +f 1138/1139/1636 1142/1144/1636 1148/1148/1636 +f 1144/1149/1644 1138/1139/1644 1148/1148/1644 +f 1142/1144/1645 1144/1149/1645 1148/1148/1645 +f 1145/1145/1637 1135/1136/1637 1149/1150/1637 +f 1142/1144/1646 1146/1146/1646 1149/1150/1646 +f 1146/1146/1647 1145/1145/1647 1149/1150/1647 +f 1135/1136/1648 1147/1147/1648 1149/1150/1648 +f 1147/1147/1649 1142/1144/1649 1149/1150/1649 +f 1133/1140/1650 1139/1141/1650 1150/1151/1650 +f 1145/1145/1651 1133/1140/1651 1150/1151/1651 +f 1139/1141/1637 1145/1145/1637 1150/1151/1637 +f 1138/1139/1652 1144/1149/1652 1151/1152/1652 +f 1144/1149/1653 1142/1144/1653 1151/1152/1653 +f 1147/1147/1635 1138/1139/1635 1151/1152/1635 +f 1142/1144/1654 1147/1147/1654 1151/1152/1654 +f 1136/1138/1655 1140/1142/1655 1152/1135/1655 +f 1140/1142/1656 1137/1133/1656 1152/1135/1656 +f 1143/1134/1636 1136/1138/1636 1152/1135/1636 +o Bowl_hull_36 +v -0.039241 -0.029742 -0.010548 +v -0.039673 -0.007763 -0.019172 +v -0.039673 -0.007763 -0.018739 +v -0.005183 -0.039660 -0.019175 +v -0.039241 -0.039657 0.008847 +v -0.022857 -0.037936 -0.019175 +v -0.039673 -0.040094 0.002379 +v -0.039673 -0.019403 -0.019172 +v -0.018549 -0.040091 -0.019175 +v -0.032772 -0.030176 -0.018739 +v -0.005183 -0.039660 -0.018742 +v -0.039241 -0.007763 -0.018739 +v -0.039673 -0.040094 0.008847 +v -0.031050 -0.040094 -0.007962 +v -0.005183 -0.040091 -0.018742 +v -0.029325 -0.033192 -0.019172 +v -0.039673 -0.037932 -0.000638 +v -0.036222 -0.025432 -0.019172 +v -0.037515 -0.040094 -0.000638 +v -0.039673 -0.023283 -0.016152 +v -0.025014 -0.040091 -0.013999 +v -0.027600 -0.036211 -0.017016 +vt 0.487569 0.933242 +vt 0.425020 0.999902 +vt 0.350039 0.879894 +vt 0.000000 0.000000 +vt 1.000000 0.986590 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 0.000000 0.360023 +vt 0.612471 0.999902 +vt 0.012529 0.000000 +vt 0.012529 0.986492 +vt 1.000000 0.986590 +vt 0.000000 1.000000 +vt 0.250000 1.000000 +vt 1.000000 0.999902 +vt 0.000000 0.933144 +vt 0.012529 0.679816 +vt 0.200078 0.693226 +vt 0.100039 0.546496 +vt 0.300020 0.786511 +vt 0.062549 1.000000 +vt 0.000000 0.480031 +vn -0.4879 -0.7148 -0.5010 +vn 0.0000 0.0001 -1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.0002 0.0000 -1.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 1.0000 0.0000 +vn 0.5622 0.6080 -0.5606 +vn 0.0000 0.6542 0.7563 +vn 0.6836 0.7299 0.0000 +vn 0.5225 0.5578 0.6449 +vn -0.5485 0.5427 0.6361 +vn 0.0000 -1.0000 0.0000 +vn 0.0002 -1.0000 0.0001 +vn 0.0228 -0.7094 -0.7045 +vn 1.0000 0.0000 0.0000 +vn 0.6295 0.0000 0.7770 +vn 0.5314 -0.5258 0.6642 +vn 0.0000 -1.0000 -0.0003 +vn -0.6630 -0.5626 -0.4938 +vn -0.0004 -0.0003 -1.0000 +vn -0.6754 -0.5374 -0.5050 +vn -0.0012 -0.0011 -1.0000 +vn -0.4510 -0.4009 -0.7974 +vn -0.6055 -0.6203 -0.4986 +vn -0.5607 -0.6638 -0.4950 +vn -0.6315 -0.6303 -0.4515 +vn -0.6142 -0.6130 -0.4969 +vn -0.8912 -0.3298 -0.3114 +vn -0.7316 -0.4187 -0.5379 +vn -0.7281 -0.4764 -0.4929 +vn -0.3906 -0.7807 -0.4878 +vn -0.0021 -1.0000 -0.0026 +vn -0.4946 -0.7145 -0.4949 +vn -0.4947 -0.6742 -0.5483 +vn -0.5511 -0.6700 -0.4973 +usemtl None +s off +f 1158/1153/1657 1173/1154/1657 1174/1155/1657 +f 1154/1156/1658 1156/1157/1658 1158/1153/1658 +f 1155/1158/1659 1154/1156/1659 1159/1159/1659 +f 1154/1156/1660 1158/1153/1660 1160/1160/1660 +f 1159/1159/1659 1154/1156/1659 1160/1160/1659 +f 1158/1153/1661 1156/1157/1661 1161/1161/1661 +f 1154/1156/1662 1155/1158/1662 1164/1162/1662 +f 1156/1157/1663 1154/1156/1663 1164/1162/1663 +f 1155/1158/1664 1157/1163/1664 1164/1162/1664 +f 1163/1164/1665 1156/1157/1665 1164/1162/1665 +f 1157/1163/1666 1163/1164/1666 1164/1162/1666 +f 1157/1163/1667 1155/1158/1667 1165/1165/1667 +f 1155/1158/1659 1159/1159/1659 1165/1165/1659 +f 1165/1165/1668 1159/1159/1668 1166/1166/1668 +f 1165/1165/1669 1166/1166/1669 1167/1167/1669 +f 1161/1161/1670 1156/1157/1670 1167/1167/1670 +f 1156/1157/1671 1163/1164/1671 1167/1167/1671 +f 1163/1164/1672 1157/1163/1672 1167/1167/1672 +f 1157/1163/1673 1165/1165/1673 1167/1167/1673 +f 1166/1166/1674 1161/1161/1674 1167/1167/1674 +f 1159/1159/1659 1160/1160/1659 1169/1168/1659 +f 1153/1169/1675 1162/1170/1675 1169/1168/1675 +f 1160/1160/1676 1158/1153/1676 1170/1171/1676 +f 1162/1170/1677 1153/1169/1677 1170/1171/1677 +f 1158/1153/1678 1168/1172/1678 1170/1171/1678 +f 1168/1172/1679 1162/1170/1679 1170/1171/1679 +f 1166/1166/1668 1159/1159/1668 1171/1173/1668 +f 1162/1170/1680 1168/1172/1680 1171/1173/1680 +f 1168/1172/1681 1166/1166/1681 1171/1173/1681 +f 1159/1159/1682 1169/1168/1682 1171/1173/1682 +f 1169/1168/1683 1162/1170/1683 1171/1173/1683 +f 1153/1169/1684 1169/1168/1684 1172/1174/1684 +f 1169/1168/1659 1160/1160/1659 1172/1174/1659 +f 1160/1160/1685 1170/1171/1685 1172/1174/1685 +f 1170/1171/1686 1153/1169/1686 1172/1174/1686 +f 1158/1153/1687 1161/1161/1687 1173/1154/1687 +f 1161/1161/1688 1166/1166/1688 1173/1154/1688 +f 1173/1154/1689 1166/1166/1689 1174/1155/1689 +f 1168/1172/1690 1158/1153/1690 1174/1155/1690 +f 1166/1166/1691 1168/1172/1691 1174/1155/1691 +o Bowl_hull_37 +v -0.055196 -0.045701 0.028676 +v -0.042259 -0.071565 0.050235 +v -0.042259 -0.067253 0.050235 +v -0.072867 -0.040094 0.050230 +v -0.042259 -0.040094 0.013162 +v -0.068124 -0.040094 0.049800 +v -0.042691 -0.040525 0.006692 +v -0.054330 -0.063371 0.049365 +v -0.065107 -0.052167 0.049369 +v -0.042691 -0.059061 0.030829 +v -0.064676 -0.040528 0.036864 +v -0.045711 -0.069837 0.049369 +v -0.042691 -0.045701 0.012731 +v -0.061227 -0.056905 0.049800 +v -0.042259 -0.040094 0.006692 +v -0.042691 -0.040094 0.014023 +v -0.071141 -0.043547 0.049369 +v -0.051745 -0.040528 0.018336 +v -0.042259 -0.066821 0.049800 +v -0.059936 -0.055614 0.046352 +v -0.043554 -0.041388 0.008418 +v -0.053471 -0.064234 0.050235 +v -0.065970 -0.047857 0.045921 +v -0.068556 -0.040094 0.050230 +v -0.042259 -0.071565 0.049369 +v -0.053902 -0.056474 0.039882 +v -0.067261 -0.049582 0.050230 +v -0.072867 -0.040094 0.049369 +v -0.050022 -0.066821 0.049365 +v -0.043554 -0.052170 0.022219 +v -0.042259 -0.053464 0.023076 +v -0.051745 -0.040097 0.018336 +v -0.043122 -0.071131 0.048935 +v -0.059073 -0.040960 0.029107 +v -0.061227 -0.050013 0.041608 +v -0.056919 -0.060355 0.048508 +vt 0.910826 0.493148 +vt 0.762236 0.520458 +vt 0.960356 0.643794 +vt 1.000000 0.862960 +vt 1.000000 1.000000 +vt 0.148590 0.000000 +vt 0.999902 0.000000 +vt 0.990016 0.000000 +vt 0.000000 0.000000 +vt 0.138704 0.178152 +vt 0.000000 0.013704 +vt 0.168363 0.000000 +vt 0.990016 0.849256 +vt 0.990016 0.534162 +vt 0.980129 0.383614 +vt 0.039644 0.041112 +vt 0.504894 0.178152 +vt 0.267424 0.013802 +vt 1.000000 0.767032 +vt 0.980129 0.945086 +vt 0.980031 0.739624 +vt 0.980129 0.109730 +vt 0.900940 0.246672 +vt 0.692933 0.013802 +vt 0.999902 0.000000 +vt 0.980129 1.000000 +vt 0.999902 0.301488 +vt 0.980129 0.000000 +vt 0.554327 0.602682 +vt 0.980031 0.849256 +vt 0.356597 0.383712 +vt 0.376272 0.424824 +vt 0.267424 0.000098 +vt 0.970145 0.986198 +vt 0.514781 0.027506 +vt 0.801879 0.315192 +vn -0.6155 -0.6156 -0.4922 +vn 1.0000 0.0000 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.6046 -0.6048 -0.5183 +vn 0.5915 0.5724 0.5679 +vn 0.7618 0.5233 0.3818 +vn 0.6399 0.6193 0.4549 +vn -0.6628 -0.5852 -0.4673 +vn -0.4770 -0.6674 -0.5719 +vn -0.6637 -0.5565 -0.4999 +vn -0.7228 -0.4019 -0.5621 +vn -0.6513 -0.5738 -0.4965 +vn -0.0000 0.0000 1.0000 +vn -0.4873 -0.7451 0.4555 +vn -0.6848 -0.7274 -0.0444 +vn -0.7293 -0.5105 -0.4556 +vn -0.7271 -0.4791 -0.4916 +vn 0.5830 0.5646 0.5843 +vn 0.0001 0.0002 1.0000 +vn 0.0000 0.0002 1.0000 +vn -0.4477 -0.8942 0.0000 +vn -0.5805 -0.6458 -0.4959 +vn -0.6087 -0.6186 -0.4968 +vn -0.6184 -0.6097 -0.4957 +vn -0.7722 -0.6348 -0.0265 +vn -0.8213 -0.4852 0.3000 +vn -0.7784 -0.5449 -0.3117 +vn -0.0008 -0.0005 1.0000 +vn -0.4144 -0.3898 0.8224 +vn -0.8945 -0.4470 0.0000 +vn -0.7770 -0.3883 -0.4955 +vn -0.4977 -0.7122 -0.4950 +vn -0.5657 -0.8084 0.1624 +vn -0.6176 -0.7712 -0.1543 +vn -0.5733 -0.6517 -0.4965 +vn -0.4464 -0.7199 -0.5315 +vn -0.5430 -0.6781 -0.4954 +vn -0.5294 -0.6874 -0.4972 +vn -0.2292 -0.7831 -0.5781 +vn 0.7729 -0.4916 -0.4012 +vn 0.4446 -0.7378 -0.5079 +vn -0.6127 0.6129 -0.4989 +vn -0.7894 0.0000 -0.6138 +vn -0.8200 0.0000 -0.5723 +vn -0.0027 1.0000 -0.0019 +vn -0.7053 0.5216 -0.4801 +vn -0.4527 -0.7369 -0.5020 +vn -0.4477 -0.8942 -0.0048 +vn -0.1362 -0.8228 -0.5518 +vn -0.7719 -0.3377 -0.5387 +vn -0.7221 -0.4837 -0.4946 +vn -0.7007 -0.5115 -0.4973 +vn -0.6792 -0.5402 -0.4969 +vn -0.6546 -0.5708 -0.4957 +vn -0.6631 -0.5669 -0.4888 +vn -0.6893 -0.5317 -0.4921 +vn -0.6905 -0.5266 -0.4960 +vn -0.6447 -0.6620 -0.3823 +vn -0.6336 -0.6161 -0.4679 +vn -0.5855 -0.6428 -0.4940 +usemtl None +s off +f 1194/1175/1692 1200/1176/1692 1210/1177/1692 +f 1177/1178/1693 1176/1179/1693 1179/1180/1693 +f 1179/1180/1694 1178/1181/1694 1180/1182/1694 +f 1178/1181/1694 1179/1180/1694 1189/1183/1694 +f 1179/1180/1693 1176/1179/1693 1189/1183/1693 +f 1187/1184/1695 1181/1185/1695 1189/1183/1695 +f 1179/1180/1694 1180/1182/1694 1190/1186/1694 +f 1177/1178/1693 1179/1180/1693 1193/1187/1693 +f 1180/1182/1696 1177/1178/1696 1193/1187/1696 +f 1179/1180/1697 1190/1186/1697 1193/1187/1697 +f 1190/1186/1698 1180/1182/1698 1193/1187/1698 +f 1188/1188/1699 1183/1189/1699 1194/1175/1699 +f 1181/1185/1700 1187/1184/1700 1195/1190/1700 +f 1175/1191/1701 1192/1192/1701 1195/1190/1701 +f 1192/1192/1702 1181/1185/1702 1195/1190/1702 +f 1194/1175/1703 1175/1191/1703 1195/1190/1703 +f 1176/1179/1704 1177/1178/1704 1196/1193/1704 +f 1186/1194/1705 1176/1179/1705 1196/1193/1705 +f 1188/1188/1706 1182/1195/1706 1196/1193/1706 +f 1183/1189/1707 1191/1196/1707 1197/1197/1707 +f 1191/1196/1708 1185/1198/1708 1197/1197/1708 +f 1177/1178/1709 1180/1182/1709 1198/1199/1709 +f 1180/1182/1694 1178/1181/1694 1198/1199/1694 +f 1196/1193/1710 1177/1178/1710 1198/1199/1710 +f 1178/1181/1711 1196/1193/1711 1198/1199/1711 +f 1176/1179/1712 1186/1194/1712 1199/1200/1712 +f 1189/1183/1693 1176/1179/1693 1199/1200/1693 +f 1187/1184/1713 1182/1195/1713 1200/1176/1713 +f 1195/1190/1714 1187/1184/1714 1200/1176/1714 +f 1194/1175/1715 1195/1190/1715 1200/1176/1715 +f 1183/1189/1716 1188/1188/1716 1201/1201/1716 +f 1178/1181/1717 1191/1196/1717 1201/1201/1717 +f 1191/1196/1718 1183/1189/1718 1201/1201/1718 +f 1196/1193/1719 1178/1181/1719 1201/1201/1719 +f 1188/1188/1720 1196/1193/1720 1201/1201/1720 +f 1178/1181/1694 1189/1183/1694 1202/1202/1694 +f 1191/1196/1721 1178/1181/1721 1202/1202/1721 +f 1185/1198/1722 1191/1196/1722 1202/1202/1722 +f 1184/1203/1723 1186/1194/1723 1203/1204/1723 +f 1186/1194/1724 1196/1193/1724 1203/1204/1724 +f 1196/1193/1725 1182/1195/1725 1203/1204/1725 +f 1182/1195/1726 1187/1184/1726 1204/1205/1726 +f 1187/1184/1727 1184/1203/1727 1204/1205/1727 +f 1203/1204/1728 1182/1195/1728 1204/1205/1728 +f 1184/1203/1729 1203/1204/1729 1204/1205/1729 +f 1184/1203/1730 1187/1184/1730 1205/1206/1730 +f 1187/1184/1731 1189/1183/1731 1205/1206/1731 +f 1199/1200/1732 1184/1203/1732 1205/1206/1732 +f 1189/1183/1693 1199/1200/1693 1205/1206/1693 +f 1189/1183/1733 1181/1185/1733 1206/1207/1733 +f 1181/1185/1734 1192/1192/1734 1206/1207/1734 +f 1192/1192/1735 1185/1198/1735 1206/1207/1735 +f 1202/1202/1736 1189/1183/1736 1206/1207/1736 +f 1185/1198/1737 1202/1202/1737 1206/1207/1737 +f 1186/1194/1738 1184/1203/1738 1207/1208/1738 +f 1199/1200/1739 1186/1194/1739 1207/1208/1739 +f 1184/1203/1740 1199/1200/1740 1207/1208/1740 +f 1185/1198/1741 1192/1192/1741 1208/1209/1741 +f 1197/1197/1742 1185/1198/1742 1208/1209/1742 +f 1192/1192/1743 1197/1197/1743 1208/1209/1743 +f 1192/1192/1744 1175/1191/1744 1209/1210/1744 +f 1175/1191/1745 1194/1175/1745 1209/1210/1745 +f 1194/1175/1746 1183/1189/1746 1209/1210/1746 +f 1183/1189/1747 1197/1197/1747 1209/1210/1747 +f 1197/1197/1748 1192/1192/1748 1209/1210/1748 +f 1182/1195/1749 1188/1188/1749 1210/1177/1749 +f 1188/1188/1750 1194/1175/1750 1210/1177/1750 +f 1200/1176/1751 1182/1195/1751 1210/1177/1751 +o Bowl_hull_38 +v -0.039240 -0.047428 0.011009 +v -0.025879 -0.078894 0.050235 +v -0.025879 -0.075009 0.050235 +v -0.025879 -0.040094 -0.011846 +v -0.041826 -0.040098 0.012735 +v -0.042259 -0.071993 0.049797 +v -0.025879 -0.040531 -0.004511 +v -0.041395 -0.067679 0.050235 +v -0.042259 -0.040531 0.005837 +v -0.026310 -0.052601 0.006263 +v -0.031483 -0.076737 0.048503 +v -0.027603 -0.042251 -0.008395 +v -0.042259 -0.059065 0.030394 +v -0.040965 -0.072426 0.048934 +v -0.042259 -0.066821 0.049366 +v -0.026310 -0.078894 0.048940 +v -0.032344 -0.040960 -0.005374 +v -0.042259 -0.040098 0.012735 +v -0.035361 -0.072856 0.045057 +v -0.025879 -0.062077 0.021345 +v -0.034929 -0.075875 0.050235 +v -0.042259 -0.040098 0.005837 +v -0.025879 -0.040094 -0.005374 +v -0.026310 -0.062077 0.021345 +v -0.040965 -0.062939 0.034708 +v -0.042259 -0.047428 0.014454 +v -0.026310 -0.048723 0.000228 +v -0.041395 -0.040098 0.012303 +v -0.036655 -0.040531 -0.001060 +v -0.025879 -0.040964 -0.011415 +v -0.042259 -0.071993 0.050235 +v -0.027171 -0.045700 -0.003655 +v -0.041826 -0.066821 0.049366 +v -0.041826 -0.056049 0.025654 +vt 0.680403 0.488939 +vt 0.423649 0.189017 +vt 0.604052 0.411218 +vt 1.000000 0.899863 +vt 1.000000 1.000000 +vt 0.000000 0.000000 +vt 0.118148 0.011257 +vt 1.000000 0.710944 +vt 0.992952 0.822142 +vt 0.284847 0.011257 +vt 0.979052 0.833301 +vt 0.986002 0.688821 +vt 0.395948 0.000098 +vt 0.395948 0.000098 +vt 0.972103 0.944401 +vt 0.916601 0.844362 +vt 0.534652 0.566562 +vt 0.979150 1.000000 +vt 1.000000 0.922181 +vt 0.284847 0.000098 +vt 0.104248 0.000000 +vt 0.534652 0.566562 +vt 0.291699 0.322337 +vt 0.055599 0.055599 +vt 0.749902 0.588782 +vt 0.194499 0.222396 +vt 0.388998 0.000098 +vt 0.104248 0.022318 +vt 0.368148 0.189017 +vt 0.173747 0.011257 +vt 0.006950 0.022416 +vt 1.000000 0.822142 +vt 0.131950 0.144479 +vt 0.986002 0.688821 +vn -0.6386 -0.6215 -0.4538 +vn 1.0000 0.0000 0.0000 +vn -0.0000 -0.0000 1.0000 +vn -1.0000 -0.0000 0.0000 +vn -0.5439 -0.6983 -0.4653 +vn 0.0000 0.8079 0.5894 +vn -0.3836 -0.7971 -0.4663 +vn 0.8337 -0.4773 -0.2778 +vn -0.4443 -0.8652 -0.2322 +vn -0.3978 -0.8375 -0.3746 +vn -0.3147 -0.9434 0.1049 +vn -0.3536 -0.8998 -0.2557 +vn -0.0002 1.0000 0.0000 +vn 0.0000 1.0000 0.0002 +vn -0.2979 -0.8151 -0.4968 +vn -0.3596 -0.7901 -0.4964 +vn -0.3537 -0.7933 -0.4956 +vn 0.0000 -0.8468 -0.5320 +vn 0.0000 -0.8539 -0.5204 +vn -0.4908 -0.7163 -0.4960 +vn -0.5394 -0.7005 -0.4672 +vn -0.3986 -0.7716 -0.4958 +vn -0.4018 -0.7700 -0.4956 +vn 0.3888 -0.7751 -0.4981 +vn 0.4799 0.7345 0.4798 +vn 0.5152 0.7252 0.4567 +vn 0.4573 0.7934 0.4016 +vn 0.0018 1.0000 0.0018 +vn -0.5637 -0.6593 -0.4975 +vn -0.7074 0.0000 -0.7068 +vn -0.7761 0.0000 -0.6306 +vn -0.4420 0.7982 -0.4093 +vn -0.5670 -0.6570 -0.4969 +vn -0.6096 -0.6189 -0.4954 +vn -0.6419 -0.3408 -0.6869 +vn -0.5335 -0.6243 -0.5706 +vn 0.4458 -0.7524 -0.4849 +vn -0.6373 0.1277 0.7600 +vn -0.4680 -0.8837 0.0000 +vn -0.4562 -0.7388 -0.4960 +vn -0.4496 -0.7431 -0.4956 +vn -0.4233 -0.7580 -0.4963 +vn -0.3514 -0.7720 -0.5297 +vn -0.3369 -0.7777 -0.5308 +vn 0.3574 0.7545 0.5504 +vn 0.3530 0.7473 0.5629 +vn 0.0000 0.7114 0.7027 +vn -0.5014 -0.7085 -0.4966 +vn -0.5399 -0.6802 -0.4958 +vn -0.5082 -0.7032 -0.4973 +vn -0.5607 -0.6665 -0.4914 +usemtl None +s off +f 1223/1211/1752 1236/1212/1752 1244/1213/1752 +f 1213/1214/1753 1212/1215/1753 1214/1216/1753 +f 1213/1214/1753 1214/1216/1753 1217/1217/1753 +f 1212/1215/1754 1213/1214/1754 1218/1218/1754 +f 1216/1219/1755 1219/1220/1755 1223/1211/1755 +f 1216/1219/1756 1223/1211/1756 1224/1221/1756 +f 1219/1220/1755 1216/1219/1755 1225/1222/1755 +f 1225/1222/1757 1215/1223/1757 1228/1224/1757 +f 1219/1220/1755 1225/1222/1755 1228/1224/1755 +f 1221/1225/1758 1224/1221/1758 1229/1226/1758 +f 1214/1216/1753 1212/1215/1753 1230/1227/1753 +f 1212/1215/1759 1226/1228/1759 1230/1227/1759 +f 1212/1215/1754 1218/1218/1754 1231/1229/1754 +f 1216/1219/1760 1224/1221/1760 1231/1229/1760 +f 1224/1221/1761 1221/1225/1761 1231/1229/1761 +f 1226/1228/1762 1212/1215/1762 1231/1229/1762 +f 1221/1225/1763 1226/1228/1763 1231/1229/1763 +f 1228/1224/1764 1214/1216/1764 1232/1230/1764 +f 1219/1220/1755 1228/1224/1755 1232/1230/1755 +f 1217/1217/1753 1214/1216/1753 1233/1231/1753 +f 1214/1216/1764 1228/1224/1764 1233/1231/1764 +f 1228/1224/1765 1215/1223/1765 1233/1231/1765 +f 1226/1228/1766 1221/1225/1766 1234/1232/1766 +f 1229/1226/1767 1220/1233/1767 1234/1232/1767 +f 1221/1225/1768 1229/1226/1768 1234/1232/1768 +f 1220/1233/1769 1230/1227/1769 1234/1232/1769 +f 1230/1227/1770 1226/1228/1770 1234/1232/1770 +f 1223/1211/1771 1222/1234/1771 1235/1235/1771 +f 1224/1221/1772 1223/1211/1772 1235/1235/1772 +f 1223/1211/1755 1219/1220/1755 1236/1212/1755 +f 1220/1233/1773 1229/1226/1773 1237/1236/1773 +f 1229/1226/1774 1224/1221/1774 1237/1236/1774 +f 1230/1227/1775 1220/1233/1775 1237/1236/1775 +f 1215/1223/1776 1213/1214/1776 1238/1237/1776 +f 1213/1214/1777 1217/1217/1777 1238/1237/1777 +f 1217/1217/1778 1233/1231/1778 1238/1237/1778 +f 1233/1231/1779 1215/1223/1779 1238/1237/1779 +f 1227/1238/1780 1211/1239/1780 1239/1240/1780 +f 1214/1216/1781 1227/1238/1781 1239/1240/1781 +f 1219/1220/1782 1232/1230/1782 1239/1240/1782 +f 1232/1230/1783 1214/1216/1783 1239/1240/1783 +f 1211/1239/1784 1236/1212/1784 1239/1240/1784 +f 1236/1212/1785 1219/1220/1785 1239/1240/1785 +f 1227/1238/1786 1214/1216/1786 1240/1241/1786 +f 1222/1234/1787 1227/1238/1787 1240/1241/1787 +f 1214/1216/1753 1230/1227/1753 1240/1241/1753 +f 1230/1227/1788 1237/1236/1788 1240/1241/1788 +f 1218/1218/1789 1225/1222/1789 1241/1242/1789 +f 1225/1222/1755 1216/1219/1755 1241/1242/1755 +f 1231/1229/1754 1218/1218/1754 1241/1242/1754 +f 1216/1219/1790 1231/1229/1790 1241/1242/1790 +f 1235/1235/1791 1222/1234/1791 1242/1243/1791 +f 1224/1221/1792 1235/1235/1792 1242/1243/1792 +f 1237/1236/1793 1224/1221/1793 1242/1243/1793 +f 1222/1234/1794 1240/1241/1794 1242/1243/1794 +f 1240/1241/1795 1237/1236/1795 1242/1243/1795 +f 1213/1214/1796 1215/1223/1796 1243/1244/1796 +f 1218/1218/1797 1213/1214/1797 1243/1244/1797 +f 1215/1223/1757 1225/1222/1757 1243/1244/1757 +f 1225/1222/1798 1218/1218/1798 1243/1244/1798 +f 1222/1234/1799 1223/1211/1799 1244/1213/1799 +f 1211/1239/1800 1227/1238/1800 1244/1213/1800 +f 1227/1238/1801 1222/1234/1801 1244/1213/1801 +f 1236/1212/1802 1211/1239/1802 1244/1213/1802 +o Bowl_hull_39 +v -0.024582 -0.059067 0.015314 +v -0.013376 -0.081912 0.050235 +v -0.013376 -0.078461 0.050235 +v -0.013376 -0.040094 -0.021331 +v -0.025445 -0.040528 -0.004946 +v -0.025877 -0.075441 0.050235 +v -0.013376 -0.040528 -0.013996 +v -0.025877 -0.078457 0.048070 +v -0.025877 -0.040962 -0.011839 +v -0.014237 -0.042681 -0.017877 +v -0.013807 -0.080185 0.045919 +v -0.021996 -0.080185 0.048932 +v -0.025014 -0.075011 0.049793 +v -0.013376 -0.078032 0.049800 +v -0.025877 -0.040098 -0.005807 +v -0.020703 -0.040528 -0.017016 +v -0.013807 -0.054327 0.001520 +v -0.025014 -0.040098 -0.005807 +v -0.025877 -0.079321 0.050235 +v -0.025877 -0.050876 0.003244 +v -0.017686 -0.081478 0.049366 +v -0.025877 -0.040098 -0.012273 +v -0.013376 -0.040958 -0.020896 +v -0.013376 -0.081912 0.048939 +v -0.015963 -0.041821 -0.018304 +v -0.025445 -0.072424 0.037723 +v -0.013376 -0.040094 -0.014858 +v -0.025877 -0.073287 0.047208 +v -0.020271 -0.044842 -0.010550 +v -0.025877 -0.065956 0.027384 +vt 0.042287 0.041308 +vt 0.825176 0.773101 +vt 0.680697 0.618442 +vt 1.000000 0.917482 +vt 1.000000 1.000000 +vt 0.000000 0.000000 +vt 1.000000 0.845243 +vt 0.102486 0.010376 +vt 0.969753 0.917384 +vt 0.132635 0.020752 +vt 0.993833 0.834965 +vt 0.993931 0.907204 +vt 0.216915 0.000098 +vt 0.981793 0.958692 +vt 0.048258 0.061864 +vt 0.319303 0.340348 +vt 0.228955 0.010376 +vt 0.216915 0.000098 +vt 1.000000 0.938039 +vt 0.343383 0.257831 +vt 0.060298 0.010376 +vt 0.939702 0.958692 +vt 0.987862 0.989624 +vt 0.126566 0.000098 +vt 0.006069 0.020654 +vt 0.981891 1.000000 +vt 0.090446 0.000000 +vt 0.957713 0.793755 +vt 0.512040 0.453700 +vt 0.150646 0.113547 +vn -0.3055 -0.8129 -0.4957 +vn 1.0000 0.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn -1.0000 -0.0000 0.0000 +vn 0.1362 0.5634 0.8149 +vn 0.1810 0.6990 0.6918 +vn -0.2356 -0.8355 -0.4964 +vn 0.2136 0.8273 0.5195 +vn 0.3621 0.8036 0.4724 +vn 0.2144 0.8272 0.5194 +vn 0.0000 0.8948 0.4464 +vn -0.3144 -0.8817 -0.3518 +vn -0.4324 -0.7535 -0.4953 +vn -0.1570 -0.8534 -0.4970 +vn -0.2035 -0.8444 -0.4957 +vn -0.1802 -0.8695 0.4599 +vn -0.2677 -0.9486 -0.1685 +vn -0.0003 1.0000 0.0000 +vn -0.6504 -0.3413 -0.6786 +vn -0.2776 0.8812 -0.3827 +vn -0.4469 -0.4019 -0.7992 +vn -0.0823 -0.8552 -0.5116 +vn 0.4075 -0.7877 -0.4620 +vn 0.0621 -0.8625 -0.5023 +vn -0.1002 -0.9950 -0.0000 +vn -0.1347 -0.8682 -0.4775 +vn -0.3582 -0.7180 -0.5968 +vn -0.2673 -0.8021 -0.5341 +vn -0.2566 -0.8298 -0.4956 +vn -0.2594 -0.8295 -0.4946 +vn -0.2856 -0.8199 -0.4962 +vn 0.3299 0.8431 0.4246 +vn 0.0000 1.0000 0.0005 +vn 0.0950 0.8426 0.5301 +vn -0.1087 0.8100 0.5763 +vn -0.2103 0.8287 0.5188 +vn -0.3694 -0.7869 -0.4943 +vn -0.3794 -0.7811 -0.4959 +vn -0.3311 -0.8024 -0.4965 +vn -0.3522 -0.7892 -0.5031 +vn -0.3922 -0.7802 -0.4874 +vn -0.3138 -0.8097 -0.4958 +vn -0.3981 -0.7851 -0.4745 +usemtl None +s off +f 1269/1245/1803 1270/1246/1803 1274/1247/1803 +f 1247/1248/1804 1246/1249/1804 1248/1250/1804 +f 1246/1249/1805 1247/1248/1805 1250/1251/1805 +f 1247/1248/1804 1248/1250/1804 1251/1252/1804 +f 1252/1253/1806 1250/1251/1806 1253/1254/1806 +f 1250/1251/1807 1247/1248/1807 1257/1255/1807 +f 1247/1248/1804 1251/1252/1804 1258/1256/1804 +f 1257/1255/1808 1247/1248/1808 1258/1256/1808 +f 1253/1254/1806 1250/1251/1806 1259/1257/1806 +f 1256/1258/1809 1254/1259/1809 1261/1260/1809 +f 1249/1261/1810 1257/1255/1810 1262/1262/1810 +f 1258/1256/1811 1251/1252/1811 1262/1262/1811 +f 1257/1255/1812 1258/1256/1812 1262/1262/1812 +f 1259/1257/1813 1249/1261/1813 1262/1262/1813 +f 1246/1249/1805 1250/1251/1805 1263/1263/1805 +f 1250/1251/1806 1252/1253/1806 1263/1263/1806 +f 1252/1253/1814 1256/1258/1814 1263/1263/1814 +f 1252/1253/1806 1253/1254/1806 1264/1264/1806 +f 1253/1254/1815 1260/1265/1815 1264/1264/1815 +f 1261/1260/1816 1255/1266/1816 1265/1267/1816 +f 1256/1258/1817 1261/1260/1817 1265/1267/1817 +f 1246/1249/1818 1263/1263/1818 1265/1267/1818 +f 1263/1263/1819 1256/1258/1819 1265/1267/1819 +f 1259/1257/1820 1248/1250/1820 1266/1268/1820 +f 1253/1254/1806 1259/1257/1806 1266/1268/1806 +f 1260/1265/1821 1253/1254/1821 1266/1268/1821 +f 1248/1250/1822 1260/1265/1822 1266/1268/1822 +f 1248/1250/1804 1246/1249/1804 1267/1269/1804 +f 1260/1265/1823 1248/1250/1823 1267/1269/1823 +f 1261/1260/1824 1254/1259/1824 1267/1269/1824 +f 1261/1260/1825 1267/1269/1825 1268/1270/1825 +f 1255/1266/1826 1261/1260/1826 1268/1270/1826 +f 1246/1249/1827 1265/1267/1827 1268/1270/1827 +f 1265/1267/1828 1255/1266/1828 1268/1270/1828 +f 1267/1269/1804 1246/1249/1804 1268/1270/1804 +f 1260/1265/1829 1267/1269/1829 1269/1245/1829 +f 1267/1269/1830 1254/1259/1830 1269/1245/1830 +f 1254/1259/1831 1256/1258/1831 1270/1246/1831 +f 1256/1258/1832 1252/1253/1832 1270/1246/1832 +f 1269/1245/1833 1254/1259/1833 1270/1246/1833 +f 1251/1252/1804 1248/1250/1804 1271/1271/1804 +f 1248/1250/1820 1259/1257/1820 1271/1271/1820 +f 1262/1262/1834 1251/1252/1834 1271/1271/1834 +f 1259/1257/1835 1262/1262/1835 1271/1271/1835 +f 1257/1255/1836 1249/1261/1836 1272/1272/1836 +f 1250/1251/1837 1257/1255/1837 1272/1272/1837 +f 1249/1261/1838 1259/1257/1838 1272/1272/1838 +f 1259/1257/1806 1250/1251/1806 1272/1272/1806 +f 1245/1273/1839 1264/1264/1839 1273/1274/1839 +f 1264/1264/1840 1260/1265/1840 1273/1274/1840 +f 1269/1245/1841 1245/1273/1841 1273/1274/1841 +f 1260/1265/1842 1269/1245/1842 1273/1274/1842 +f 1264/1264/1843 1245/1273/1843 1274/1247/1843 +f 1252/1253/1806 1264/1264/1806 1274/1247/1806 +f 1245/1273/1844 1269/1245/1844 1274/1247/1844 +f 1270/1246/1845 1252/1253/1845 1274/1247/1845 diff --git a/cram_boxy/cram_boxy_assembly_demo/resource/breakfast_cereal.stl b/cram_demos/cram_pr2_pick_place_demo/resource/breakfast_cereal.stl similarity index 100% rename from cram_boxy/cram_boxy_assembly_demo/resource/breakfast_cereal.stl rename to cram_demos/cram_pr2_pick_place_demo/resource/breakfast_cereal.stl diff --git a/cram_boxy/cram_boxy_assembly_demo/resource/buttermilk.dae b/cram_demos/cram_pr2_pick_place_demo/resource/buttermilk.dae similarity index 100% rename from cram_boxy/cram_boxy_assembly_demo/resource/buttermilk.dae rename to cram_demos/cram_pr2_pick_place_demo/resource/buttermilk.dae diff --git a/cram_boxy/cram_boxy_assembly_demo/resource/cereal.dae b/cram_demos/cram_pr2_pick_place_demo/resource/cereal.dae similarity index 100% rename from cram_boxy/cram_boxy_assembly_demo/resource/cereal.dae rename to cram_demos/cram_pr2_pick_place_demo/resource/cereal.dae diff --git a/cram_pr2/cram_pr2_pick_place_demo/resource/cube.stl b/cram_demos/cram_pr2_pick_place_demo/resource/cube.stl similarity index 100% rename from cram_pr2/cram_pr2_pick_place_demo/resource/cube.stl rename to cram_demos/cram_pr2_pick_place_demo/resource/cube.stl diff --git a/cram_demos/cram_pr2_pick_place_demo/resource/cup.obj b/cram_demos/cram_pr2_pick_place_demo/resource/cup.obj new file mode 100644 index 0000000000..6f38a826b1 --- /dev/null +++ b/cram_demos/cram_pr2_pick_place_demo/resource/cup.obj @@ -0,0 +1,4111 @@ +# Blender v2.83.4 OBJ File: '' +# www.blender.org +mtllib cup_33.mtl +o Cup_hull_1 +v 0.014889 0.020425 -0.050166 +v -0.014857 -0.020390 -0.048198 +v -0.015384 -0.020122 -0.048198 +v 0.014889 0.020425 -0.048198 +v 0.019895 -0.015647 -0.050166 +v -0.020386 0.014891 -0.050166 +v -0.015648 0.019893 -0.048198 +v 0.020427 -0.014856 -0.048198 +v -0.015384 -0.020122 -0.050166 +v -0.020390 -0.014856 -0.048198 +v 0.020423 0.014891 -0.050166 +v 0.014893 -0.020390 -0.048198 +v -0.014857 0.020425 -0.050166 +v 0.020423 0.014891 -0.048198 +v 0.014893 -0.020390 -0.050166 +v -0.020390 -0.014856 -0.050166 +v -0.020386 0.014891 -0.048198 +v 0.020427 -0.014856 -0.050166 +v -0.014857 0.020425 -0.048198 +v -0.014857 -0.020390 -0.050166 +v 0.018577 0.017260 -0.048198 +v -0.018808 0.016997 -0.050166 +v 0.016999 -0.018807 -0.048198 +v -0.019072 -0.016702 -0.048198 +v 0.017258 0.018579 -0.050166 +v -0.016702 -0.019071 -0.050166 +v -0.018808 0.016997 -0.048198 +v 0.016999 -0.018807 -0.050166 +v -0.016966 0.018839 -0.050166 +v 0.018840 -0.016966 -0.048198 +v -0.019072 -0.016702 -0.050166 +vt 0.090348 0.032302 +vt 0.032302 0.090348 +vt 0.032302 0.090348 +vt 0.122651 0.006558 +vt 0.135572 0.000000 +vt 0.864330 1.000000 +vt 0.864330 1.000000 +vt 0.986981 0.116190 +vt 0.000098 0.864428 +vt 0.116190 0.986981 +vt 1.000000 0.135572 +vt 0.122651 0.006558 +vt 0.000000 0.135572 +vt 0.999902 0.864428 +vt 0.864428 0.000000 +vt 0.135572 1.000000 +vt 0.999902 0.864428 +vt 0.864428 0.000000 +vt 0.000000 0.135572 +vt 0.000098 0.864428 +vt 1.000000 0.135572 +vt 0.135572 1.000000 +vt 0.135572 0.000000 +vt 0.954679 0.922475 +vt 0.038763 0.916014 +vt 0.916014 0.038763 +vt 0.922377 0.954777 +vt 0.038763 0.916014 +vt 0.916014 0.038763 +vt 0.083888 0.961139 +vt 0.961139 0.083888 +vn -0.7071 -0.7071 0.0000 +vn 0.0000 0.0000 1.0000 +vn -0.0000 0.0000 -1.0000 +vn -0.4526 -0.8917 0.0000 +vn 0.0000 1.0000 0.0000 +vn 1.0000 0.0001 0.0000 +vn 0.0000 -1.0000 0.0000 +vn -1.0000 0.0001 0.0000 +vn 0.8301 -0.5576 0.0000 +vn -0.5576 0.8301 0.0000 +vn 0.7888 0.6146 0.0000 +vn -0.8002 0.5998 0.0000 +vn 0.6007 -0.7995 0.0000 +vn -0.8137 -0.5813 0.0000 +vn 0.6146 0.7889 0.0000 +vn 0.6495 0.7570 0.0720 +vn 0.7569 0.6495 -0.0720 +vn -0.6232 -0.7820 0.0000 +vn -0.6786 -0.7317 0.0640 +vn -0.6007 0.7990 -0.0258 +vn -0.6745 0.7360 0.0575 +vn -0.7071 0.7071 0.0000 +vn 0.7990 -0.6008 0.0258 +vn 0.7360 -0.6746 -0.0575 +vn 0.7071 -0.7071 0.0000 +usemtl None +s off +f 26/1/1 24/2/1 31/3/1 +f 3/4/2 2/5/2 4/6/2 +f 1/7/3 5/8/3 6/9/3 +f 3/4/2 4/6/2 7/10/2 +f 4/6/2 2/5/2 8/11/2 +f 2/5/4 3/4/4 9/12/4 +f 6/9/3 5/8/3 9/12/3 +f 3/4/2 7/10/2 10/13/2 +f 5/8/3 1/7/3 11/14/3 +f 8/11/2 2/5/2 12/15/2 +f 4/6/5 1/7/5 13/16/5 +f 1/7/3 6/9/3 13/16/3 +f 4/6/2 8/11/2 14/17/2 +f 8/11/6 11/14/6 14/17/6 +f 9/12/3 5/8/3 15/18/3 +f 12/15/7 2/5/7 15/18/7 +f 6/9/3 9/12/3 16/19/3 +f 10/13/8 6/9/8 16/19/8 +f 6/9/8 10/13/8 17/20/8 +f 10/13/2 7/10/2 17/20/2 +f 8/11/9 5/8/9 18/21/9 +f 5/8/3 11/14/3 18/21/3 +f 11/14/6 8/11/6 18/21/6 +f 7/10/2 4/6/2 19/22/2 +f 4/6/5 13/16/5 19/22/5 +f 13/16/10 7/10/10 19/22/10 +f 2/5/4 9/12/4 20/23/4 +f 15/18/7 2/5/7 20/23/7 +f 9/12/3 15/18/3 20/23/3 +f 4/6/2 14/17/2 21/24/2 +f 14/17/11 11/14/11 21/24/11 +f 13/16/3 6/9/3 22/25/3 +f 6/9/12 17/20/12 22/25/12 +f 8/11/2 12/15/2 23/26/2 +f 12/15/13 15/18/13 23/26/13 +f 3/4/2 10/13/2 24/2/2 +f 10/13/14 16/19/14 24/2/14 +f 1/7/15 4/6/15 25/27/15 +f 11/14/3 1/7/3 25/27/3 +f 4/6/16 21/24/16 25/27/16 +f 21/24/17 11/14/17 25/27/17 +f 9/12/18 3/4/18 26/1/18 +f 16/19/3 9/12/3 26/1/3 +f 3/4/19 24/2/19 26/1/19 +f 17/20/2 7/10/2 27/28/2 +f 22/25/12 17/20/12 27/28/12 +f 15/18/3 5/8/3 28/29/3 +f 23/26/13 15/18/13 28/29/13 +f 7/10/20 13/16/20 29/30/20 +f 13/16/3 22/25/3 29/30/3 +f 27/28/21 7/10/21 29/30/21 +f 22/25/22 27/28/22 29/30/22 +f 5/8/23 8/11/23 30/31/23 +f 8/11/2 23/26/2 30/31/2 +f 28/29/24 5/8/24 30/31/24 +f 23/26/25 28/29/25 30/31/25 +f 24/2/14 16/19/14 31/3/14 +f 16/19/3 26/1/3 31/3/3 +o Cup_hull_2 +v 0.020427 0.005943 -0.048198 +v 0.013054 0.012263 0.015036 +v 0.013317 0.011736 0.013909 +v 0.020427 0.012526 0.015036 +v 0.013054 0.012526 -0.048198 +v 0.017003 0.005943 0.015036 +v 0.020427 0.012526 -0.048198 +v 0.016740 0.006206 -0.048198 +v 0.020427 0.005943 0.015036 +v 0.013054 0.012526 0.015036 +v 0.013317 0.011736 -0.048198 +v 0.017003 0.005943 -0.048198 +v 0.016740 0.006206 0.015036 +v 0.013054 0.012263 -0.048198 +vt 1.000000 0.000000 +vt 1.000000 0.035732 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 0.000000 0.535683 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.499951 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 0.017815 0.035732 +vt 1.000000 0.535683 +vt 0.000000 0.499951 +vn 0.0000 0.0000 -1.0000 +vn -0.0000 0.0000 1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.8945 -0.4470 0.0000 +vn -0.8503 -0.5263 0.0000 +vn -0.7073 -0.7069 0.0000 +vn -0.8534 -0.5194 0.0435 +usemtl None +s off +f 36/32/26 42/33/26 45/34/26 +f 35/35/27 33/36/27 37/37/27 +f 35/35/28 32/38/28 38/39/28 +f 32/38/26 36/32/26 38/39/26 +f 36/32/29 35/35/29 38/39/29 +f 36/32/26 32/38/26 39/40/26 +f 32/38/28 35/35/28 40/41/28 +f 35/35/27 37/37/27 40/41/27 +f 37/37/30 32/38/30 40/41/30 +f 33/36/27 35/35/27 41/42/27 +f 35/35/29 36/32/29 41/42/29 +f 36/32/31 33/36/31 41/42/31 +f 34/43/32 33/36/32 42/33/32 +f 36/32/26 39/40/26 42/33/26 +f 39/40/33 34/43/33 42/33/33 +f 32/38/30 37/37/30 43/44/30 +f 39/40/26 32/38/26 43/44/26 +f 37/37/34 39/40/34 43/44/34 +f 33/36/35 34/43/35 44/45/35 +f 37/37/27 33/36/27 44/45/27 +f 34/43/33 39/40/33 44/45/33 +f 39/40/34 37/37/34 44/45/34 +f 33/36/31 36/32/31 45/34/31 +f 42/33/32 33/36/32 45/34/32 +o Cup_hull_3 +v -0.012229 0.013316 -0.048198 +v -0.020392 0.007259 0.015036 +v -0.016442 0.007259 0.015036 +v -0.020392 0.013316 0.015036 +v -0.020392 0.007259 -0.048198 +v -0.020392 0.013316 -0.048198 +v -0.012229 0.013316 0.015036 +v -0.016442 0.007259 -0.048198 +v -0.012229 0.013053 0.015036 +v -0.012229 0.013053 -0.048198 +v -0.016179 0.007523 -0.048198 +v -0.016179 0.007523 0.015036 +vt 1.000000 0.516104 +vt 0.000000 1.000000 +vt 0.000000 0.516104 +vt 0.000000 0.000000 +vt 0.000000 0.483896 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 0.483896 +vt 1.000000 1.000000 +vn 0.8137 -0.5813 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0001 1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.7084 -0.7059 0.0000 +vn 0.0001 0.0000 -1.0000 +usemtl None +s off +f 56/46/36 54/47/36 57/48/36 +f 47/49/37 48/50/37 49/51/37 +f 48/50/38 47/49/38 50/52/38 +f 47/49/39 49/51/39 50/52/39 +f 49/51/40 46/53/40 51/54/40 +f 46/53/41 50/52/41 51/54/41 +f 50/52/39 49/51/39 51/54/39 +f 49/51/37 48/50/37 52/55/37 +f 46/53/40 49/51/40 52/55/40 +f 50/52/41 46/53/41 53/56/41 +f 48/50/38 50/52/38 53/56/38 +f 46/53/42 52/55/42 54/47/42 +f 52/55/37 48/50/37 54/47/37 +f 53/56/41 46/53/41 55/57/41 +f 46/53/42 54/47/42 55/57/42 +f 48/50/43 53/56/43 56/46/43 +f 53/56/44 55/57/44 56/46/44 +f 55/57/36 54/47/36 56/46/36 +f 54/47/37 48/50/37 57/48/37 +f 48/50/43 56/46/43 57/48/43 +o Cup_hull_4 +v 0.017003 0.005679 0.015036 +v 0.020427 0.005943 -0.048198 +v 0.020427 -0.000377 -0.048198 +v 0.017003 0.005943 -0.048198 +v 0.020427 0.005943 0.015036 +v 0.018057 -0.000377 0.015036 +v 0.018057 -0.000377 -0.048198 +v 0.020427 -0.000377 0.015036 +v 0.017003 0.005943 0.015036 +v 0.017003 0.005415 -0.048198 +v 0.017003 0.005415 0.014751 +vt 1.000000 0.916504 +vt 0.000000 0.000000 +vt 0.004503 0.916504 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 1.000000 1.000000 +vt 0.000000 1.000000 +vt 0.000000 0.958203 +vt 1.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vn -0.9839 -0.1790 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.0001 0.0000 -1.0000 +vn -0.9730 -0.1693 0.1567 +usemtl None +s off +f 67/58/45 63/59/45 68/60/45 +f 59/61/46 60/62/46 61/63/46 +f 60/62/47 59/61/47 62/64/47 +f 59/61/48 61/63/48 62/64/48 +f 62/64/49 58/65/49 63/59/49 +f 61/63/46 60/62/46 64/66/46 +f 60/62/50 63/59/50 64/66/50 +f 60/62/47 62/64/47 65/67/47 +f 63/59/50 60/62/50 65/67/50 +f 62/64/49 63/59/49 65/67/49 +f 61/63/51 58/65/51 66/68/51 +f 58/65/49 62/64/49 66/68/49 +f 62/64/48 61/63/48 66/68/48 +f 58/65/51 61/63/51 67/58/51 +f 61/63/52 64/66/52 67/58/52 +f 64/66/45 63/59/45 67/58/45 +f 63/59/53 58/65/53 68/60/53 +f 58/65/51 67/58/51 68/60/51 +o Cup_hull_5 +v -0.002748 -0.025132 0.032181 +v -0.013281 -0.021446 0.050166 +v -0.013017 -0.021708 0.050166 +v 0.000413 -0.024341 0.050166 +v -0.012753 -0.018548 0.032181 +v 0.000413 -0.022761 0.032181 +v -0.013017 -0.021708 0.032181 +v -0.006961 -0.024342 0.050166 +v -0.012753 -0.020392 0.050166 +v 0.000413 -0.025132 0.050166 +v -0.009330 -0.023552 0.032181 +v 0.000413 -0.025132 0.032181 +v 0.000413 -0.024078 0.048477 +v -0.002485 -0.025132 0.050166 +v -0.013281 -0.018548 0.033306 +v -0.005909 -0.024605 0.032181 +v -0.009856 -0.023288 0.050166 +v 0.000413 -0.022761 0.033306 +v -0.013281 -0.021446 0.032181 +v -0.004591 -0.024868 0.050166 +v -0.013017 -0.018548 0.033306 +v -0.013281 -0.020392 0.050166 +v -0.006961 -0.024342 0.034992 +v -0.004591 -0.024868 0.032181 +v -0.008540 -0.023814 0.050166 +v -0.012753 -0.018548 0.032462 +vt 1.000000 0.038567 +vt 0.937451 0.019284 +vt 0.984338 0.038567 +vt 0.000000 0.000000 +vt 0.000000 0.019284 +vt 0.000000 1.000000 +vt 1.000000 0.769186 +vt 1.000000 1.000000 +vt 1.000000 0.019284 +vt 0.000000 0.461531 +vt 0.000000 0.038567 +vt 0.000000 1.000000 +vt 1.000000 0.288567 +vt 1.000000 1.000000 +vt 0.093872 1.000000 +vt 0.000000 0.788371 +vt 1.000000 0.538371 +vt 0.000000 0.250098 +vt 0.937451 1.000000 +vt 1.000000 0.000000 +vt 0.937451 0.000000 +vt 0.000000 0.634593 +vt 0.000000 0.000000 +vt 0.843677 0.461531 +vt 1.000000 0.634593 +vt 0.000000 0.346222 +vn 0.0000 1.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn -0.7047 -0.7095 0.0000 +vn 1.0000 0.0000 0.0000 +vn -0.4471 -0.8945 0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.2842 0.9474 0.1475 +vn -0.4470 -0.8945 0.0000 +vn 0.3048 0.9524 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.8931 0.1628 -0.4193 +vn -0.1242 -0.9923 0.0018 +vn -0.2169 -0.9762 0.0016 +vn 0.2801 0.9547 0.1000 +vn 0.0000 0.9941 0.1087 +vn -0.3164 -0.9486 0.0000 +vn -0.2941 -0.9555 -0.0207 +vn -0.2424 -0.9702 0.0000 +vn -0.1416 -0.9899 0.0000 +vn -0.1962 -0.9806 0.0000 +vn -0.3167 -0.9485 0.0000 +vn -0.3714 -0.9285 0.0027 +vn 0.2990 0.9507 0.0825 +vn 0.2898 0.9528 0.0907 +usemtl None +s off +f 73/69/54 89/70/54 94/71/54 +f 70/72/55 71/73/55 72/74/55 +f 69/75/56 73/69/56 74/76/56 +f 71/73/57 70/72/57 75/77/57 +f 73/69/56 69/75/56 75/77/56 +f 72/74/55 71/73/55 76/78/55 +f 70/72/55 72/74/55 77/79/55 +f 74/76/58 72/74/58 78/80/58 +f 72/74/55 76/78/55 78/80/55 +f 75/77/56 69/75/56 79/81/56 +f 71/73/59 75/77/59 79/81/59 +f 69/75/56 74/76/56 80/82/56 +f 78/80/60 69/75/60 80/82/60 +f 74/76/58 78/80/58 80/82/58 +f 72/74/58 74/76/58 81/83/58 +f 77/79/61 72/74/61 81/83/61 +f 69/75/60 78/80/60 82/84/60 +f 78/80/55 76/78/55 82/84/55 +f 79/81/56 69/75/56 84/85/56 +f 76/78/55 71/73/55 85/86/55 +f 71/73/62 79/81/62 85/86/62 +f 74/76/63 73/69/63 86/87/63 +f 81/83/58 74/76/58 86/87/58 +f 75/77/57 70/72/57 87/88/57 +f 73/69/56 75/77/56 87/88/56 +f 70/72/64 83/89/64 87/88/64 +f 83/89/65 73/69/65 87/88/65 +f 69/75/66 82/84/66 88/90/66 +f 82/84/55 76/78/55 88/90/55 +f 76/78/67 84/85/67 88/90/67 +f 77/79/68 81/83/68 89/70/68 +f 73/69/54 83/89/54 89/70/54 +f 83/89/69 77/79/69 89/70/69 +f 70/72/55 77/79/55 90/91/55 +f 83/89/64 70/72/64 90/91/64 +f 77/79/69 83/89/69 90/91/69 +f 76/78/70 79/81/70 91/92/70 +f 79/81/71 84/85/71 91/92/71 +f 84/85/72 76/78/72 91/92/72 +f 84/85/56 69/75/56 92/93/56 +f 69/75/73 88/90/73 92/93/73 +f 88/90/74 84/85/74 92/93/74 +f 79/81/75 76/78/75 93/94/75 +f 76/78/55 85/86/55 93/94/55 +f 85/86/76 79/81/76 93/94/76 +f 86/87/63 73/69/63 94/71/63 +f 81/83/77 86/87/77 94/71/77 +f 89/70/78 81/83/78 94/71/78 +o Cup_hull_6 +v -0.004591 -0.024868 0.018410 +v -0.013281 -0.021443 0.032177 +v -0.013017 -0.021707 0.032177 +v 0.000413 -0.022497 0.031895 +v -0.013017 -0.012229 0.015037 +v 0.000413 -0.018023 0.015037 +v -0.013281 -0.020390 0.015037 +v -0.013281 -0.018286 0.032177 +v 0.000413 -0.025130 0.032177 +v 0.000413 -0.024868 0.017286 +v -0.005909 -0.024605 0.032177 +v -0.009330 -0.023550 0.018410 +v -0.013017 -0.012756 0.017286 +v 0.000413 -0.020654 0.015037 +v 0.000413 -0.018548 0.018130 +v -0.013017 -0.021707 0.018130 +v -0.013281 -0.012229 0.015037 +v -0.009330 -0.023550 0.032177 +v -0.001695 -0.024341 0.016724 +v -0.002485 -0.025130 0.018410 +v -0.002485 -0.025130 0.032177 +v -0.005382 -0.024341 0.017286 +v -0.013017 -0.018286 0.032177 +v 0.000413 -0.025130 0.017848 +v -0.007751 -0.024077 0.018130 +v 0.000413 -0.022761 0.032177 +v 0.000413 -0.018023 0.015881 +v -0.013017 -0.012493 0.016444 +v -0.008804 -0.020654 0.015037 +v -0.013281 -0.021443 0.017848 +v -0.009068 -0.023288 0.017286 +v -0.005909 -0.024605 0.018410 +v -0.004591 -0.024868 0.032177 +v -0.002485 -0.024604 0.017006 +v -0.010910 -0.022761 0.017848 +v 0.000413 -0.024341 0.016724 +v -0.007751 -0.024077 0.032177 +vt 0.000000 0.288567 +vt 0.819561 0.403876 +vt 0.000000 0.403876 +vt 1.000000 0.019284 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.019284 +vt 0.016448 1.000000 +vt 0.000000 1.000000 +vt 0.868807 1.000000 +vt 0.000000 0.538371 +vt 1.000000 1.000000 +vt 0.819561 1.000000 +vt 0.819561 0.019284 +vt 1.000000 0.000000 +vt 0.868807 0.019284 +vt 0.000000 0.788371 +vt 0.803211 0.788371 +vt 0.803211 0.634593 +vt 0.000000 0.019284 +vt 0.836009 1.000000 +vt 0.803211 0.288567 +vt 0.000000 1.000000 +vt 0.950754 1.000000 +vt 0.917956 0.019284 +vt 1.000000 0.326938 +vt 0.901606 0.846124 +vt 0.836009 0.000000 +vt 0.868807 0.576840 +vt 0.868807 0.307655 +vt 0.803211 0.538371 +vt 0.000000 0.634593 +vt 0.885158 0.788371 +vt 0.836009 0.173160 +vt 0.901606 1.000000 +vn -0.3164 -0.9486 0.0000 +vn 0.0000 0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 1.0000 -0.0000 0.0000 +vn -0.7070 -0.7072 0.0000 +vn -0.6912 0.6814 0.2408 +vn 0.0000 -1.0000 0.0000 +vn -0.1238 -0.9923 0.0000 +vn 0.2885 0.8976 0.3333 +vn 0.0000 0.9375 0.3481 +vn 0.2363 0.7093 0.6641 +vn 0.3961 0.9182 0.0000 +vn 0.3797 0.9008 0.2105 +vn 0.3458 0.8958 0.2794 +vn 0.3704 0.8929 0.2561 +vn 0.0000 0.9828 0.1845 +vn -0.5337 0.8073 0.2518 +vn 0.3813 0.9086 0.1706 +vn -0.0270 -0.4585 -0.8883 +vn 0.0000 -0.4160 -0.9094 +vn -0.4896 -0.8165 -0.3060 +vn -0.2225 -0.7788 -0.5865 +vn -0.2486 -0.8701 -0.4256 +vn -0.1955 -0.9807 0.0000 +vn -0.1861 -0.9335 -0.3064 +vn -0.2756 -0.9613 0.0000 +vn -0.2162 -0.9231 -0.3180 +vn -0.0868 -0.5956 -0.7986 +vn -0.0006 -0.7308 -0.6826 +vn -0.1160 -0.9300 -0.3487 +vn -0.1183 -0.9286 -0.3518 +vn -0.1315 -0.6757 -0.7254 +vn -0.0415 -0.9052 -0.4230 +vn -0.0680 -0.9342 -0.3503 +vn -0.4472 -0.8945 0.0000 +vn -0.4578 -0.8314 -0.3151 +vn -0.4470 -0.8945 0.0000 +vn -0.4469 -0.8946 0.0000 +vn -0.3480 -0.8951 -0.2786 +vn -0.3632 -0.8403 -0.4024 +vn -0.3449 -0.8911 -0.2950 +vn 0.0000 -0.7297 -0.6837 +usemtl None +s off +f 112/95/79 119/96/79 131/97/79 +f 99/98/80 100/99/80 101/100/80 +f 101/100/81 96/101/81 102/102/81 +f 96/101/82 97/103/82 102/102/82 +f 100/99/83 98/104/83 103/105/83 +f 102/102/82 97/103/82 103/105/82 +f 100/99/83 103/105/83 104/106/83 +f 103/105/82 97/103/82 105/107/82 +f 101/100/80 100/99/80 108/108/80 +f 100/99/83 104/106/83 108/108/83 +f 98/104/83 100/99/83 109/109/83 +f 97/103/84 96/101/84 110/110/84 +f 99/98/80 101/100/80 111/111/80 +f 101/100/81 102/102/81 111/111/81 +f 102/102/85 107/112/85 111/111/85 +f 105/107/82 97/103/82 112/95/82 +f 103/105/82 105/107/82 115/113/82 +f 114/114/86 103/105/86 115/113/86 +f 95/115/87 114/114/87 115/113/87 +f 102/102/82 103/105/82 117/116/82 +f 98/104/88 107/112/88 117/116/88 +f 107/112/89 102/102/89 117/116/89 +f 104/106/83 103/105/83 118/117/83 +f 103/105/86 114/114/86 118/117/86 +f 112/95/79 106/118/79 119/96/79 +f 103/105/83 98/104/83 120/119/83 +f 98/104/90 117/116/90 120/119/90 +f 117/116/82 103/105/82 120/119/82 +f 100/99/91 99/98/91 121/120/91 +f 109/109/83 100/99/83 121/120/83 +f 109/109/92 121/120/92 122/121/92 +f 107/112/93 98/104/93 122/121/93 +f 98/104/94 109/109/94 122/121/94 +f 99/98/95 111/111/95 122/121/95 +f 111/111/96 107/112/96 122/121/96 +f 121/120/97 99/98/97 122/121/97 +f 101/100/80 108/108/80 123/122/80 +f 113/123/98 101/100/98 123/122/98 +f 108/108/99 113/123/99 123/122/99 +f 96/101/81 101/100/81 124/124/81 +f 110/110/84 96/101/84 124/124/84 +f 101/100/100 110/110/100 124/124/100 +f 101/100/101 116/125/101 125/126/101 +f 116/125/102 119/96/102 125/126/102 +f 95/115/103 105/107/103 126/127/103 +f 116/125/104 95/115/104 126/127/104 +f 105/107/105 119/96/105 126/127/105 +f 119/96/106 116/125/106 126/127/106 +f 105/107/103 95/115/103 127/128/103 +f 95/115/87 115/113/87 127/128/87 +f 115/113/82 105/107/82 127/128/82 +f 101/100/107 113/123/107 128/129/107 +f 113/123/108 104/106/108 128/129/108 +f 114/114/109 95/115/109 128/129/109 +f 95/115/110 116/125/110 128/129/110 +f 116/125/111 101/100/111 128/129/111 +f 104/106/112 118/117/112 128/129/112 +f 118/117/113 114/114/113 128/129/113 +f 97/103/114 110/110/114 129/130/114 +f 110/110/115 101/100/115 129/130/115 +f 112/95/116 97/103/116 129/130/116 +f 106/118/117 112/95/117 129/130/117 +f 119/96/118 106/118/118 129/130/118 +f 101/100/119 125/126/119 129/130/119 +f 125/126/120 119/96/120 129/130/120 +f 108/108/83 104/106/83 130/131/83 +f 104/106/121 113/123/121 130/131/121 +f 113/123/99 108/108/99 130/131/99 +f 105/107/82 112/95/82 131/97/82 +f 119/96/105 105/107/105 131/97/105 +o Cup_hull_7 +v -0.006700 0.024377 0.032460 +v -0.014335 0.019637 0.050164 +v -0.013806 0.019637 0.050164 +v -0.014335 0.017795 0.032460 +v 0.000413 0.024113 0.050164 +v 0.000413 0.022797 0.032460 +v -0.006700 0.024377 0.050164 +v -0.013806 0.021217 0.032460 +v 0.000413 0.025167 0.032460 +v -0.013017 0.021742 0.050164 +v -0.002222 0.025167 0.050164 +v -0.014070 0.017795 0.033306 +v -0.009855 0.023323 0.032460 +v 0.000413 0.025167 0.050164 +v -0.004328 0.024903 0.032460 +v -0.014335 0.020691 0.032460 +v -0.009855 0.023323 0.050164 +v -0.014335 0.020691 0.050164 +v 0.000413 0.022797 0.033586 +v -0.002222 0.025167 0.032460 +v -0.004328 0.024903 0.050164 +v -0.013017 0.021742 0.032460 +v -0.013806 0.021217 0.050164 +v -0.005646 0.024639 0.050164 +vt 0.000000 0.678543 +vt 1.000000 0.678543 +vt 0.000000 0.589174 +vt 0.000000 0.000000 +vt 0.000000 0.035826 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 1.000000 0.517717 +vt 1.000000 1.000000 +vt 0.000000 0.517717 +vt 1.000000 0.035826 +vt 1.000000 1.000000 +vt 0.000000 0.089370 +vt 0.000000 0.821359 +vt 0.952232 0.017913 +vt 1.000000 0.303739 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.303739 +vt 0.000000 0.000000 +vt 0.936374 1.000000 +vt 1.000000 0.821359 +vt 1.000000 0.089370 +vt 0.000000 0.035826 +vn -0.1960 0.9806 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 -0.9941 0.1086 +vn -0.3146 -0.9441 0.0983 +vn 0.2988 -0.9492 0.0991 +vn 0.3196 -0.9423 -0.0998 +vn -0.3167 0.9485 0.0000 +vn 0.0000 1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.4472 0.8944 0.0000 +vn -0.7056 0.7086 0.0000 +vn 0.3242 -0.9430 0.0749 +vn 0.3265 -0.9452 0.0000 +vn -0.1244 0.9922 0.0000 +vn -0.5540 0.8325 0.0000 +vn -0.2419 0.9703 0.0000 +vn -0.2166 0.9763 -0.0016 +usemtl None +s off +f 152/132/122 146/133/122 155/134/122 +f 133/135/123 134/136/123 136/137/123 +f 135/138/124 132/139/124 137/140/124 +f 133/135/123 136/137/123 138/141/123 +f 132/139/124 135/138/124 139/142/124 +f 137/140/124 132/139/124 140/143/124 +f 136/137/125 137/140/125 140/143/125 +f 133/135/123 138/141/123 141/144/123 +f 138/141/123 136/137/123 142/145/123 +f 134/136/126 133/135/126 143/146/126 +f 133/135/127 135/138/127 143/146/127 +f 136/137/128 134/136/128 143/146/128 +f 135/138/129 137/140/129 143/146/129 +f 138/141/130 132/139/130 144/147/130 +f 132/139/124 139/142/124 144/147/124 +f 136/137/125 140/143/125 145/148/125 +f 142/145/123 136/137/123 145/148/123 +f 140/143/131 142/145/131 145/148/131 +f 140/143/124 132/139/124 146/133/124 +f 135/138/132 133/135/132 147/149/132 +f 139/142/124 135/138/124 147/149/124 +f 141/144/123 138/141/123 148/150/123 +f 138/141/130 144/147/130 148/150/130 +f 144/147/133 141/144/133 148/150/133 +f 133/135/123 141/144/123 149/151/123 +f 147/149/132 133/135/132 149/151/132 +f 139/142/134 147/149/134 149/151/134 +f 137/140/125 136/137/125 150/152/125 +f 136/137/135 143/146/135 150/152/135 +f 143/146/136 137/140/136 150/152/136 +f 142/145/131 140/143/131 151/153/131 +f 140/143/124 146/133/124 151/153/124 +f 146/133/137 142/145/137 151/153/137 +f 138/141/123 142/145/123 152/132/123 +f 142/145/137 146/133/137 152/132/137 +f 139/142/138 141/144/138 153/154/138 +f 144/147/124 139/142/124 153/154/124 +f 141/144/133 144/147/133 153/154/133 +f 141/144/138 139/142/138 154/155/138 +f 149/151/123 141/144/123 154/155/123 +f 139/142/134 149/151/134 154/155/134 +f 132/139/139 138/141/139 155/134/139 +f 146/133/140 132/139/140 155/134/140 +f 138/141/123 152/132/123 155/134/123 +o Cup_hull_8 +v -0.003801 0.024902 0.017846 +v -0.014335 0.017794 0.032458 +v -0.014335 0.020688 0.032458 +v 0.000413 0.022796 0.032458 +v -0.014070 0.011212 0.015036 +v 0.000413 0.018057 0.015036 +v -0.014335 0.020426 0.015036 +v 0.000413 0.025166 0.032458 +v 0.000413 0.024376 0.016722 +v -0.009858 0.023322 0.032458 +v -0.014070 0.011475 0.017004 +v -0.009858 0.023322 0.018409 +v -0.005645 0.024639 0.032458 +v 0.000413 0.018320 0.017285 +v 0.000413 0.022532 0.032179 +v 0.000413 0.020426 0.015036 +v -0.014070 0.017531 0.032179 +v -0.013017 0.021741 0.018409 +v 0.000413 0.025166 0.017846 +v -0.014335 0.011212 0.016161 +v -0.002222 0.025166 0.032458 +v -0.006698 0.024376 0.018128 +v -0.013017 0.021741 0.032458 +v -0.014070 0.011212 0.016161 +v -0.005645 0.024111 0.017004 +v -0.002222 0.025166 0.018409 +v -0.004328 0.024902 0.018409 +v -0.013806 0.021215 0.018128 +v -0.001958 0.024639 0.017004 +v -0.006698 0.024376 0.032458 +v 0.000413 0.018057 0.015880 +v -0.004328 0.024902 0.032458 +v -0.014335 0.011212 0.015036 +v -0.014335 0.020688 0.017285 +v -0.013806 0.021215 0.032458 +v -0.009330 0.023322 0.017565 +vt 0.822516 0.517815 +vt 0.887029 0.589272 +vt 0.854821 0.339370 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.017913 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 0.903182 1.000000 +vt 0.000000 0.303543 +vt 0.000000 0.589272 +vt 0.870876 1.000000 +vt 0.016055 1.000000 +vt 1.000000 1.000000 +vt 0.016055 0.017913 +vt 0.887029 0.017913 +vt 0.806363 0.303543 +vt 0.806363 0.089370 +vt 0.838669 1.000000 +vt 0.935389 0.000000 +vt 0.000000 0.821359 +vt 0.000000 0.089370 +vt 0.935389 0.017913 +vt 0.838669 0.714272 +vt 0.806363 0.821359 +vt 0.806363 0.678543 +vt 0.822516 0.035826 +vt 0.887029 0.839272 +vt 0.000000 0.517815 +vt 0.951542 1.000000 +vt 0.000000 0.678543 +vt 1.000000 0.000000 +vt 0.870876 0.000000 +vt 0.000000 0.035826 +vn -0.2516 0.8624 -0.4393 +vn 0.0000 0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 0.3927 -0.9197 +vn 0.2065 -0.6089 0.7659 +vn 0.3054 -0.8844 0.3530 +vn 0.2437 -0.7058 0.6652 +vn -0.4409 0.8811 -0.1713 +vn -0.4475 0.8943 0.0000 +vn -0.4642 -0.8213 0.3317 +vn -0.2519 -0.8988 0.3587 +vn 0.0000 1.0000 0.0000 +vn -0.3166 0.9486 0.0000 +vn 0.4273 -0.9041 0.0000 +vn 0.3853 -0.8811 0.2743 +vn 0.4112 -0.8771 0.2481 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 -0.9548 0.2972 +vn -0.2012 0.8944 -0.3995 +vn -0.0599 0.9580 -0.2805 +vn -0.1242 0.9923 0.0000 +vn -0.1926 0.9646 -0.1803 +vn -0.2164 0.9763 -0.0020 +vn -0.1234 0.9856 -0.1155 +vn -0.5179 0.8459 -0.1275 +vn -0.5543 0.8323 0.0000 +vn -0.0430 0.5239 -0.8507 +vn -0.0570 0.9105 -0.4095 +vn 0.0223 0.8181 -0.5747 +vn -0.0894 0.6249 -0.7755 +vn -0.1204 0.8415 -0.5266 +vn -0.2415 0.9704 0.0000 +vn 0.4240 -0.8903 0.1661 +vn -0.1964 0.9805 0.0000 +vn -0.7064 0.7078 0.0000 +vn -0.6278 0.7731 -0.0901 +vn -0.3902 0.8877 -0.2442 +vn -0.3262 0.9230 -0.2041 +vn -0.2527 0.8463 -0.4689 +usemtl None +s off +f 177/156/141 180/157/141 191/158/141 +f 158/159/142 157/160/142 159/161/142 +f 161/162/143 160/163/143 162/164/143 +f 157/160/144 158/159/144 162/164/144 +f 158/159/142 159/161/142 163/165/142 +f 159/161/145 161/162/145 163/165/145 +f 163/165/145 161/162/145 164/166/145 +f 158/159/142 163/165/142 165/167/142 +f 165/167/142 163/165/142 168/168/142 +f 161/162/145 159/161/145 169/169/145 +f 169/169/145 159/161/145 170/170/145 +f 161/162/143 162/164/143 171/171/143 +f 164/166/145 161/162/145 171/171/145 +f 162/164/146 164/166/146 171/171/146 +f 159/161/147 157/160/147 172/172/147 +f 166/173/148 170/170/148 172/172/148 +f 170/170/149 159/161/149 172/172/149 +f 167/174/150 162/164/150 173/175/150 +f 165/167/151 167/174/151 173/175/151 +f 163/165/145 164/166/145 174/176/145 +f 157/160/144 162/164/144 175/177/144 +f 172/172/152 157/160/152 175/177/152 +f 166/173/153 172/172/153 175/177/153 +f 168/168/142 163/165/142 176/178/142 +f 163/165/154 174/176/154 176/178/154 +f 167/174/155 165/167/155 177/156/155 +f 158/159/142 165/167/142 178/179/142 +f 165/167/151 173/175/151 178/179/151 +f 160/163/156 161/162/156 179/180/156 +f 170/170/157 166/173/157 179/180/157 +f 169/169/158 170/170/158 179/180/158 +f 175/177/159 160/163/159 179/180/159 +f 166/173/160 175/177/160 179/180/160 +f 177/156/161 156/181/161 180/157/161 +f 174/176/162 156/181/162 181/182/162 +f 176/178/154 174/176/154 181/182/154 +f 176/178/163 181/182/163 182/183/163 +f 156/181/164 177/156/164 182/183/164 +f 177/156/165 168/168/165 182/183/165 +f 181/182/166 156/181/166 182/183/166 +f 173/175/167 162/164/167 183/184/167 +f 178/179/168 173/175/168 183/184/168 +f 164/166/169 162/164/169 184/185/169 +f 156/181/170 174/176/170 184/185/170 +f 174/176/171 164/166/171 184/185/171 +f 162/164/172 180/157/172 184/185/172 +f 180/157/173 156/181/173 184/185/173 +f 165/167/142 168/168/142 185/186/142 +f 177/156/155 165/167/155 185/186/155 +f 168/168/174 177/156/174 185/186/174 +f 161/162/145 169/169/145 186/187/145 +f 179/180/156 161/162/156 186/187/156 +f 169/169/175 179/180/175 186/187/175 +f 168/168/142 176/178/142 187/188/142 +f 176/178/163 182/183/163 187/188/163 +f 182/183/176 168/168/176 187/188/176 +f 162/164/143 160/163/143 188/189/143 +f 160/163/159 175/177/159 188/189/159 +f 175/177/144 162/164/144 188/189/144 +f 162/164/144 158/159/144 189/190/144 +f 158/159/177 183/184/177 189/190/177 +f 183/184/178 162/164/178 189/190/178 +f 158/159/142 178/179/142 190/191/142 +f 183/184/177 158/159/177 190/191/177 +f 178/179/168 183/184/168 190/191/168 +f 162/164/179 167/174/179 191/158/179 +f 167/174/180 177/156/180 191/158/180 +f 180/157/181 162/164/181 191/158/181 +o Cup_hull_9 +v 0.004625 -0.024868 0.026844 +v 0.008313 -0.016178 0.015036 +v 0.007785 -0.016178 0.015036 +v 0.008313 -0.022761 0.050166 +v 0.000413 -0.024077 0.049041 +v 0.000413 -0.018023 0.015036 +v 0.008313 -0.023814 0.017848 +v 0.000413 -0.025132 0.017848 +v 0.004363 -0.024868 0.050166 +v 0.008313 -0.020655 0.015036 +v 0.007785 -0.024077 0.050166 +v 0.000413 -0.025132 0.050166 +v 0.008049 -0.016178 0.016442 +v 0.000413 -0.020655 0.015036 +v 0.000676 -0.024077 0.049884 +v 0.002520 -0.025132 0.018409 +v 0.000413 -0.018023 0.015882 +v 0.001730 -0.024341 0.016724 +v 0.005942 -0.024604 0.018409 +v 0.007785 -0.022761 0.050166 +v 0.002520 -0.025132 0.050166 +v 0.008313 -0.023814 0.050166 +v 0.005679 -0.024077 0.017006 +v 0.004625 -0.024868 0.048477 +v 0.007785 -0.024077 0.018409 +v 0.000413 -0.024341 0.016724 +v 0.008313 -0.023287 0.017006 +v 0.003309 -0.024868 0.017567 +v 0.000940 -0.024077 0.050166 +v 0.008313 -0.016178 0.016442 +vt 0.959965 1.000000 +vt 0.000000 0.264781 +vt 0.959965 1.000000 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.793951 +vt 0.919930 0.147220 +vt 0.032009 0.117756 +vt 0.919930 0.000000 +vt 1.000000 0.500000 +vt 0.000000 0.029464 +vt 0.000000 0.117756 +vt 0.000000 0.000000 +vt 1.000000 0.500000 +vt 0.008027 0.117756 +vt 0.903974 0.000000 +vt 0.975920 0.793951 +vt 0.951938 0.088293 +vt 0.663861 0.029464 +vt 0.903974 0.058927 +vt 0.000000 0.264781 +vt 0.000000 0.000000 +vt 0.000000 0.147220 +vt 0.943911 0.117756 +vt 0.048062 0.029464 +vt 0.903974 0.117756 +vt 0.951938 0.088293 +vt 0.943911 0.206049 +vt 0.927956 0.029464 +vt 0.000000 0.117756 +vn 0.0000 0.9815 0.1916 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn -1.0000 -0.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 1.0000 0.0000 +vn -0.9093 0.3035 0.2846 +vn 0.0000 -1.0000 0.0000 +vn -0.2427 0.9701 0.0000 +vn -0.2377 0.9703 0.0446 +vn -0.4977 0.8532 0.1558 +vn -0.2432 0.9546 0.1719 +vn 0.0000 -0.4164 -0.9092 +vn 0.1524 -0.9883 -0.0071 +vn 0.1244 -0.9922 0.0000 +vn 0.4474 -0.8944 0.0000 +vn 0.0960 -0.5511 -0.8289 +vn 0.2249 -0.9738 0.0349 +vn 0.1964 -0.9805 0.0000 +vn 0.2416 -0.9704 0.0021 +vn 0.1417 -0.9897 0.0220 +vn 0.2697 -0.9439 -0.1905 +vn 0.2747 -0.9615 0.0000 +vn 0.0000 -0.8181 -0.5751 +vn 0.2466 -0.8217 -0.5138 +vn 0.1770 -0.5898 -0.7879 +vn 0.0645 -0.9680 -0.2426 +vn 0.0212 -0.8294 -0.5583 +vn 0.1503 -0.9749 -0.1644 +vn 0.2113 -0.9015 -0.3778 +vn 0.2112 -0.9013 -0.3782 +vn 0.0968 -0.7522 -0.6518 +vn -0.6860 0.3432 0.6416 +vn -0.1968 0.9630 0.1841 +vn -0.1855 0.9647 0.1869 +usemtl None +s off +f 204/192/182 195/193/182 221/194/182 +f 194/195/183 193/196/183 197/197/183 +f 193/196/184 195/193/184 198/198/184 +f 196/199/185 197/197/185 199/200/185 +f 197/197/183 193/196/183 201/201/183 +f 193/196/184 198/198/184 201/201/184 +f 195/193/186 200/202/186 202/203/186 +f 196/199/185 199/200/185 203/204/185 +f 200/202/186 195/193/186 203/204/186 +f 193/196/187 194/195/187 204/192/187 +f 199/200/185 197/197/185 205/205/185 +f 197/197/183 201/201/183 205/205/183 +f 196/199/188 203/204/188 206/206/188 +f 203/204/189 199/200/189 207/207/189 +f 194/195/190 197/197/190 208/208/190 +f 197/197/185 196/199/185 208/208/185 +f 204/192/191 194/195/191 208/208/191 +f 196/199/192 206/206/192 208/208/192 +f 206/206/193 204/192/193 208/208/193 +f 205/205/194 201/201/194 209/209/194 +f 192/210/195 207/207/195 210/211/195 +f 203/204/186 195/193/186 211/212/186 +f 195/193/182 204/192/182 211/212/182 +f 200/202/186 203/204/186 212/213/186 +f 207/207/196 192/210/196 212/213/196 +f 203/204/189 207/207/189 212/213/189 +f 198/198/184 195/193/184 213/214/184 +f 202/203/197 198/198/197 213/214/197 +f 195/193/186 202/203/186 213/214/186 +f 209/209/198 201/201/198 214/215/198 +f 202/203/199 200/202/199 215/216/199 +f 192/210/200 210/211/200 215/216/200 +f 210/211/201 202/203/201 215/216/201 +f 212/213/196 192/210/196 215/216/196 +f 200/202/202 212/213/202 215/216/202 +f 198/198/197 202/203/197 216/217/197 +f 210/211/203 198/198/203 216/217/203 +f 202/203/204 210/211/204 216/217/204 +f 199/200/185 205/205/185 217/218/185 +f 209/209/205 199/200/205 217/218/205 +f 205/205/194 209/209/194 217/218/194 +f 201/201/184 198/198/184 218/219/184 +f 198/198/206 214/215/206 218/219/206 +f 214/215/207 201/201/207 218/219/207 +f 207/207/208 199/200/208 219/220/208 +f 199/200/209 209/209/209 219/220/209 +f 210/211/210 207/207/210 219/220/210 +f 198/198/211 210/211/211 219/220/211 +f 214/215/212 198/198/212 219/220/212 +f 209/209/213 214/215/213 219/220/213 +f 206/206/214 203/204/214 220/221/214 +f 204/192/215 206/206/215 220/221/215 +f 203/204/186 211/212/186 220/221/186 +f 211/212/216 204/192/216 220/221/216 +f 195/193/184 193/196/184 221/194/184 +f 193/196/187 204/192/187 221/194/187 +o Cup_hull_10 +v 0.021743 -0.013016 0.050164 +v 0.025167 -0.000378 0.032460 +v 0.025167 -0.002222 0.032460 +v 0.017793 -0.014070 0.032460 +v 0.024113 -0.000379 0.050164 +v 0.021743 -0.013016 0.032460 +v 0.022796 -0.000379 0.032460 +v 0.019637 -0.014335 0.050164 +v 0.024640 -0.005645 0.050164 +v 0.024113 -0.007750 0.032460 +v 0.025167 -0.000378 0.050164 +v 0.020691 -0.014335 0.032460 +v 0.023323 -0.009856 0.050164 +v 0.019637 -0.013806 0.050164 +v 0.017793 -0.014070 0.033306 +v 0.020691 -0.014335 0.050164 +v 0.022796 -0.000379 0.033586 +v 0.025167 -0.002222 0.050164 +v 0.024903 -0.004328 0.032460 +v 0.023323 -0.009856 0.032460 +v 0.017793 -0.014335 0.032460 +v 0.024113 -0.007750 0.050164 +v 0.021217 -0.013806 0.032460 +v 0.024903 -0.004328 0.050164 +v 0.024640 -0.005645 0.032460 +v 0.021217 -0.013806 0.050164 +vt 0.000000 0.000000 +vt 1.000000 0.037882 +vt 0.000000 0.037882 +vt 1.000000 1.000000 +vt 1.000000 0.867854 +vt 1.000000 0.018990 +vt 1.000000 0.094460 +vt 1.000000 0.999902 +vt 0.000000 0.094460 +vt 0.000000 0.999902 +vt 0.000000 0.000000 +vt 0.000000 0.622651 +vt 1.000000 0.471809 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.320869 +vt 0.000000 0.037882 +vt 0.952232 0.018990 +vt 0.936374 0.999902 +vt 0.000000 0.867854 +vt 1.000000 0.717012 +vt 1.000000 0.320869 +vt 1.000000 0.000000 +vt 0.000000 0.471809 +vt 0.000000 0.717012 +vt 1.000000 0.622651 +vn 0.7093 -0.7049 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 0.0000 1.0000 +vn 1.0000 0.0000 0.0000 +vn -0.0006 1.0000 0.0000 +vn 0.8944 -0.4472 0.0000 +vn -0.9941 0.0000 0.1087 +vn -0.9392 0.3433 0.0000 +vn -0.9441 0.3147 0.0984 +vn 0.0000 -1.0000 0.0000 +vn -0.0013 1.0000 0.0001 +vn -0.9371 0.3410 0.0744 +vn 0.9923 -0.1242 0.0000 +vn 0.9363 -0.3513 0.0000 +vn -0.9444 -0.3139 0.0984 +vn -1.0000 0.0000 0.0000 +vn 0.9701 -0.2428 0.0000 +vn 0.8322 -0.5545 0.0000 +vn 0.9806 -0.1962 0.0000 +usemtl None +s off +f 237/222/217 244/223/217 247/224/217 +f 223/225/218 224/226/218 225/227/218 +f 225/227/218 224/226/218 227/228/218 +f 223/225/218 225/227/218 228/229/218 +f 222/230/219 226/231/219 229/232/219 +f 226/231/219 222/230/219 230/233/219 +f 227/228/218 224/226/218 231/234/218 +f 224/226/220 223/225/220 232/235/220 +f 223/225/221 228/229/221 232/235/221 +f 226/231/219 230/233/219 232/235/219 +f 225/227/218 227/228/218 233/236/218 +f 222/230/222 227/228/222 234/237/222 +f 230/233/219 222/230/219 234/237/219 +f 229/232/219 226/231/219 235/238/219 +f 229/232/223 235/238/223 236/239/223 +f 228/229/224 225/227/224 236/239/224 +f 235/238/225 226/231/225 236/239/225 +f 222/230/219 229/232/219 237/222/219 +f 229/232/226 233/236/226 237/222/226 +f 232/235/221 228/229/221 238/240/221 +f 226/231/227 232/235/227 238/240/227 +f 228/229/224 236/239/224 238/240/224 +f 236/239/228 226/231/228 238/240/228 +f 224/226/220 232/235/220 239/241/220 +f 232/235/219 230/233/219 239/241/219 +f 231/234/218 224/226/218 240/242/218 +f 224/226/229 239/241/229 240/242/229 +f 227/228/218 231/234/218 241/243/218 +f 234/237/222 227/228/222 241/243/222 +f 231/234/230 234/237/230 241/243/230 +f 225/227/218 233/236/218 242/244/218 +f 233/236/226 229/232/226 242/244/226 +f 229/232/231 236/239/231 242/244/231 +f 236/239/232 225/227/232 242/244/232 +f 231/234/233 230/233/233 243/245/233 +f 230/233/219 234/237/219 243/245/219 +f 234/237/230 231/234/230 243/245/230 +f 227/228/234 222/230/234 244/223/234 +f 233/236/218 227/228/218 244/223/218 +f 237/222/217 233/236/217 244/223/217 +f 239/241/219 230/233/219 245/246/219 +f 230/233/235 240/242/235 245/246/235 +f 240/242/229 239/241/229 245/246/229 +f 230/233/233 231/234/233 246/247/233 +f 231/234/218 240/242/218 246/247/218 +f 240/242/235 230/233/235 246/247/235 +f 222/230/219 237/222/219 247/224/219 +f 244/223/234 222/230/234 247/224/234 +o Cup_hull_11 +v 0.024903 -0.004329 0.032460 +v 0.021479 -0.000377 0.016161 +v 0.020426 -0.000379 0.015036 +v 0.020426 -0.014335 0.015036 +v 0.011211 -0.014335 0.016161 +v 0.017530 -0.014071 0.032177 +v 0.022533 -0.000377 0.032177 +v 0.025166 -0.000377 0.017846 +v 0.020690 -0.014335 0.032458 +v 0.018056 -0.000379 0.015036 +v 0.023322 -0.009856 0.018411 +v 0.025166 -0.000377 0.032460 +v 0.011211 -0.014335 0.015036 +v 0.023322 -0.009856 0.032460 +v 0.024375 -0.006699 0.018128 +v 0.018318 -0.000379 0.017285 +v 0.011474 -0.014071 0.017004 +v 0.021743 -0.013016 0.018411 +v 0.024375 -0.000905 0.016724 +v 0.017794 -0.014335 0.032458 +v 0.025166 -0.002222 0.018411 +v 0.024112 -0.007750 0.032460 +v 0.021743 -0.013016 0.032460 +v 0.024375 -0.004329 0.017004 +v 0.011211 -0.014071 0.016161 +v 0.022796 -0.000377 0.032460 +v 0.021216 -0.013807 0.018130 +v 0.024903 -0.004329 0.018411 +v 0.025166 -0.002222 0.032460 +v 0.023586 -0.008277 0.017285 +v 0.018056 -0.000379 0.015880 +v 0.024639 -0.005646 0.032460 +v 0.020690 -0.014335 0.017285 +v 0.011211 -0.014071 0.015036 +v 0.021216 -0.013807 0.032458 +vt 0.822435 0.037784 +vt 0.000000 0.094460 +vt 0.000098 0.037784 +vt 1.000000 0.999902 +vt 0.935395 1.000000 +vt 0.838684 1.000000 +vt 0.016249 1.000000 +vt 0.935395 0.000000 +vt 1.000000 0.000000 +vt 0.000098 0.000000 +vt 1.000000 0.999902 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.716915 +vt 0.000000 0.320869 +vt 0.016249 0.018892 +vt 0.887040 0.018892 +vt 0.806284 0.320869 +vt 0.806284 0.094460 +vt 0.903093 0.962216 +vt 0.000098 0.000000 +vt 0.806284 0.867854 +vt 0.000000 0.471809 +vt 0.822533 0.547083 +vt 0.887040 0.716915 +vt 0.935395 0.018892 +vt 0.870889 0.999902 +vt 0.000000 1.000000 +vt 0.806284 0.716915 +vt 0.000000 0.867854 +vt 0.870889 0.434025 +vt 0.951547 0.999902 +vt 0.000000 0.622553 +vt 0.870889 0.000000 +vt 1.000000 0.018892 +vn 0.8321 -0.5547 0.0000 +vn 0.0010 1.0000 -0.0021 +vn 0.0000 1.0000 -0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 1.0000 -0.0012 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 0.0000 1.0000 +vn -0.8998 -0.2478 0.3591 +vn -0.8795 0.3213 0.3510 +vn 0.8812 -0.4404 -0.1718 +vn 0.8945 -0.4470 0.0000 +vn 0.3931 0.0000 -0.9195 +vn 0.3488 0.7294 -0.5885 +vn -0.8201 -0.4665 0.3313 +vn 1.0000 0.0000 0.0000 +vn 0.9364 -0.3510 0.0000 +vn 0.9484 -0.3169 -0.0058 +vn 0.0000 -0.0013 1.0000 +vn 0.5751 -0.0666 -0.8153 +vn 0.8266 -0.0458 -0.5610 +vn 0.9275 -0.1094 -0.3575 +vn -1.0000 0.0000 0.0000 +vn -0.8684 0.4306 0.2457 +vn -0.9544 0.0000 0.2986 +vn -0.8736 0.4026 0.2734 +vn -0.7070 0.2583 0.6584 +vn -0.6033 0.2161 0.7677 +vn -0.0004 0.0000 1.0000 +vn 0.8456 -0.5183 -0.1275 +vn 0.9923 -0.1242 0.0000 +vn 0.9237 -0.1641 -0.3461 +vn 0.9300 -0.1164 -0.3485 +vn 0.8884 -0.3554 -0.2906 +vn 0.9131 -0.3265 -0.2442 +vn 0.7927 -0.1996 -0.5760 +vn 0.8765 -0.2063 -0.4350 +vn -0.0004 1.0000 0.0000 +vn -0.0010 1.0000 0.0002 +vn -0.8944 0.4472 0.0000 +vn -0.8809 0.4438 0.1644 +vn 0.9700 -0.2431 0.0000 +vn 0.9805 -0.1963 0.0000 +vn 0.9762 -0.2169 -0.0020 +vn 0.7740 -0.6267 -0.0907 +vn 0.7081 -0.7062 0.0000 +vn 0.0065 -0.0065 1.0000 +usemtl None +s off +f 274/248/236 270/249/236 282/250/236 +f 250/251/237 249/252/237 255/253/237 +f 249/252/238 254/254/238 255/253/238 +f 252/255/239 251/256/239 256/257/239 +f 249/252/240 250/251/240 257/258/240 +f 250/251/241 251/256/241 257/258/241 +f 255/253/238 254/254/238 259/259/238 +f 251/256/239 252/255/239 260/260/239 +f 257/258/241 251/256/241 260/260/241 +f 248/261/242 259/259/242 261/262/242 +f 252/255/243 253/263/243 264/264/243 +f 253/263/244 254/254/244 264/264/244 +f 251/256/245 258/265/245 265/266/245 +f 258/265/246 261/262/246 265/266/246 +f 251/256/247 250/251/247 266/267/247 +f 250/251/248 255/253/248 266/267/248 +f 253/263/249 252/255/249 267/268/249 +f 252/255/239 256/257/239 267/268/239 +f 255/253/250 259/259/250 268/269/250 +f 248/261/242 261/262/242 269/270/242 +f 261/262/251 258/265/251 269/270/251 +f 258/265/252 262/271/252 269/270/252 +f 261/262/242 259/259/242 270/249/242 +f 265/266/246 261/262/246 270/249/246 +f 267/268/253 256/257/253 270/249/253 +f 251/256/254 266/267/254 271/272/254 +f 266/267/255 255/253/255 271/272/255 +f 255/253/256 268/269/256 271/272/256 +f 260/260/257 252/255/257 272/273/257 +f 254/254/258 263/274/258 272/273/258 +f 252/255/259 264/264/259 272/273/259 +f 264/264/260 254/254/260 272/273/260 +f 254/254/261 253/263/261 273/275/261 +f 259/259/238 254/254/238 273/275/238 +f 253/263/262 267/268/262 273/275/262 +f 270/249/242 259/259/242 273/275/242 +f 267/268/263 270/249/263 273/275/263 +f 251/256/264 265/266/264 274/248/264 +f 265/266/236 270/249/236 274/248/236 +f 268/269/265 248/261/265 275/276/265 +f 262/271/266 271/272/266 275/276/266 +f 271/272/267 268/269/267 275/276/267 +f 259/259/242 248/261/242 276/277/242 +f 248/261/265 268/269/265 276/277/265 +f 268/269/250 259/259/250 276/277/250 +f 258/265/268 251/256/268 277/278/268 +f 262/271/269 258/265/269 277/278/269 +f 251/256/270 271/272/270 277/278/270 +f 271/272/271 262/271/271 277/278/271 +f 254/254/272 249/252/272 278/279/272 +f 249/252/272 257/258/272 278/279/272 +f 263/274/273 254/254/273 278/279/273 +f 257/258/274 272/273/274 278/279/274 +f 272/273/275 263/274/275 278/279/275 +f 248/261/242 269/270/242 279/280/242 +f 269/270/276 262/271/276 279/280/276 +f 275/276/277 248/261/277 279/280/277 +f 262/271/278 275/276/278 279/280/278 +f 256/257/239 251/256/239 280/281/239 +f 251/256/279 274/248/279 280/281/279 +f 274/248/280 256/257/280 280/281/280 +f 257/258/241 260/260/241 281/282/241 +f 260/260/257 272/273/257 281/282/257 +f 272/273/274 257/258/274 281/282/274 +f 270/249/281 256/257/281 282/250/281 +f 256/257/280 274/248/280 282/250/280 +o Cup_hull_12 +v 0.024903 0.004363 0.050164 +v 0.021217 0.013580 0.032460 +v 0.021481 0.013315 0.032460 +v 0.022796 -0.000377 0.032460 +v 0.020164 0.013052 0.050164 +v 0.018320 0.013315 0.032460 +v 0.025167 0.002257 0.032460 +v 0.024113 -0.000377 0.050164 +v 0.023322 0.009891 0.050164 +v 0.024376 0.006732 0.032460 +v 0.025167 -0.000377 0.032460 +v 0.021217 0.013580 0.050164 +v 0.025167 -0.000377 0.050164 +v 0.018320 0.013315 0.033306 +v 0.023060 0.010417 0.032460 +v 0.021743 0.013052 0.050164 +v 0.022796 -0.000377 0.033586 +v 0.018320 0.013580 0.033306 +v 0.024376 0.006732 0.050164 +v 0.025167 0.002257 0.050164 +v 0.020164 0.013580 0.050164 +v 0.024903 0.004363 0.032460 +v 0.022006 0.012525 0.032460 +v 0.023586 0.009103 0.032460 +v 0.024640 0.005682 0.045386 +vt 1.000000 0.339663 +vt 1.000000 0.509397 +vt 0.269871 0.434123 +vt 1.000000 1.000000 +vt 1.000000 0.981010 +vt 1.000000 0.000000 +vt 1.000000 0.981010 +vt 1.000000 0.188724 +vt 0.000000 0.339663 +vt 0.000000 0.962216 +vt 0.000000 0.000000 +vt 0.000000 0.735709 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 0.952232 0.981010 +vt 1.000000 0.773395 +vt 0.000000 0.962216 +vt 0.936374 0.000000 +vt 0.952232 1.000000 +vt 0.000000 0.509397 +vt 0.000000 0.188724 +vt 0.000000 1.000000 +vt 1.000000 0.924432 +vt 1.000000 0.679229 +vn 0.9762 0.2171 -0.0023 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn -0.9505 -0.3107 0.0000 +vn -0.9546 -0.2807 0.1000 +vn 0.7093 0.7049 -0.0001 +vn 0.7079 0.7063 0.0000 +vn 0.8946 0.4468 -0.0000 +vn -0.9483 -0.3085 0.0753 +vn -0.0870 0.9506 -0.2979 +vn 0.0000 1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.9941 0.0000 0.1087 +vn 0.9922 0.1244 0.0000 +vn 0.8325 0.5540 -0.0041 +vn 0.8945 0.4471 -0.0000 +vn 0.9282 0.3720 -0.0027 +vn 0.9486 0.3164 0.0001 +vn 0.9488 0.3160 0.0000 +vn 0.9761 0.2171 0.0062 +vn 0.9698 0.2438 0.0000 +vn 0.9807 0.1954 0.0000 +usemtl None +s off +f 304/283/282 292/284/282 307/285/282 +f 284/286/283 285/287/283 286/288/283 +f 284/286/283 286/288/283 288/289/283 +f 286/288/283 285/287/283 289/290/283 +f 283/291/284 287/292/284 290/293/284 +f 287/292/284 283/291/284 291/294/284 +f 289/290/283 285/287/283 292/284/283 +f 286/288/283 289/290/283 293/295/283 +f 290/293/285 286/288/285 293/295/285 +f 287/292/284 291/294/284 294/296/284 +f 283/291/284 290/293/284 295/297/284 +f 293/295/286 289/290/286 295/297/286 +f 290/293/285 293/295/285 295/297/285 +f 288/289/287 286/288/287 296/298/287 +f 290/293/288 287/292/288 296/298/288 +f 292/284/283 285/287/283 297/299/283 +f 285/287/289 284/286/289 298/300/289 +f 284/286/290 294/296/290 298/300/290 +f 294/296/284 291/294/284 298/300/284 +f 291/294/291 297/299/291 298/300/291 +f 286/288/285 290/293/285 299/301/285 +f 296/298/287 286/288/287 299/301/287 +f 290/293/292 296/298/292 299/301/292 +f 284/286/293 288/289/293 300/302/293 +f 294/296/294 284/286/294 300/302/294 +f 288/289/295 296/298/295 300/302/295 +f 296/298/296 287/292/296 300/302/296 +f 291/294/284 283/291/284 301/303/284 +f 289/290/297 283/291/297 302/304/297 +f 283/291/284 295/297/284 302/304/284 +f 295/297/286 289/290/286 302/304/286 +f 287/292/284 294/296/284 303/305/284 +f 294/296/294 300/302/294 303/305/294 +f 300/302/296 287/292/296 303/305/296 +f 283/291/297 289/290/297 304/283/297 +f 289/290/283 292/284/283 304/283/283 +f 297/299/283 285/287/283 305/306/283 +f 285/287/298 298/300/298 305/306/298 +f 298/300/299 297/299/299 305/306/299 +f 297/299/300 291/294/300 306/307/300 +f 292/284/283 297/299/283 306/307/283 +f 291/294/301 301/303/301 306/307/301 +f 301/303/302 292/284/302 306/307/302 +f 301/303/303 283/291/303 307/285/303 +f 292/284/304 301/303/304 307/285/304 +f 283/291/305 304/283/305 307/285/305 +o Cup_hull_13 +v 0.022533 0.001203 0.032460 +v 0.020425 0.013580 0.015036 +v 0.024113 0.006469 0.017285 +v 0.018057 -0.000377 0.015036 +v 0.012001 0.013580 0.015880 +v 0.021215 0.013580 0.032458 +v 0.025167 -0.000377 0.032460 +v 0.024903 -0.000377 0.017285 +v 0.018057 0.013315 0.032177 +v 0.022533 -0.000377 0.032177 +v 0.024640 0.005682 0.032460 +v 0.023060 0.010418 0.018409 +v 0.024903 0.004363 0.018409 +v 0.012001 0.013580 0.015036 +v 0.018319 -0.000377 0.017285 +v 0.020425 -0.000377 0.015036 +v 0.023060 0.010418 0.032460 +v 0.012001 0.013315 0.015880 +v 0.021478 0.013315 0.017846 +v 0.025167 0.002257 0.018409 +v 0.024375 0.006732 0.018409 +v 0.018319 0.013580 0.032458 +v 0.024375 0.000677 0.016724 +v 0.025167 0.002257 0.032460 +v 0.022007 0.012525 0.032460 +v 0.012265 0.013315 0.016724 +v 0.025167 -0.000377 0.017848 +v 0.023585 0.009101 0.032460 +v 0.023585 0.009101 0.018130 +v 0.024375 0.004101 0.017004 +v 0.022007 0.012525 0.018409 +v 0.021215 0.013580 0.017846 +v 0.018057 -0.000377 0.015880 +v 0.024903 0.004363 0.032460 +v 0.024375 0.006732 0.032460 +v 0.022797 -0.000377 0.032460 +v 0.024903 0.003048 0.017567 +vt 0.870889 0.000000 +vt 0.887040 0.320869 +vt 0.854738 0.245399 +vt 1.000000 1.000000 +vt 0.951547 1.000000 +vt 0.000098 1.000000 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 0.016249 0.000000 +vt 0.000000 0.113254 +vt 0.000000 0.434123 +vt 1.000000 1.000000 +vt 0.870889 0.000000 +vt 1.000000 0.000000 +vt 0.000000 0.773493 +vt 0.951547 0.981010 +vt 0.806382 0.773493 +vt 0.838684 0.981010 +vt 0.806382 0.339663 +vt 0.806382 0.509397 +vt 0.870889 0.490505 +vt 0.000098 1.000000 +vt 0.016249 0.981010 +vt 0.903093 0.075568 +vt 0.000000 0.188724 +vt 0.806382 0.188724 +vt 0.000000 0.924432 +vt 0.903093 0.981010 +vt 0.838587 0.000000 +vt 0.000000 0.679131 +vt 0.822435 0.679131 +vt 0.806382 0.924432 +vt 0.838684 1.000000 +vt 0.951547 0.000000 +vt 0.000000 0.339663 +vt 0.000000 0.509397 +vt 0.000000 0.000000 +vn 0.7754 0.0517 -0.6294 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.0000 0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn -0.9103 -0.3950 -0.1240 +vn -1.0000 0.0000 0.0000 +vn -0.8884 -0.3842 0.2513 +vn 0.8637 0.4163 -0.2843 +vn 0.9761 0.2172 -0.0021 +vn 0.9402 0.2092 -0.2690 +vn -0.8192 0.4811 0.3122 +vn 0.3931 0.0000 -0.9195 +vn 0.4355 -0.2435 -0.8667 +vn 1.0000 0.0000 0.0000 +vn 0.9922 0.1244 0.0000 +vn 0.8945 0.4471 0.0000 +vn 0.7999 0.6001 0.0035 +vn 0.0000 0.0016 1.0000 +vn -0.0005 -0.0000 1.0000 +vn -0.9208 0.1815 0.3451 +vn -0.8954 -0.2927 0.3356 +vn -0.9544 0.0000 0.2987 +vn -0.8925 -0.3541 0.2793 +vn 0.9287 0.3708 0.0000 +vn 0.9486 0.3164 0.0000 +vn 0.8514 0.3069 -0.4254 +vn 0.8648 0.4076 -0.2933 +vn 0.9203 0.2739 -0.2795 +vn 0.7206 0.1602 -0.6746 +vn 0.5691 0.0670 -0.8196 +vn 0.7744 0.0515 -0.6306 +vn 0.8750 0.4373 -0.2079 +vn 0.8311 0.5561 0.0000 +vn 0.6962 0.6906 -0.1957 +vn 0.7100 0.7043 0.0000 +vn -0.9145 -0.4045 0.0000 +vn -0.9014 -0.3987 0.1686 +vn 0.9807 0.1956 0.0000 +vn 0.9698 0.2439 0.0000 +vn -0.7111 -0.2325 0.6636 +vn -0.6165 -0.1977 0.7621 +vn -0.0008 -0.0001 1.0000 +vn 0.9349 0.1913 -0.2988 +vn 0.9740 0.1222 -0.1907 +vn 0.9047 0.0349 -0.4247 +vn 0.9661 0.0538 -0.2524 +vn 0.8487 0.1544 -0.5059 +usemtl None +s off +f 315/308/306 337/309/306 344/310/306 +f 309/311/307 312/312/307 313/313/307 +f 314/314/308 311/315/308 315/308/308 +f 311/315/308 314/314/308 317/316/308 +f 308/317/309 314/314/309 318/318/309 +f 309/311/310 311/315/310 321/319/310 +f 312/312/307 309/311/307 321/319/307 +f 311/315/308 317/316/308 322/320/308 +f 311/315/310 309/311/310 323/321/310 +f 315/308/308 311/315/308 323/321/308 +f 308/317/309 318/318/309 324/322/309 +f 321/319/311 311/315/311 325/323/311 +f 312/312/312 321/319/312 325/323/312 +f 322/320/313 317/316/313 325/323/313 +f 319/324/314 309/311/314 326/325/314 +f 318/318/315 320/326/315 328/327/315 +f 320/326/316 310/328/316 328/327/316 +f 313/313/307 312/312/307 329/329/307 +f 312/312/317 316/330/317 329/329/317 +f 323/321/318 309/311/318 330/331/318 +f 315/308/319 323/321/319 330/331/319 +f 318/318/309 314/314/309 331/332/309 +f 314/314/320 327/333/320 331/332/320 +f 327/333/321 320/326/321 331/332/321 +f 308/317/309 324/322/309 332/334/309 +f 324/322/322 319/324/322 332/334/322 +f 326/325/323 313/313/323 332/334/323 +f 313/313/324 329/329/324 332/334/324 +f 329/329/325 308/317/325 332/334/325 +f 316/330/326 312/312/326 333/335/326 +f 317/316/327 316/330/327 333/335/327 +f 312/312/328 325/323/328 333/335/328 +f 325/323/329 317/316/329 333/335/329 +f 314/314/308 315/308/308 334/336/308 +f 327/333/320 314/314/320 334/336/320 +f 324/322/309 318/318/309 335/337/309 +f 319/324/330 324/322/330 335/337/330 +f 335/337/331 328/327/331 336/338/331 +f 310/328/332 309/311/332 336/338/332 +f 309/311/333 319/324/333 336/338/333 +f 328/327/334 310/328/334 336/338/334 +f 319/324/330 335/337/330 336/338/330 +f 309/311/335 310/328/335 337/309/335 +f 330/331/336 309/311/336 337/309/336 +f 315/308/337 330/331/337 337/309/337 +f 319/324/338 326/325/338 338/339/338 +f 332/334/322 319/324/322 338/339/322 +f 326/325/339 332/334/339 338/339/339 +f 309/311/307 313/313/307 339/340/307 +f 326/325/340 309/311/340 339/340/340 +f 313/313/341 326/325/341 339/340/341 +f 311/315/308 322/320/308 340/341/308 +f 325/323/342 311/315/342 340/341/342 +f 322/320/343 325/323/343 340/341/343 +f 320/326/344 318/318/344 341/342/344 +f 318/318/309 331/332/309 341/342/309 +f 331/332/321 320/326/321 341/342/321 +f 318/318/345 328/327/345 342/343/345 +f 335/337/309 318/318/309 342/343/309 +f 328/327/331 335/337/331 342/343/331 +f 314/314/309 308/317/309 343/344/309 +f 317/316/308 314/314/308 343/344/308 +f 316/330/346 317/316/346 343/344/346 +f 329/329/347 316/330/347 343/344/347 +f 308/317/348 329/329/348 343/344/348 +f 310/328/349 320/326/349 344/310/349 +f 320/326/350 327/333/350 344/310/350 +f 334/336/351 315/308/351 344/310/351 +f 327/333/352 334/336/352 344/310/352 +f 337/309/353 310/328/353 344/310/353 +o Cup_hull_14 +v 0.008313 0.022796 0.050166 +v 0.001204 0.025166 0.017848 +v 0.003047 0.024902 0.017567 +v 0.008049 0.015951 0.015036 +v 0.000413 0.024112 0.050166 +v 0.000413 0.018058 0.015036 +v 0.008313 0.023849 0.018130 +v 0.004363 0.024902 0.050166 +v 0.000413 0.024376 0.016724 +v 0.008313 0.020427 0.015036 +v 0.000413 0.025166 0.050166 +v 0.008313 0.023849 0.050166 +v 0.005679 0.024639 0.018409 +v 0.008313 0.015951 0.015318 +v 0.000413 0.018058 0.015882 +v 0.000413 0.020428 0.015036 +v 0.002257 0.025166 0.018409 +v 0.008049 0.015951 0.015318 +v 0.007785 0.022796 0.050166 +v 0.000413 0.025166 0.017848 +v 0.006733 0.023849 0.017006 +v 0.006733 0.024377 0.050166 +v 0.002257 0.025166 0.047913 +v 0.004363 0.024902 0.018409 +v 0.006733 0.024377 0.018409 +v 0.003836 0.024112 0.016724 +v 0.008313 0.023323 0.017006 +v 0.005679 0.024639 0.050166 +vt 0.000000 0.914342 +vt 0.903974 0.942829 +vt 0.000000 0.942829 +vt 0.000000 0.885659 +vt 0.000000 0.742830 +vt 0.000000 0.971415 +vt 0.919930 1.000000 +vt 0.927956 0.971415 +vt 0.951938 0.914244 +vt 1.000000 0.228684 +vt 1.000000 0.000000 +vt 1.000000 0.485756 +vt 0.911903 0.857073 +vt 0.000000 1.000000 +vt 0.000000 0.857073 +vt 0.991973 0.000000 +vt 0.975920 0.228684 +vt 1.000000 0.485854 +vt 0.903974 1.000000 +vt 0.991973 0.000000 +vt 0.000000 0.742830 +vt 0.919930 1.000000 +vt 0.943911 0.857073 +vt 0.064115 1.000000 +vt 0.903974 0.971415 +vt 0.903974 0.914342 +vt 0.951938 0.885659 +vt 0.943911 0.800000 +vn 0.2417 0.9704 0.0000 +vn -0.0000 0.0000 1.0000 +vn 0.0259 0.8092 -0.5869 +vn -1.0000 0.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.7297 -0.0430 -0.6824 +vn -0.2660 -0.9640 0.0000 +vn 0.0000 0.3932 -0.9194 +vn 0.1080 0.9732 -0.2030 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -0.9812 0.1928 +vn 0.0000 -1.0000 0.0000 +vn -0.2506 -0.9533 0.1683 +vn -0.1726 -0.9668 0.1886 +vn 0.0000 0.8182 -0.5750 +vn 0.2058 0.9106 -0.3583 +vn 0.3168 0.9485 0.0000 +vn 0.0664 0.9963 0.0544 +vn 0.1241 0.9923 0.0000 +vn 0.1962 0.9806 0.0000 +vn 0.1876 0.9375 -0.2931 +vn 0.1219 0.9741 -0.1904 +vn 0.2431 0.9079 -0.3415 +vn 0.2270 0.9115 -0.3429 +vn 0.0581 0.7547 -0.6535 +vn 0.0347 0.4508 -0.8920 +vn 0.1305 0.7812 -0.6105 +vn 0.1300 0.5392 -0.8321 +vn 0.2887 0.8672 -0.4056 +vn 0.1841 0.5529 -0.8126 +usemtl None +s off +f 366/345/354 357/346/354 372/347/354 +f 349/348/355 345/349/355 352/350/355 +f 346/351/356 347/352/356 353/353/356 +f 350/354/357 349/348/357 353/353/357 +f 348/355/358 350/354/358 354/356/358 +f 351/357/359 345/349/359 354/356/359 +f 349/348/355 352/350/355 355/358/355 +f 353/353/357 349/348/357 355/358/357 +f 345/349/359 351/357/359 356/359/359 +f 352/350/355 345/349/355 356/359/355 +f 354/356/359 345/349/359 358/360/359 +f 348/355/360 354/356/360 358/360/360 +f 349/348/357 350/354/357 359/361/357 +f 350/354/361 348/355/361 359/361/361 +f 350/354/357 353/353/357 360/362/357 +f 354/356/358 350/354/358 360/362/358 +f 353/353/362 354/356/362 360/362/362 +f 347/352/363 346/351/363 361/363/363 +f 346/351/364 355/358/364 361/363/364 +f 358/360/365 345/349/365 362/364/365 +f 348/355/366 358/360/366 362/364/366 +f 359/361/361 348/355/361 362/364/361 +f 349/348/367 359/361/367 362/364/367 +f 345/349/355 349/348/355 363/365/355 +f 362/364/365 345/349/365 363/365/365 +f 349/348/368 362/364/368 363/365/368 +f 346/351/369 353/353/369 364/366/369 +f 355/358/364 346/351/364 364/366/364 +f 353/353/357 355/358/357 364/366/357 +f 347/352/370 357/346/370 365/367/370 +f 356/359/371 351/357/371 366/345/371 +f 352/350/355 356/359/355 366/345/355 +f 355/358/372 352/350/372 367/368/372 +f 361/363/364 355/358/364 367/368/364 +f 352/350/373 361/363/373 367/368/373 +f 352/350/374 357/346/374 368/369/374 +f 357/346/375 347/352/375 368/369/375 +f 347/352/376 361/363/376 368/369/376 +f 361/363/373 352/350/373 368/369/373 +f 351/357/377 365/367/377 369/370/377 +f 365/367/378 357/346/378 369/370/378 +f 366/345/371 351/357/371 369/370/371 +f 357/346/354 366/345/354 369/370/354 +f 353/353/379 347/352/379 370/371/379 +f 354/356/380 353/353/380 370/371/380 +f 347/352/381 365/367/381 370/371/381 +f 365/367/382 354/356/382 370/371/382 +f 351/357/359 354/356/359 371/372/359 +f 365/367/383 351/357/383 371/372/383 +f 354/356/384 365/367/384 371/372/384 +f 357/346/374 352/350/374 372/347/374 +f 352/350/355 366/345/355 372/347/355 +o Cup_hull_15 +v -0.002221 -0.020392 -0.048198 +v -0.020392 -0.014862 0.015036 +v -0.020126 -0.015389 0.015036 +v -0.002221 -0.017758 0.015036 +v -0.013280 -0.011965 -0.048198 +v -0.014860 -0.020392 -0.048198 +v -0.014860 -0.020392 0.015036 +v -0.013280 -0.011965 0.015036 +v -0.020392 -0.011965 -0.048198 +v -0.002221 -0.020392 0.015036 +v -0.002221 -0.017758 -0.048198 +v -0.020392 -0.011965 0.015036 +v -0.020126 -0.015389 -0.048198 +v -0.016704 -0.019073 -0.027679 +v -0.019074 -0.016704 0.015036 +v -0.019074 -0.016704 -0.048198 +v -0.020392 -0.014862 -0.048198 +v -0.015386 -0.020128 0.015036 +v -0.015386 -0.020128 -0.048198 +v -0.016968 -0.018811 0.015036 +v -0.016704 -0.019073 -0.048198 +vt 0.000000 0.188430 +vt 1.000000 0.072533 +vt 1.000000 0.202917 +vt 0.000000 0.000000 +vt 0.000000 0.014585 +vt 0.000000 1.000000 +vt 1.000000 0.391347 +vt 1.000000 1.000000 +vt 1.000000 0.304424 +vt 0.000000 0.304424 +vt 0.000000 0.391347 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 0.000000 0.000000 +vt 1.000000 0.014585 +vt 0.000000 0.072533 +vt 1.000000 0.000000 +vt 0.000000 0.275450 +vt 1.000000 0.275450 +vt 0.675509 0.202917 +vn -0.7071 -0.7071 -0.0000 +vn -0.0000 0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.4640 0.8858 0.0000 +vn -0.0001 1.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.8934 -0.4492 0.0000 +vn -0.7807 -0.6248 0.0000 +vn -0.4482 -0.8939 0.0000 +vn -0.6246 -0.7809 0.0000 +vn -0.7072 -0.7070 0.0000 +vn -0.6398 -0.7685 0.0008 +vn -0.7059 -0.7083 0.0000 +usemtl None +s off +f 392/373/385 388/374/385 393/375/385 +f 374/376/386 375/377/386 376/378/386 +f 377/379/387 373/380/387 378/381/387 +f 378/381/388 373/380/388 379/382/388 +f 376/378/386 375/377/386 379/382/386 +f 374/376/386 376/378/386 380/383/386 +f 376/378/389 377/379/389 380/383/389 +f 380/383/390 377/379/390 381/384/390 +f 377/379/387 378/381/387 381/384/387 +f 373/380/391 376/378/391 382/385/391 +f 379/382/388 373/380/388 382/385/388 +f 376/378/386 379/382/386 382/385/386 +f 376/378/391 373/380/391 383/386/391 +f 373/380/387 377/379/387 383/386/387 +f 377/379/389 376/378/389 383/386/389 +f 374/376/386 380/383/386 384/387/386 +f 380/383/390 381/384/390 384/387/390 +f 381/384/392 374/376/392 384/387/392 +f 375/377/393 374/376/393 385/388/393 +f 381/384/387 378/381/387 385/388/387 +f 379/382/386 375/377/386 387/389/386 +f 375/377/394 385/388/394 387/389/394 +f 385/388/387 378/381/387 388/374/387 +f 387/389/394 385/388/394 388/374/394 +f 374/376/392 381/384/392 389/390/392 +f 385/388/393 374/376/393 389/390/393 +f 381/384/387 385/388/387 389/390/387 +f 378/381/395 379/382/395 390/391/395 +f 379/382/386 387/389/386 390/391/386 +f 388/374/387 378/381/387 391/392/387 +f 378/381/395 390/391/395 391/392/395 +f 390/391/396 386/393/396 391/392/396 +f 387/389/397 388/374/397 392/373/397 +f 386/393/398 390/391/398 392/373/398 +f 390/391/386 387/389/386 392/373/386 +f 388/374/387 391/392/387 393/375/387 +f 391/392/396 386/393/396 393/375/396 +f 386/393/399 392/373/399 393/375/399 +o Cup_hull_16 +v -0.020127 -0.011963 0.015036 +v -0.018021 -0.000377 -0.048198 +v -0.013545 -0.011700 -0.048198 +v -0.020392 -0.011963 -0.048198 +v -0.020392 -0.000377 0.015029 +v -0.013545 -0.011963 0.015036 +v -0.018021 -0.000377 0.015036 +v -0.020392 -0.000377 -0.048198 +v -0.020392 -0.011963 0.015029 +v -0.013545 -0.011963 -0.048198 +v -0.013545 -0.011700 0.015036 +vt 1.000000 0.022712 +vt 0.000000 1.000000 +vt 0.000000 0.022712 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000098 1.000000 +vt 1.000000 1.000000 +vt 0.000098 0.000000 +vt 1.000000 0.000000 +vn 0.9300 0.3677 0.0000 +vn -0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn -0.0026 0.0005 1.0000 +vn 0.0000 1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.0234 0.0000 0.9997 +vn 1.0000 0.0000 0.0000 +usemtl None +s off +f 396/394/400 400/395/400 404/396/400 +f 395/397/401 396/394/401 397/398/401 +f 394/399/402 397/398/402 399/400/402 +f 394/399/403 399/400/403 400/395/403 +f 396/394/400 395/397/400 400/395/400 +f 398/401/404 394/399/404 400/395/404 +f 395/397/405 398/401/405 400/395/405 +f 395/397/401 397/398/401 401/402/401 +f 397/398/406 398/401/406 401/402/406 +f 398/401/405 395/397/405 401/402/405 +f 397/398/402 394/399/402 402/403/402 +f 394/399/407 398/401/407 402/403/407 +f 398/401/406 397/398/406 402/403/406 +f 397/398/401 396/394/401 403/404/401 +f 396/394/408 399/400/408 403/404/408 +f 399/400/402 397/398/402 403/404/402 +f 399/400/408 396/394/408 404/396/408 +f 400/395/403 399/400/403 404/396/403 +o Cup_hull_17 +v 0.015424 -0.020127 0.015036 +v 0.020163 -0.000379 -0.048198 +v 0.018057 -0.000379 -0.048198 +v 0.012263 -0.020390 -0.048198 +v 0.020426 -0.014861 -0.048192 +v 0.018057 -0.000379 0.015036 +v 0.012263 -0.013017 0.015036 +v 0.020426 -0.014859 0.015036 +v 0.012263 -0.013017 -0.048198 +v 0.020426 -0.000379 0.015036 +v 0.012263 -0.020390 0.015036 +v 0.014897 -0.020390 -0.048198 +v 0.018846 -0.016967 -0.048198 +v 0.020426 -0.000379 -0.048192 +v 0.018583 -0.017230 0.015036 +v 0.017003 -0.018811 -0.048198 +v 0.014897 -0.020390 0.015036 +v 0.017003 -0.018811 0.015036 +v 0.019899 -0.015651 0.015036 +v 0.015424 -0.020127 -0.044540 +v 0.019899 -0.015651 -0.048198 +vt 0.000000 0.236832 +vt 1.000000 0.171040 +vt 1.000000 0.236832 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 0.000000 0.013119 +vt 0.000000 0.368416 +vt 0.000000 0.276385 +vt 1.000000 0.368416 +vt 0.000000 1.000000 +vt 0.999902 0.276287 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 0.999902 1.000000 +vt 0.000000 0.157920 +vt 1.000000 0.078911 +vt 0.000000 0.000000 +vt 0.000000 0.078911 +vt 0.942150 0.013119 +vn 0.7809 -0.6247 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 1.0000 0.0000 +vn -0.0000 0.0000 1.0000 +vn -0.9090 0.4167 0.0000 +vn -1.0000 0.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0235 0.0000 -0.9997 +vn 0.4461 -0.8950 0.0000 +vn 0.7072 -0.7070 0.0000 +vn 0.7071 -0.7071 0.0000 +vn 0.6404 -0.7681 0.0000 +vn 0.8326 -0.5539 0.0000 +vn 0.7682 -0.6403 0.0005 +vn 0.5997 -0.7997 -0.0289 +vn 0.0121 -0.0002 -0.9999 +vn 0.8319 -0.5549 0.0000 +usemtl None +s off +f 423/405/409 417/406/409 425/407/409 +f 407/408/410 406/409/410 408/410/410 +f 406/409/411 407/408/411 410/411/411 +f 405/412/412 410/411/412 411/413/412 +f 410/411/413 407/408/413 411/413/413 +f 410/411/412 405/412/412 412/414/412 +f 407/408/410 408/410/410 413/415/410 +f 411/413/413 407/408/413 413/415/413 +f 408/410/414 411/413/414 413/415/414 +f 406/409/411 410/411/411 414/416/411 +f 412/414/415 409/417/415 414/416/415 +f 410/411/412 412/414/412 414/416/412 +f 405/412/412 411/413/412 415/418/412 +f 411/413/414 408/410/414 415/418/414 +f 408/410/410 406/409/410 416/419/410 +f 415/418/416 408/410/416 416/419/416 +f 416/419/410 406/409/410 417/406/410 +f 409/417/417 406/409/417 418/420/417 +f 406/409/411 414/416/411 418/420/411 +f 414/416/415 409/417/415 418/420/415 +f 412/414/412 405/412/412 419/421/412 +f 416/419/410 417/406/410 420/422/410 +f 405/412/412 415/418/412 421/423/412 +f 416/419/418 405/412/418 421/423/418 +f 415/418/416 416/419/416 421/423/416 +f 419/421/412 405/412/412 422/424/412 +f 417/406/419 419/421/419 422/424/419 +f 420/422/420 417/406/420 422/424/420 +f 405/412/421 420/422/421 422/424/421 +f 409/417/422 412/414/422 423/405/422 +f 412/414/412 419/421/412 423/405/412 +f 419/421/423 417/406/423 423/405/423 +f 405/412/418 416/419/418 424/425/418 +f 420/422/421 405/412/421 424/425/421 +f 416/419/424 420/422/424 424/425/424 +f 406/409/425 409/417/425 425/407/425 +f 417/406/410 406/409/410 425/407/410 +f 409/417/426 423/405/426 425/407/426 +o Cup_hull_18 +v -0.015651 0.019899 -0.048198 +v -0.020392 0.013317 0.015036 +v -0.011965 0.013317 0.015036 +v 0.000413 0.020426 0.015036 +v -0.011965 0.013317 -0.048198 +v 0.000413 0.018056 -0.048198 +v -0.014861 0.020425 0.015036 +v -0.020392 0.014897 -0.048198 +v 0.000413 0.020426 -0.048198 +v 0.000413 0.018056 0.015036 +v -0.020392 0.013317 -0.048198 +v -0.018811 0.017002 0.015036 +v -0.014861 0.020425 -0.048198 +v -0.020392 0.014897 0.015036 +v -0.018811 0.017002 -0.048198 +v -0.017231 0.018583 0.015036 +v -0.020127 0.015424 0.015036 +v -0.016966 0.018846 -0.048198 +v -0.015651 0.019899 0.015036 +v -0.020127 0.015424 -0.045667 +vt 0.000000 0.012725 +vt 1.000000 0.075959 +vt 0.959965 0.012725 +vt 0.000000 0.000000 +vt 0.000000 0.405051 +vt 0.000000 1.000000 +vt 1.000000 0.405051 +vt 1.000000 1.000000 +vt 1.000000 0.227878 +vt 0.000000 0.265858 +vt 1.000000 0.000000 +vt 1.000000 1.000000 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.075959 +vt 1.000000 0.265858 +vt 0.000000 0.000000 +vt 0.000000 0.151919 +vt 1.000000 0.164644 +vt 0.000000 0.227878 +vn -0.7682 0.6402 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.3576 -0.9339 0.0000 +vn -0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn -0.0000 1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.5543 0.8323 0.0000 +vn -0.7072 0.7070 0.0000 +vn -0.8935 0.4490 0.0000 +vn -0.7069 0.7074 -0.0000 +vn -0.6400 0.7684 0.0005 +vn -0.6249 0.7807 0.0000 +vn -0.7991 0.5998 -0.0413 +usemtl None +s off +f 442/426/427 440/427/427 445/428/427 +f 427/429/428 428/430/428 429/431/428 +f 428/430/429 427/429/429 430/432/429 +f 428/430/430 430/432/430 431/433/430 +f 430/432/431 426/434/431 431/433/431 +f 427/429/428 429/431/428 432/435/428 +f 426/434/431 430/432/431 433/436/431 +f 429/431/432 431/433/432 434/437/432 +f 431/433/431 426/434/431 434/437/431 +f 432/435/433 429/431/433 434/437/433 +f 429/431/428 428/430/428 435/438/428 +f 428/430/430 431/433/430 435/438/430 +f 431/433/432 429/431/432 435/438/432 +f 430/432/429 427/429/429 436/439/429 +f 433/436/431 430/432/431 436/439/431 +f 427/429/434 433/436/434 436/439/434 +f 427/429/428 432/435/428 437/440/428 +f 426/434/435 432/435/435 438/441/435 +f 434/437/431 426/434/431 438/441/431 +f 432/435/433 434/437/433 438/441/433 +f 433/436/434 427/429/434 439/442/434 +f 427/429/428 437/440/428 439/442/428 +f 426/434/431 433/436/431 440/427/431 +f 440/427/436 437/440/436 441/443/436 +f 437/440/428 432/435/428 441/443/428 +f 433/436/437 439/442/437 442/426/437 +f 439/442/428 437/440/428 442/426/428 +f 437/440/427 440/427/427 442/426/427 +f 426/434/431 440/427/431 443/444/431 +f 440/427/438 441/443/438 443/444/438 +f 443/444/439 441/443/439 444/445/439 +f 432/435/435 426/434/435 444/445/435 +f 441/443/428 432/435/428 444/445/428 +f 426/434/440 443/444/440 444/445/440 +f 440/427/441 433/436/441 445/428/441 +f 433/436/437 442/426/437 445/428/437 +o Cup_hull_19 +v 0.018056 0.017793 -0.048198 +v 0.000413 0.018056 0.015036 +v 0.012788 0.012527 0.015036 +v 0.014896 0.020427 0.015036 +v 0.000413 0.020426 -0.048198 +v 0.012788 0.012527 -0.048198 +v 0.020427 0.012527 0.015036 +v 0.020427 0.012527 -0.048192 +v 0.014896 0.020427 -0.048198 +v 0.000413 0.020426 0.015036 +v 0.000413 0.018056 -0.048198 +v 0.020427 0.014897 0.015036 +v 0.020427 0.014897 -0.048192 +v 0.018319 0.017529 0.015036 +v 0.015686 0.019898 0.015036 +v 0.019900 0.015686 -0.048198 +v 0.017265 0.018583 -0.048198 +v 0.019900 0.015686 0.015036 +v 0.018583 0.017266 -0.048198 +v 0.015686 0.019898 -0.048198 +v 0.017792 0.018056 0.015036 +vt 1.000000 0.842013 +vt 0.000000 0.763117 +vt 0.000000 0.868344 +vt 0.000000 0.000000 +vt 0.000000 0.618344 +vt 0.000000 0.723669 +vt 1.000000 0.618344 +vt 1.000000 0.000000 +vt 1.000000 0.881558 +vt 0.000000 1.000000 +vt 0.999902 1.000000 +vt 1.000000 0.723669 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 0.999902 1.000000 +vt 0.000000 0.894675 +vt 1.000000 0.973669 +vt 0.000000 0.973669 +vt 1.000000 0.907890 +vt 1.000000 0.763117 +vn 0.6585 0.7526 0.0008 +vn 0.0000 0.0000 1.0000 +vn -0.4079 -0.9130 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.0001 1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.5560 0.8312 0.0000 +vn 0.0008 -0.0018 -1.0000 +vn 0.0117 0.0000 -0.9999 +vn 0.8317 0.5552 -0.0000 +vn 0.8315 0.5555 0.0000 +vn 0.7682 0.6402 0.0000 +vn 0.7069 0.7073 0.0000 +vn -0.0001 0.0000 -1.0000 +vn 0.7590 0.6511 0.0005 +vn 0.6401 0.7683 0.0000 +vn 0.7066 0.7076 0.0000 +usemtl None +s off +f 462/446/442 460/447/442 466/448/442 +f 447/449/443 448/450/443 449/451/443 +f 448/450/444 447/449/444 451/452/444 +f 450/453/445 446/454/445 451/452/445 +f 448/450/446 451/452/446 452/455/446 +f 449/451/443 448/450/443 452/455/443 +f 452/455/446 451/452/446 453/456/446 +f 446/454/445 450/453/445 454/457/445 +f 450/453/447 449/451/447 454/457/447 +f 447/449/443 449/451/443 455/458/443 +f 449/451/447 450/453/447 455/458/447 +f 450/453/448 447/449/448 455/458/448 +f 447/449/448 450/453/448 456/459/448 +f 451/452/444 447/449/444 456/459/444 +f 450/453/445 451/452/445 456/459/445 +f 449/451/443 452/455/443 457/460/443 +f 452/455/449 453/456/449 457/460/449 +f 457/460/449 453/456/449 458/461/449 +f 449/451/443 457/460/443 459/462/443 +f 454/457/450 449/451/450 460/447/450 +f 449/451/443 459/462/443 460/447/443 +f 451/452/445 446/454/445 461/463/445 +f 453/456/451 451/452/451 461/463/451 +f 458/461/452 453/456/452 461/463/452 +f 457/460/453 458/461/453 461/463/453 +f 446/454/445 454/457/445 462/446/445 +f 459/462/443 457/460/443 463/464/443 +f 457/460/454 461/463/454 463/464/454 +f 463/464/455 461/463/455 464/465/455 +f 446/454/456 459/462/456 464/465/456 +f 461/463/457 446/454/457 464/465/457 +f 459/462/458 463/464/458 464/465/458 +f 454/457/450 460/447/450 465/466/450 +f 462/446/445 454/457/445 465/466/445 +f 460/447/459 462/446/459 465/466/459 +f 459/462/456 446/454/456 466/448/456 +f 460/447/443 459/462/443 466/448/443 +f 446/454/460 462/446/460 466/448/460 +o Cup_hull_20 +v -0.019075 -0.016703 0.048477 +v -0.021180 -0.009068 0.034429 +v -0.023551 -0.009068 0.034429 +v -0.013281 -0.021182 0.034429 +v -0.013281 -0.020127 0.050166 +v -0.022498 -0.009068 0.050166 +v -0.019075 -0.016703 0.034429 +v -0.013281 -0.018811 0.034429 +v -0.021708 -0.013019 0.050166 +v -0.015389 -0.020127 0.050166 +v -0.020918 -0.014335 0.034429 +v -0.023287 -0.009859 0.050166 +v -0.016705 -0.019074 0.034429 +v -0.013808 -0.021182 0.050166 +v -0.022234 -0.009068 0.049039 +v -0.014335 -0.020917 0.034429 +v -0.021180 -0.009068 0.035553 +v -0.022498 -0.011439 0.034429 +v -0.016705 -0.019074 0.050166 +v -0.013281 -0.018811 0.035553 +v -0.020127 -0.015387 0.050166 +v -0.023551 -0.009068 0.046230 +v -0.013281 -0.021182 0.050166 +v -0.023551 -0.009332 0.034429 +v -0.021708 -0.013019 0.034429 +v -0.023287 -0.009068 0.050166 +v -0.013808 -0.021182 0.034429 +vt 0.000000 0.000000 +vt 1.000000 0.021829 +vt 1.000000 0.000000 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 0.369714 +vt 1.000000 0.195673 +vt 0.000000 0.087020 +vt 0.000000 0.673845 +vt 0.000000 0.087020 +vt 1.000000 0.565192 +vt 0.000000 0.934710 +vt 0.107283 0.369714 +vt 1.000000 0.173943 +vt 0.071554 1.000000 +vt 0.928543 1.000000 +vt 1.000000 0.804229 +vt 0.000000 0.173943 +vt 0.928543 0.195673 +vt 0.000000 0.478367 +vt 0.250098 1.000000 +vt 0.000000 0.000000 +vt 1.000000 0.978172 +vt 1.000000 0.673845 +vt 0.000000 1.000000 +vn -0.4486 -0.8937 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 1.0000 -0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn -0.7074 -0.7068 0.0000 +vn 0.7560 0.6300 0.1775 +vn -0.6137 -0.7895 -0.0015 +vn -0.5547 -0.8321 0.0046 +vn 0.7768 0.6297 0.0000 +vn 0.7728 0.6317 0.0604 +vn -0.8945 -0.4471 0.0000 +vn -0.6248 -0.7808 0.0000 +vn 0.7756 0.6287 0.0566 +vn -0.7810 -0.6246 0.0000 +vn -0.7892 -0.6141 -0.0014 +vn -0.8318 -0.5551 0.0047 +vn -0.7311 -0.6784 0.0731 +vn 0.0000 -1.0000 0.0000 +vn -0.0001 0.0000 -1.0000 +vn -0.8946 -0.4469 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.9579 -0.2870 0.0064 +vn -0.8574 -0.5147 0.0000 +vn -0.8943 -0.4474 0.0000 +vn -0.9978 0.0000 0.0668 +usemtl None +s off +f 480/467/461 482/468/461 493/469/461 +f 469/470/462 468/471/462 470/472/462 +f 468/471/463 469/470/463 472/473/463 +f 469/470/462 470/472/462 473/474/462 +f 470/472/462 468/471/462 474/475/462 +f 471/476/464 470/472/464 474/475/464 +f 471/476/465 472/473/465 475/477/465 +f 471/476/465 475/477/465 476/478/465 +f 469/470/462 473/474/462 477/479/462 +f 475/477/465 472/473/465 478/480/465 +f 467/481/466 473/474/466 479/482/466 +f 473/474/462 470/472/462 479/482/462 +f 471/476/465 476/478/465 480/467/465 +f 468/471/463 472/473/463 481/483/463 +f 472/473/467 471/476/467 481/483/467 +f 479/482/462 470/472/462 482/468/462 +f 476/478/468 479/482/468 482/468/468 +f 480/467/469 476/478/469 482/468/469 +f 474/475/470 468/471/470 483/484/470 +f 468/471/463 481/483/463 483/484/463 +f 481/483/471 471/476/471 483/484/471 +f 469/470/462 477/479/462 484/485/462 +f 475/477/472 478/480/472 484/485/472 +f 476/478/465 475/477/465 485/486/465 +f 467/481/466 479/482/466 485/486/466 +f 479/482/473 476/478/473 485/486/473 +f 471/476/464 474/475/464 486/487/464 +f 474/475/470 483/484/470 486/487/470 +f 483/484/474 471/476/474 486/487/474 +f 473/474/475 467/481/475 487/488/475 +f 477/479/476 473/474/476 487/488/476 +f 475/477/477 477/479/477 487/488/477 +f 467/481/478 485/486/478 487/488/478 +f 485/486/465 475/477/465 487/488/465 +f 472/473/463 469/470/463 488/489/463 +f 470/472/464 471/476/464 489/490/464 +f 480/467/479 470/472/479 489/490/479 +f 471/476/465 480/467/465 489/490/465 +f 469/470/480 484/485/480 490/491/480 +f 484/485/481 478/480/481 490/491/481 +f 488/489/482 469/470/482 490/491/482 +f 478/480/483 488/489/483 490/491/483 +f 477/479/484 475/477/484 491/492/484 +f 484/485/462 477/479/462 491/492/462 +f 475/477/485 484/485/485 491/492/485 +f 478/480/465 472/473/465 492/493/465 +f 472/473/463 488/489/463 492/493/463 +f 488/489/486 478/480/486 492/493/486 +f 470/472/479 480/467/479 493/469/479 +f 482/468/462 470/472/462 493/469/462 +o Cup_hull_21 +v -0.016705 -0.019073 0.034427 +v -0.015388 -0.009068 0.015038 +v -0.020391 -0.009068 0.015038 +v -0.013281 -0.020391 0.015038 +v -0.023552 -0.009332 0.034427 +v -0.013281 -0.018548 0.034143 +v -0.020127 -0.015387 0.015038 +v -0.020918 -0.009068 0.034143 +v -0.013281 -0.011966 0.015038 +v -0.023552 -0.009068 0.018410 +v -0.013808 -0.021182 0.018129 +v -0.013281 -0.021182 0.034427 +v -0.020918 -0.014335 0.034427 +v -0.016969 -0.018811 0.015038 +v -0.021708 -0.013019 0.018129 +v -0.015915 -0.009068 0.017568 +v -0.019075 -0.016704 0.034427 +v -0.014335 -0.020917 0.034427 +v -0.015388 -0.020126 0.015038 +v -0.021181 -0.009068 0.034427 +v -0.013281 -0.012492 0.017287 +v -0.022760 -0.009859 0.017006 +v -0.019075 -0.016704 0.015038 +v -0.023552 -0.009068 0.034427 +v -0.023552 -0.009332 0.018410 +v -0.021708 -0.013019 0.034427 +v -0.013281 -0.021182 0.017568 +v -0.013281 -0.018811 0.034427 +v -0.020391 -0.014861 0.015038 +v -0.020918 -0.014335 0.018410 +v -0.013808 -0.021182 0.034427 +v -0.022497 -0.009068 0.016725 +v -0.014335 -0.020917 0.018410 +vt 0.000000 0.021829 +vt 1.000000 0.087118 +vt 0.826057 0.021829 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.065290 +vt 1.000000 0.478367 +vt 0.014683 1.000000 +vt 1.000000 0.760768 +vt 0.014683 0.217404 +vt 0.826057 1.000000 +vt 0.000000 0.978172 +vt 0.000000 0.174041 +vt 0.000000 0.000000 +vt 0.000000 0.565192 +vt 1.000000 0.195673 +vt 0.869518 1.000000 +vt 0.000000 0.369616 +vt 0.000000 1.000000 +vt 0.884005 0.717306 +vt 1.000000 0.369616 +vt 0.000000 1.000000 +vt 0.826057 0.978172 +vt 0.840544 0.673845 +vt 0.898493 0.934710 +vt 0.000000 0.673845 +vt 0.869518 0.000000 +vt 0.840544 0.000000 +vt 0.000000 0.195673 +vt 1.000000 0.521731 +vt 0.826057 0.565192 +vt 0.000000 0.000000 +vt 0.912980 1.000000 +vn -0.6004 -0.7997 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 1.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn -0.0000 0.0000 1.0000 +vn 0.7581 0.6107 0.2288 +vn -0.7893 -0.6140 0.0011 +vn -0.7070 -0.7072 0.0000 +vn -0.6396 -0.7687 -0.0017 +vn -0.6140 -0.7893 0.0012 +vn 0.8012 0.5826 0.1364 +vn 0.7884 0.5929 0.1641 +vn 0.7832 0.5852 0.2102 +vn -0.7813 -0.6242 0.0000 +vn -0.7073 -0.7069 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.8944 -0.4473 0.0000 +vn -0.8713 0.0000 -0.4908 +vn 0.0001 0.0000 1.0000 +vn -0.8574 -0.5147 0.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.1189 -0.9477 -0.2963 +vn -0.2242 -0.9516 -0.2102 +vn 0.6737 0.5426 0.5017 +vn 0.6308 0.5114 0.5836 +vn -0.8882 -0.4454 -0.1129 +vn -0.8916 -0.4368 -0.1194 +vn -0.8797 -0.2601 -0.3981 +vn -0.7995 -0.6007 0.0000 +vn -0.8532 -0.5202 -0.0377 +vn -0.4486 -0.8937 0.0000 +vn -0.8440 0.0935 -0.5281 +vn -0.6252 0.0000 -0.7804 +vn -0.6798 -0.0338 -0.7326 +vn -0.4726 -0.8793 -0.0586 +usemtl None +s off +f 511/494/487 512/495/487 526/496/487 +f 496/497/488 495/498/488 497/499/488 +f 496/497/488 497/499/488 500/500/488 +f 495/498/489 496/497/489 501/501/489 +f 497/499/488 495/498/488 502/502/488 +f 499/503/490 497/499/490 502/502/490 +f 501/501/489 496/497/489 503/504/489 +f 498/505/491 494/506/491 505/507/491 +f 497/499/490 499/503/490 505/507/490 +f 494/506/491 498/505/491 506/508/491 +f 500/500/488 497/499/488 507/509/488 +f 495/498/489 501/501/489 509/510/489 +f 501/501/492 499/503/492 509/510/492 +f 494/506/491 506/508/491 510/511/491 +f 506/508/493 500/500/493 510/511/493 +f 507/509/494 494/506/494 510/511/494 +f 505/507/491 494/506/491 511/494/491 +f 507/509/488 497/499/488 512/495/488 +f 494/506/495 507/509/495 512/495/495 +f 511/494/496 494/506/496 512/495/496 +f 501/501/489 503/504/489 513/512/489 +f 498/505/491 505/507/491 513/512/491 +f 502/502/497 495/498/497 514/513/497 +f 499/503/490 502/502/490 514/513/490 +f 495/498/498 509/510/498 514/513/498 +f 509/510/499 499/503/499 514/513/499 +f 500/500/488 507/509/488 516/514/488 +f 510/511/500 500/500/500 516/514/500 +f 507/509/501 510/511/501 516/514/501 +f 503/504/502 498/505/502 517/515/502 +f 498/505/491 513/512/491 517/515/491 +f 513/512/489 503/504/489 517/515/489 +f 498/505/502 503/504/502 518/516/502 +f 508/517/503 498/505/503 518/516/503 +f 503/504/504 515/518/504 518/516/504 +f 506/508/505 498/505/505 519/519/505 +f 498/505/503 508/517/503 519/519/503 +f 508/517/506 506/508/506 519/519/506 +f 497/499/490 505/507/490 520/520/490 +f 505/507/507 504/521/507 520/520/507 +f 512/495/508 497/499/508 520/520/508 +f 504/521/509 512/495/509 520/520/509 +f 499/503/510 501/501/510 521/522/510 +f 505/507/490 499/503/490 521/522/490 +f 501/501/511 513/512/511 521/522/511 +f 513/512/491 505/507/491 521/522/491 +f 496/497/488 500/500/488 522/523/488 +f 500/500/512 508/517/512 522/523/512 +f 508/517/513 518/516/513 522/523/513 +f 518/516/514 515/518/514 522/523/514 +f 500/500/515 506/508/515 523/524/515 +f 508/517/516 500/500/516 523/524/516 +f 506/508/506 508/517/506 523/524/506 +f 504/521/507 505/507/507 524/525/507 +f 505/507/491 511/494/491 524/525/491 +f 511/494/517 504/521/517 524/525/517 +f 503/504/489 496/497/489 525/526/489 +f 515/518/518 503/504/518 525/526/518 +f 496/497/519 522/523/519 525/526/519 +f 522/523/520 515/518/520 525/526/520 +f 504/521/517 511/494/517 526/496/517 +f 512/495/521 504/521/521 526/496/521 +o Cup_hull_22 +v -0.024078 -0.007750 0.050164 +v -0.023025 -0.000378 0.033584 +v -0.025132 -0.000378 0.033584 +v -0.021182 -0.009067 0.033584 +v -0.024078 -0.000642 0.050164 +v -0.023814 -0.008540 0.033584 +v -0.022499 -0.009067 0.050164 +v -0.025132 -0.002485 0.050164 +v -0.024868 -0.004592 0.033584 +v -0.025132 -0.000378 0.050164 +v -0.021182 -0.008803 0.034991 +v -0.023551 -0.009067 0.050164 +v -0.023551 -0.009067 0.033584 +v -0.024604 -0.005907 0.050164 +v -0.023025 -0.000378 0.034991 +v -0.022499 -0.008540 0.050164 +v -0.025132 -0.002485 0.033584 +v -0.024604 -0.005907 0.033584 +v -0.024868 -0.004592 0.050164 +v -0.024078 -0.000378 0.048758 +v -0.021182 -0.008540 0.033584 +vt 0.915133 1.000000 +vt 0.915133 0.030345 +vt 1.000000 0.060689 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 1.000000 0.060689 +vt 0.000000 0.969655 +vt 0.000000 0.151527 +vt 0.000000 0.000000 +vt 0.000000 0.757537 +vt 1.000000 0.515074 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 0.000000 0.363645 +vt 0.000000 0.060689 +vt 1.000000 0.757537 +vt 1.000000 0.363645 +vt 0.000000 0.515074 +vt 0.084769 1.000000 +vn 0.9761 0.2136 0.0400 +vn 0.0000 0.0000 -1.0000 +vn -0.0000 0.0000 1.0000 +vn 0.0000 1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.9183 -0.3892 0.0729 +vn -0.9285 -0.3714 0.0029 +vn 0.0000 -1.0000 0.0000 +vn -0.8947 -0.4467 0.0000 +vn 0.9744 0.2132 0.0713 +vn 0.9773 0.1954 0.0814 +vn 0.9963 0.0000 0.0865 +vn -0.9922 -0.1244 0.0000 +vn -0.9578 -0.2874 -0.0015 +vn -0.9615 -0.2747 0.0000 +vn -0.9806 -0.1962 0.0000 +vn 0.2388 0.9544 0.1790 +vn 0.9238 0.3764 0.0706 +vn 1.0000 0.0000 0.0000 +vn 0.9754 0.2203 0.0000 +usemtl None +s off +f 541/527/522 537/528/522 547/529/522 +f 529/530/523 528/531/523 530/532/523 +f 529/530/523 530/532/523 532/533/523 +f 531/534/524 527/535/524 533/536/524 +f 527/535/524 531/534/524 534/537/524 +f 529/530/523 532/533/523 535/538/523 +f 528/531/525 529/530/525 536/539/525 +f 534/537/524 531/534/524 536/539/524 +f 529/530/526 534/537/526 536/539/526 +f 533/536/527 530/532/527 537/528/527 +f 527/535/528 532/533/528 538/540/528 +f 530/532/529 533/536/529 538/540/529 +f 533/536/524 527/535/524 538/540/524 +f 532/533/523 530/532/523 539/541/523 +f 538/540/530 532/533/530 539/541/530 +f 530/532/529 538/540/529 539/541/529 +f 527/535/524 534/537/524 540/542/524 +f 528/531/525 536/539/525 541/527/525 +f 531/534/531 537/528/531 541/527/531 +f 531/534/524 533/536/524 542/543/524 +f 537/528/532 531/534/532 542/543/532 +f 533/536/533 537/528/533 542/543/533 +f 534/537/526 529/530/526 543/544/526 +f 529/530/523 535/538/523 543/544/523 +f 535/538/534 534/537/534 543/544/534 +f 532/533/535 527/535/535 544/545/535 +f 535/538/523 532/533/523 544/545/523 +f 527/535/536 540/542/536 544/545/536 +f 540/542/537 535/538/537 544/545/537 +f 534/537/534 535/538/534 545/546/534 +f 540/542/524 534/537/524 545/546/524 +f 535/538/537 540/542/537 545/546/537 +f 536/539/538 531/534/538 546/547/538 +f 541/527/525 536/539/525 546/547/525 +f 531/534/539 541/527/539 546/547/539 +f 530/532/523 528/531/523 547/529/523 +f 537/528/540 530/532/540 547/529/540 +f 528/531/541 541/527/541 547/529/541 +o Cup_hull_23 +v -0.015652 -0.009067 0.015036 +v -0.025131 -0.002485 0.033582 +v -0.024868 -0.004592 0.033582 +v -0.024868 -0.003275 0.017567 +v -0.018022 -0.000378 0.015037 +v -0.020918 -0.009066 0.033301 +v -0.023550 -0.009066 0.017846 +v -0.022761 -0.000378 0.033301 +v -0.025131 -0.000378 0.017846 +v -0.020655 -0.008803 0.015037 +v -0.023550 -0.009066 0.033582 +v -0.015915 -0.008804 0.017004 +v -0.025131 -0.000378 0.033582 +v -0.020655 -0.000378 0.015037 +v -0.018549 -0.000378 0.018128 +v -0.024605 -0.005907 0.018409 +v -0.024341 -0.000378 0.016722 +v -0.025131 -0.002485 0.018409 +v -0.024078 -0.007750 0.033582 +v -0.024341 -0.004592 0.017004 +v -0.021181 -0.008277 0.033582 +v -0.020918 -0.008803 0.033301 +v -0.023024 -0.009066 0.017004 +v -0.023814 -0.008540 0.018409 +v -0.018022 -0.000378 0.015880 +v -0.022761 -0.000906 0.033582 +v -0.024868 -0.004592 0.018409 +v -0.024605 -0.005907 0.033582 +v -0.015652 -0.008804 0.015880 +v -0.020392 -0.009066 0.015037 +vt 0.893882 0.222222 +vt 0.999902 0.472149 +vt 0.999902 0.499951 +vt 0.015174 0.250024 +vt 0.999902 0.749976 +vt 0.848458 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.027704 +vt 0.000000 0.166716 +vt 1.000000 1.000000 +vt 0.015174 0.444445 +vt 0.848458 0.166716 +vt 0.893882 0.972198 +vt 0.000000 0.000000 +vt 0.999902 0.472149 +vt 0.833284 0.694371 +vt 0.863534 0.027704 +vt 0.909055 0.083309 +vt 0.818111 0.000000 +vt 0.000000 0.111111 +vt 0.818111 0.055507 +vt 0.893882 0.083309 +vt 0.000000 0.416642 +vt 0.015174 0.444445 +vt 0.818111 0.138913 +vt 0.954479 0.749976 +vt 0.000000 0.250024 +vt 0.818111 0.027704 +vt 0.000000 0.055507 +vt 0.954479 1.000000 +vn -0.5131 -0.5145 -0.6870 +vn 0.0000 1.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.0001 -1.0000 0.0000 +vn 0.6427 -0.7434 0.1853 +vn -1.0000 0.0000 0.0000 +vn 0.0000 0.0002 -1.0000 +vn -0.0004 0.0000 -1.0000 +vn 0.9313 0.2566 0.2585 +vn -0.8181 -0.0187 -0.5748 +vn -0.4157 0.0000 -0.9095 +vn -0.9923 -0.1237 0.0000 +vn -0.9683 -0.0645 -0.2414 +vn -0.9078 -0.2076 -0.3645 +vn -0.8945 -0.2302 -0.3832 +vn -0.7764 -0.0420 -0.6288 +vn -0.5198 -0.0569 -0.8524 +vn 0.1013 -0.3039 0.9473 +vn 0.9560 0.0000 0.2935 +vn 0.9357 0.2047 0.2872 +vn 0.7299 0.0000 0.6835 +vn -0.0001 -1.0000 -0.0001 +vn -0.8229 -0.2422 -0.5140 +vn -0.6161 -0.1813 -0.7665 +vn -0.8942 -0.4476 0.0000 +vn -0.9427 -0.2831 -0.1766 +vn -0.9283 -0.3718 0.0032 +vn -0.9577 -0.2876 -0.0017 +vn 0.9390 0.2641 0.2202 +vn 0.1042 0.4682 0.8774 +vn 0.9069 0.1984 0.3717 +vn 0.8662 0.1856 0.4639 +vn -0.9805 -0.1965 0.0000 +vn -0.9373 -0.1878 -0.2936 +vn -0.9743 -0.1214 -0.1898 +vn -0.9615 -0.2749 0.0000 +vn 0.9615 0.2623 -0.0817 +vn 0.7851 -0.5914 0.1841 +vn 0.9626 0.2708 0.0000 +vn -0.0004 -0.0004 -1.0000 +vn -0.0002 -1.0000 -0.0002 +usemtl None +s off +f 570/548/542 557/549/542 577/550/542 +f 555/551/543 552/552/543 556/553/543 +f 549/554/544 550/555/544 558/556/544 +f 548/557/545 553/558/545 558/556/545 +f 554/559/546 548/557/546 558/556/546 +f 553/558/547 548/557/547 559/560/547 +f 556/553/548 549/554/548 560/561/548 +f 555/551/543 556/553/543 560/561/543 +f 549/554/544 558/556/544 560/561/544 +f 552/552/549 548/557/549 561/562/549 +f 556/553/543 552/552/543 561/562/543 +f 548/557/550 557/549/550 561/562/550 +f 552/552/543 555/551/543 562/563/543 +f 555/551/551 559/560/551 562/563/551 +f 551/564/552 556/553/552 564/565/552 +f 556/553/543 561/562/543 564/565/543 +f 561/562/553 557/549/553 564/565/553 +f 550/555/554 549/554/554 565/566/554 +f 549/554/548 556/553/548 565/566/548 +f 556/553/555 551/564/555 565/566/555 +f 558/556/544 550/555/544 566/567/544 +f 563/568/556 551/564/556 567/569/556 +f 554/559/557 563/568/557 567/569/557 +f 551/564/558 564/565/558 567/569/558 +f 564/565/559 557/549/559 567/569/559 +f 558/556/560 553/558/560 568/570/560 +f 560/561/544 558/556/544 568/570/544 +f 553/558/561 559/560/561 569/571/561 +f 559/560/562 555/551/562 569/571/562 +f 568/570/563 553/558/563 569/571/563 +f 548/557/564 554/559/564 570/548/564 +f 554/559/565 567/569/565 570/548/565 +f 567/569/566 557/549/566 570/548/566 +f 554/559/567 558/556/567 571/572/567 +f 563/568/568 554/559/568 571/572/568 +f 558/556/569 566/567/569 571/572/569 +f 566/567/570 563/568/570 571/572/570 +f 552/552/543 562/563/543 572/573/543 +f 562/563/571 559/560/571 572/573/571 +f 555/551/572 560/561/572 573/574/572 +f 560/561/544 568/570/544 573/574/544 +f 569/571/573 555/551/573 573/574/573 +f 568/570/574 569/571/574 573/574/574 +f 563/568/575 550/555/575 574/575/575 +f 551/564/576 563/568/576 574/575/576 +f 550/555/554 565/566/554 574/575/554 +f 565/566/577 551/564/577 574/575/577 +f 550/555/575 563/568/575 575/576/575 +f 566/567/544 550/555/544 575/576/544 +f 563/568/578 566/567/578 575/576/578 +f 548/557/579 552/552/579 576/577/579 +f 559/560/580 548/557/580 576/577/580 +f 552/552/581 572/573/581 576/577/581 +f 572/573/571 559/560/571 576/577/571 +f 557/549/582 548/557/582 577/550/582 +f 548/557/583 570/548/583 577/550/583 +o Cup_hull_24 +v -0.025132 0.002520 0.050166 +v -0.021182 0.008313 0.032181 +v -0.023814 0.008313 0.032181 +v -0.022762 -0.000376 0.032181 +v -0.022762 0.008313 0.050166 +v -0.025132 -0.000376 0.032181 +v -0.024341 -0.000376 0.050166 +v -0.024078 0.007785 0.050166 +v -0.024604 0.005941 0.032181 +v -0.021182 0.007785 0.032744 +v -0.025132 -0.000376 0.050166 +v -0.025132 0.002520 0.032181 +v -0.024078 0.000677 0.050166 +v -0.022762 -0.000376 0.033306 +v -0.024604 0.005941 0.050166 +v -0.022762 0.007785 0.050166 +v -0.023814 0.008313 0.050166 +v -0.024078 0.007785 0.032181 +v -0.024868 0.004362 0.050166 +vt 0.000000 0.727068 +vt 1.000000 0.727068 +vt 0.000000 0.545276 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.333333 +vt 0.000000 0.939207 +vt 0.968677 0.939207 +vt 0.000000 0.000000 +vt 1.000000 0.333333 +vt 0.000000 0.121194 +vt 0.937451 0.000000 +vt 0.000000 0.939207 +vt 0.000000 1.000000 +vt 1.000000 0.939207 +vn -0.9864 0.1644 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -1.0000 -0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.9703 -0.1765 -0.1655 +vn 0.9919 0.0929 0.0871 +vn -1.0000 0.0000 0.0000 +vn 0.9791 -0.1835 0.0879 +vn 0.9818 -0.1901 0.0000 +vn 0.9662 -0.2416 0.0905 +vn -0.9615 0.2747 0.0000 +vn 0.9959 0.0000 0.0903 +vn 0.9794 -0.1813 0.0888 +vn -0.8950 0.4461 0.0000 +vn -0.9899 0.1419 0.0000 +vn -0.9883 0.1524 -0.0011 +usemtl None +s off +f 592/578/584 586/579/584 596/580/584 +f 580/581/585 579/582/585 581/583/585 +f 579/582/586 580/581/586 582/584/586 +f 580/581/585 581/583/585 583/585/585 +f 583/585/587 581/583/587 584/586/587 +f 582/584/588 578/587/588 584/586/588 +f 578/587/588 582/584/588 585/588/588 +f 580/581/585 583/585/585 586/579/585 +f 581/583/589 579/582/589 587/589/589 +f 579/582/590 582/584/590 587/589/590 +f 578/587/591 583/585/591 588/590/591 +f 583/585/587 584/586/587 588/590/587 +f 584/586/588 578/587/588 588/590/588 +f 583/585/591 578/587/591 589/591/591 +f 586/579/585 583/585/585 589/591/585 +f 582/584/588 584/586/588 590/592/588 +f 587/589/592 590/592/592 591/593/592 +f 584/586/587 581/583/587 591/593/587 +f 581/583/593 587/589/593 591/593/593 +f 590/592/594 584/586/594 591/593/594 +f 578/587/588 585/588/588 592/578/588 +f 585/588/595 586/579/595 592/578/595 +f 587/589/596 582/584/596 593/594/596 +f 582/584/588 590/592/588 593/594/588 +f 590/592/597 587/589/597 593/594/597 +f 582/584/586 580/581/586 594/595/586 +f 580/581/598 585/588/598 594/595/598 +f 585/588/588 582/584/588 594/595/588 +f 585/588/598 580/581/598 595/596/598 +f 580/581/585 586/579/585 595/596/585 +f 586/579/595 585/588/595 595/596/595 +f 589/591/599 578/587/599 596/580/599 +f 586/579/600 589/591/600 596/580/600 +f 578/587/588 592/578/588 596/580/588 +o Cup_hull_25 +v -0.023551 0.007522 0.017006 +v -0.025132 -0.000376 0.032177 +v -0.022760 -0.000376 0.032177 +v -0.020655 -0.000376 0.015037 +v -0.016179 0.008313 0.016444 +v -0.023814 0.008313 0.032177 +v -0.025132 -0.000376 0.017848 +v -0.018023 -0.000376 0.015881 +v -0.020917 0.008313 0.031895 +v -0.020655 0.008313 0.015037 +v -0.024604 0.005941 0.018410 +v -0.016179 0.007785 0.015037 +v -0.025132 0.002520 0.032177 +v -0.023814 0.008313 0.017848 +v -0.022497 -0.000376 0.031895 +v -0.024340 0.001730 0.016724 +v -0.025132 0.002520 0.018410 +v -0.024604 0.005941 0.032177 +v -0.018023 -0.000376 0.015037 +v -0.016179 0.008048 0.016444 +v -0.018549 -0.000376 0.018130 +v -0.020917 0.008048 0.031895 +v -0.021180 0.008313 0.032177 +v -0.024340 0.004362 0.017006 +v -0.024340 -0.000376 0.016724 +v -0.024077 0.007785 0.032177 +v -0.016179 0.008313 0.015037 +v -0.024077 0.007785 0.018410 +v -0.024867 0.004362 0.018130 +v -0.024867 0.001730 0.017286 +vt 0.803211 0.000000 +vt 0.819561 0.029561 +vt 0.868807 0.029561 +vt 0.000000 0.264879 +vt 0.000000 0.000000 +vt 1.000000 0.500000 +vt 0.000000 0.147220 +vt 0.836009 0.000000 +vt 0.950754 0.794048 +vt 0.917956 1.000000 +vt 0.016448 0.470732 +vt 1.000000 0.500000 +vt 1.000000 1.000000 +vt 0.000000 0.000000 +vt 0.836009 0.147220 +vt 0.885158 0.176586 +vt 0.016448 0.294244 +vt 0.901606 0.088391 +vt 0.000000 0.058927 +vt 1.000000 0.794048 +vt 0.917956 1.000000 +vt 0.819561 0.735219 +vt 0.016448 0.470732 +vt 0.000000 0.441366 +vt 0.885158 0.088391 +vt 0.901606 0.088391 +vt 0.000000 0.117756 +vt 0.803211 0.058927 +vt 1.000000 1.000000 +vt 0.803211 0.117756 +vn -0.9527 0.0929 -0.2895 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 1.0000 -0.0000 +vn -0.0000 0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.5764 0.4982 -0.6477 +vn -0.4161 0.0000 -0.9093 +vn 0.9754 -0.2204 0.0000 +vn 0.9561 0.0000 0.2932 +vn 0.9755 -0.2162 0.0405 +vn 1.0000 0.0000 0.0000 +vn 0.9397 -0.2105 0.2695 +vn 0.9492 -0.2226 0.2223 +vn 0.7245 -0.1359 0.6757 +vn 0.9410 -0.1765 0.2886 +vn 0.6667 -0.1212 0.7354 +vn 0.7313 0.0000 0.6820 +vn -0.5831 0.1457 -0.7992 +vn -0.8571 0.2142 -0.4686 +vn -0.5422 0.0895 -0.8355 +vn -0.8946 0.4468 0.0000 +vn -0.9615 0.2747 0.0000 +vn -0.9441 0.2698 -0.1895 +vn -0.9058 0.2155 -0.3647 +vn -0.9898 0.1423 0.0000 +vn -0.9864 0.1642 0.0000 +vn -0.9883 0.1524 0.0014 +vn -0.8860 0.2066 -0.4151 +vn -0.8973 0.1348 -0.4203 +vn -0.9635 0.0510 -0.2626 +vn -0.7278 0.0730 -0.6819 +vn -0.8167 -0.0508 -0.5748 +vn -0.7298 0.0000 -0.6837 +usemtl None +s off +f 613/597/601 625/598/601 626/599/601 +f 599/600/602 598/601/602 600/602/602 +f 598/601/603 599/600/603 602/603/603 +f 600/602/602 598/601/602 603/604/602 +f 599/600/602 600/602/602 604/605/602 +f 601/606/604 602/603/604 605/607/604 +f 602/603/604 601/606/604 606/608/604 +f 600/602/605 606/608/605 608/609/605 +f 598/601/603 602/603/603 609/610/603 +f 603/604/606 598/601/606 609/610/606 +f 602/603/604 606/608/604 610/611/604 +f 606/608/607 597/612/607 610/611/607 +f 599/600/602 604/605/602 611/613/602 +f 606/608/608 600/602/608 612/614/608 +f 603/604/606 609/610/606 613/597/606 +f 609/610/603 602/603/603 614/615/603 +f 604/605/602 600/602/602 615/616/602 +f 600/602/605 608/609/605 615/616/605 +f 608/609/609 604/605/609 615/616/609 +f 601/606/610 605/607/610 616/617/610 +f 604/605/611 608/609/611 616/617/611 +f 608/609/612 601/606/612 616/617/612 +f 616/617/613 611/613/613 617/618/613 +f 611/613/602 604/605/602 617/618/602 +f 604/605/614 616/617/614 617/618/614 +f 599/600/615 611/613/615 618/619/615 +f 616/617/610 605/607/610 618/619/610 +f 611/613/616 616/617/616 618/619/616 +f 602/603/603 599/600/603 619/620/603 +f 605/607/604 602/603/604 619/620/604 +f 599/600/617 618/619/617 619/620/617 +f 618/619/618 605/607/618 619/620/618 +f 597/612/619 606/608/619 620/621/619 +f 610/611/620 597/612/620 620/621/620 +f 606/608/621 612/614/621 620/621/621 +f 600/602/602 603/604/602 621/622/602 +f 612/614/608 600/602/608 621/622/608 +f 602/603/622 610/611/622 622/623/622 +f 614/615/603 602/603/603 622/623/603 +f 607/624/623 614/615/623 622/623/623 +f 606/608/604 601/606/604 623/625/604 +f 601/606/612 608/609/612 623/625/612 +f 608/609/605 606/608/605 623/625/605 +f 610/611/624 607/624/624 624/626/624 +f 622/623/622 610/611/622 624/626/622 +f 607/624/623 622/623/623 624/626/623 +f 607/624/625 610/611/625 625/598/625 +f 613/597/626 609/610/626 625/598/626 +f 614/615/627 607/624/627 625/598/627 +f 609/610/628 614/615/628 625/598/628 +f 610/611/629 620/621/629 625/598/629 +f 625/598/630 620/621/630 626/599/630 +f 603/604/631 613/597/631 626/599/631 +f 620/621/632 612/614/632 626/599/632 +f 621/622/633 603/604/633 626/599/633 +f 612/614/634 621/622/634 626/599/634 +o Cup_hull_26 +v -0.020654 0.014632 0.050164 +v -0.014335 0.020690 0.033584 +v -0.014335 0.017793 0.033584 +v -0.023815 0.008313 0.033584 +v -0.022761 0.008313 0.050164 +v -0.014335 0.019373 0.050164 +v -0.021180 0.008578 0.034149 +v -0.020127 0.015422 0.033584 +v -0.015388 0.020163 0.050164 +v -0.023288 0.009895 0.050164 +v -0.021708 0.013055 0.033584 +v -0.016968 0.018846 0.033584 +v -0.018549 0.017265 0.050164 +v -0.023815 0.008313 0.050164 +v -0.021444 0.008313 0.033584 +v -0.014335 0.020690 0.050164 +v -0.021708 0.013055 0.050164 +v -0.023288 0.009895 0.033584 +v -0.022497 0.008578 0.050164 +v -0.014598 0.020690 0.033584 +v -0.014335 0.017793 0.034430 +v -0.021444 0.008313 0.035272 +v -0.018812 0.017002 0.033584 +v -0.016968 0.018846 0.050164 +v -0.023815 0.008578 0.050164 +v -0.015388 0.020163 0.033584 +v -0.023815 0.008578 0.033584 +v -0.019865 0.015685 0.050164 +v -0.014598 0.020690 0.050164 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.765955 +vt 1.000000 0.000000 +vt 0.000000 0.893598 +vt 0.000000 0.510572 +vt 0.000000 0.000000 +vt 1.000000 0.574393 +vt 0.000000 0.957420 +vt 0.000000 0.127839 +vt 1.000000 0.383124 +vt 1.000000 0.851018 +vt 0.000000 0.723277 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 0.965936 0.021437 +vt 0.000000 0.383124 +vt 1.000000 0.127839 +vt 0.000000 0.021437 +vt 0.949002 0.765955 +vt 0.898199 0.000000 +vt 1.000000 0.702036 +vt 0.000000 0.851018 +vt 0.000000 0.021437 +vt 1.000000 0.957420 +vt 1.000000 0.021437 +vt 0.000000 0.595634 +vn 0.0000 1.0000 0.0000 +vn -0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.7967 -0.5975 -0.0911 +vn -0.8316 0.5553 0.0000 +vn -0.8317 0.5552 0.0000 +vn -0.8944 0.4473 0.0000 +vn 0.8027 -0.5963 0.0000 +vn 0.8012 -0.5966 0.0471 +vn 0.7095 -0.7047 0.0000 +vn 0.7081 -0.7034 0.0626 +vn 0.7958 -0.6018 0.0670 +vn 0.8011 -0.5955 0.0598 +vn -0.7073 0.7070 0.0000 +vn -0.6402 0.7682 0.0000 +vn -0.7071 0.7071 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.9284 0.3716 0.0000 +vn -0.5551 0.8318 0.0000 +vn -0.8000 0.6001 0.0032 +vn 0.0001 0.0000 1.0000 +vn -0.7686 0.6397 0.0020 +vn -0.7684 0.6400 0.0021 +usemtl None +s off +f 642/627/635 646/628/635 655/629/635 +f 628/630/636 629/631/636 630/632/636 +f 629/631/637 628/630/637 632/633/637 +f 627/634/638 631/635/638 632/633/638 +f 628/630/636 630/632/636 634/636/636 +f 627/634/638 632/633/638 635/637/638 +f 631/635/638 627/634/638 636/638/638 +f 634/636/636 630/632/636 637/639/636 +f 628/630/636 634/636/636 638/640/636 +f 627/634/638 635/637/638 639/641/638 +f 630/632/639 631/635/639 640/642/639 +f 631/635/638 636/638/638 640/642/638 +f 630/632/636 629/631/636 641/643/636 +f 631/635/639 630/632/639 641/643/639 +f 629/631/640 633/644/640 641/643/640 +f 632/633/637 628/630/637 642/627/637 +f 635/637/638 632/633/638 642/627/638 +f 627/634/641 634/636/641 643/645/641 +f 636/638/638 627/634/638 643/645/638 +f 634/636/642 637/639/642 643/645/642 +f 637/639/643 636/638/643 643/645/643 +f 637/639/636 630/632/636 644/646/636 +f 636/638/643 637/639/643 644/646/643 +f 632/633/638 631/635/638 645/647/638 +f 628/630/636 638/640/636 646/628/636 +f 642/627/635 628/630/635 646/628/635 +f 629/631/637 632/633/637 647/648/637 +f 633/644/644 629/631/644 647/648/644 +f 633/644/645 647/648/645 648/649/645 +f 631/635/639 641/643/639 648/649/639 +f 641/643/646 633/644/646 648/649/646 +f 645/647/647 631/635/647 648/649/647 +f 632/633/648 645/647/648 648/649/648 +f 647/648/649 632/633/649 648/649/649 +f 638/640/636 634/636/636 649/650/636 +f 649/650/650 639/641/650 650/651/650 +f 635/637/651 638/640/651 650/651/651 +f 639/641/638 635/637/638 650/651/638 +f 638/640/652 649/650/652 650/651/652 +f 630/632/653 640/642/653 651/652/653 +f 640/642/638 636/638/638 651/652/638 +f 636/638/654 644/646/654 651/652/654 +f 638/640/651 635/637/651 652/653/651 +f 646/628/636 638/640/636 652/653/636 +f 635/637/655 646/628/655 652/653/655 +f 644/646/636 630/632/636 653/654/636 +f 630/632/653 651/652/653 653/654/653 +f 651/652/654 644/646/654 653/654/654 +f 634/636/656 627/634/656 654/655/656 +f 627/634/657 639/641/657 654/655/657 +f 649/650/658 634/636/658 654/655/658 +f 639/641/659 649/650/659 654/655/659 +f 635/637/638 642/627/638 655/629/638 +f 646/628/655 635/637/655 655/629/655 +o Cup_hull_27 +v -0.023550 0.008578 0.017568 +v -0.014335 0.020690 0.017848 +v -0.014335 0.020426 0.015039 +v -0.015915 0.008313 0.015882 +v -0.021180 0.008313 0.033582 +v -0.014335 0.020690 0.033582 +v -0.021708 0.013055 0.033582 +v -0.020127 0.015422 0.015039 +v -0.014335 0.017529 0.033301 +v -0.014335 0.010684 0.015039 +v -0.023815 0.008313 0.033582 +v -0.016968 0.018845 0.033582 +v -0.020654 0.008313 0.015039 +v -0.023288 0.009895 0.018411 +v -0.017233 0.018582 0.015039 +v -0.018812 0.017002 0.033582 +v -0.015388 0.020163 0.016724 +v -0.021708 0.013055 0.018411 +v -0.023815 0.008313 0.018411 +v -0.023288 0.009895 0.033582 +v -0.016179 0.008313 0.017005 +v -0.020127 0.015422 0.033582 +v -0.014598 0.020690 0.033582 +v -0.015915 0.008313 0.015039 +v -0.014335 0.010947 0.016443 +v -0.018812 0.017002 0.015039 +v -0.014335 0.017793 0.033582 +v -0.020391 0.014895 0.015039 +v -0.023815 0.008578 0.018411 +v -0.015388 0.020163 0.033582 +v -0.022761 0.008313 0.016724 +v -0.014862 0.020426 0.015039 +v -0.014598 0.020690 0.017848 +v -0.023815 0.008578 0.033582 +vt 0.000000 0.127839 +vt 0.818191 0.021437 +vt 0.000000 0.021437 +vt 1.000000 0.978661 +vt 0.848541 1.000000 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 0.000000 0.383125 +vt 0.015175 0.744616 +vt 1.000000 0.574393 +vt 1.000000 0.191562 +vt 0.954572 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.850920 +vt 1.000000 0.000000 +vt 1.000000 0.829679 +vt 0.000000 0.702036 +vt 0.909144 0.957420 +vt 0.818191 0.383125 +vt 0.818191 0.127839 +vt 0.818191 0.000000 +vt 0.893969 0.000000 +vt 0.000000 0.574393 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.924320 0.212803 +vt 1.000000 0.702036 +vt 0.000000 0.765955 +vt 1.000000 0.531813 +vt 0.863619 0.021437 +vt 0.000000 0.957420 +vt 0.909144 0.000000 +vt 1.000000 0.978661 +vt 0.848541 1.000000 +vn -0.9284 0.3716 0.0000 +vn 1.0000 0.0000 0.0000 +vn -0.0000 0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.7069 0.7073 0.0001 +vn -0.6500 0.7600 -0.0015 +vn -0.8317 0.5552 0.0000 +vn -0.8895 0.4449 -0.1046 +vn -0.8944 0.4473 0.0000 +vn 0.7835 -0.5747 0.2364 +vn -0.7686 0.6397 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.8321 -0.5546 0.0000 +vn 0.8439 -0.5274 0.0988 +vn 0.8227 -0.5347 0.1929 +vn 0.8217 -0.5309 0.2073 +vn -0.7072 0.7070 0.0000 +vn 0.7105 -0.5131 0.4816 +vn -0.8895 0.4448 -0.1047 +vn -0.9014 0.3608 -0.2395 +vn -0.9541 0.0000 -0.2995 +vn -1.0000 0.0000 0.0000 +vn -0.8985 0.3365 -0.2821 +vn -0.6405 0.7679 0.0000 +vn -0.5551 0.8318 0.0000 +vn -0.6501 -0.6421 -0.4063 +vn -0.7153 0.0799 -0.6942 +vn -0.6244 0.0250 -0.7807 +vn 0.0000 0.9956 -0.0936 +vn -0.6125 0.7875 -0.0684 +vn -0.5241 0.8511 -0.0309 +usemtl None +s off +f 675/656/660 684/657/660 689/658/660 +f 658/659/661 657/660/661 661/661/661 +f 660/662/662 661/661/662 662/663/662 +f 658/659/661 661/661/661 664/664/661 +f 663/665/663 658/659/663 665/666/663 +f 658/659/661 664/664/661 665/666/661 +f 659/667/664 660/662/664 666/668/664 +f 660/662/662 662/663/662 666/668/662 +f 662/663/662 661/661/662 667/669/662 +f 663/665/663 665/666/663 668/670/663 +f 659/667/664 666/668/664 668/670/664 +f 658/659/663 663/665/663 670/671/663 +f 667/669/665 670/671/665 671/672/665 +f 662/663/662 667/669/662 671/672/662 +f 670/671/666 667/669/666 672/673/666 +f 662/663/667 663/665/667 673/674/667 +f 663/665/668 669/675/668 673/674/668 +f 669/675/669 662/663/669 673/674/669 +f 668/670/664 666/668/664 674/676/664 +f 666/668/662 662/663/662 675/656/662 +f 662/663/669 669/675/669 675/656/669 +f 660/662/664 659/667/664 676/677/664 +f 664/664/670 660/662/670 676/677/670 +f 663/665/667 662/663/667 677/678/667 +f 662/663/662 671/672/662 677/678/662 +f 671/672/671 663/665/671 677/678/671 +f 661/661/672 657/660/672 678/679/672 +f 667/669/662 661/661/662 678/679/662 +f 665/666/673 659/667/673 679/680/673 +f 668/670/663 665/666/663 679/680/663 +f 659/667/664 668/670/664 679/680/664 +f 659/667/674 665/666/674 680/681/674 +f 665/666/661 664/664/661 680/681/661 +f 676/677/675 659/667/675 680/681/675 +f 664/664/676 676/677/676 680/681/676 +f 670/671/663 663/665/663 681/682/663 +f 671/672/677 670/671/677 681/682/677 +f 663/665/671 671/672/671 681/682/671 +f 661/661/662 660/662/662 682/683/662 +f 660/662/678 664/664/678 682/683/678 +f 664/664/661 661/661/661 682/683/661 +f 663/665/663 668/670/663 683/684/663 +f 669/675/679 663/665/679 683/684/679 +f 669/675/680 683/684/680 684/657/680 +f 656/685/681 674/676/681 684/657/681 +f 674/676/682 666/668/682 684/657/682 +f 675/656/660 669/675/660 684/657/660 +f 683/684/683 656/685/683 684/657/683 +f 672/673/684 667/669/684 685/686/684 +f 667/669/662 678/679/662 685/686/662 +f 678/679/685 672/673/685 685/686/685 +f 674/676/686 656/685/686 686/687/686 +f 668/670/664 674/676/664 686/687/664 +f 656/685/687 683/684/687 686/687/687 +f 683/684/688 668/670/688 686/687/688 +f 657/660/689 658/659/689 687/688/689 +f 658/659/663 670/671/663 687/688/663 +f 670/671/690 672/673/690 687/688/690 +f 678/679/672 657/660/672 688/689/672 +f 672/673/685 678/679/685 688/689/685 +f 657/660/689 687/688/689 688/689/689 +f 687/688/691 672/673/691 688/689/691 +f 666/668/662 675/656/662 689/658/662 +f 684/657/682 666/668/682 689/658/682 +o Cup_hull_28 +v 0.018582 -0.017233 0.015041 +v 0.008313 -0.023815 0.050164 +v 0.008579 -0.023815 0.050164 +v 0.019372 -0.014335 0.050164 +v 0.008313 -0.015916 0.015041 +v 0.008313 -0.023815 0.018414 +v 0.020425 -0.014335 0.015041 +v 0.015421 -0.020128 0.050164 +v 0.010685 -0.014335 0.015041 +v 0.015421 -0.020128 0.015041 +v 0.020689 -0.014598 0.050164 +v 0.008579 -0.022497 0.050164 +v 0.013054 -0.021707 0.018414 +v 0.008313 -0.020653 0.015041 +v 0.018055 -0.017759 0.050164 +v 0.008313 -0.015916 0.015883 +v 0.013056 -0.021707 0.050164 +v 0.009895 -0.023288 0.018132 +v 0.020688 -0.014599 0.017850 +v 0.017002 -0.018812 0.015041 +v 0.009105 -0.023023 0.017008 +v 0.020689 -0.014335 0.050164 +v 0.019898 -0.015651 0.050164 +v 0.009896 -0.023288 0.050164 +v 0.017001 -0.018812 0.050164 +v 0.008313 -0.022760 0.050164 +v 0.019899 -0.015652 0.015041 +v 0.018581 -0.017233 0.050164 +v 0.010948 -0.014335 0.016444 +v 0.008578 -0.023815 0.018414 +v 0.014896 -0.020391 0.015041 +v 0.020688 -0.014335 0.017850 +v 0.008578 -0.023550 0.017568 +vt 1.000000 0.531911 +vt 0.911992 0.127839 +vt 0.928047 0.021437 +vt 0.000000 0.000000 +vt 0.000000 0.021535 +vt 0.000000 0.893598 +vt 1.000000 0.000000 +vt 0.903965 0.000000 +vt 1.000000 0.829777 +vt 1.000000 0.978661 +vt 0.000000 0.574393 +vt 1.000000 0.191660 +vt 1.000000 0.574393 +vt 0.000000 1.000000 +vt 0.000000 0.021535 +vt 1.000000 0.000000 +vt 0.000000 0.787197 +vt 0.976016 0.000000 +vt 0.000000 0.383222 +vt 0.903965 0.383124 +vt 1.000000 0.702134 +vt 0.000000 1.000000 +vt 0.920020 0.999902 +vt 0.000000 0.936081 +vt 0.000000 0.127937 +vt 0.000000 0.702036 +vt 0.000000 0.000000 +vt 1.000000 0.936179 +vt 0.000000 0.829679 +vt 0.960059 0.212901 +vt 0.903965 0.021437 +vt 0.944004 0.064017 +vt 0.920020 0.999902 +vn 0.3165 -0.8917 -0.3237 +vn 0.0000 0.0000 1.0000 +vn -1.0000 -0.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 1.0000 0.0000 +vn -0.5547 0.8321 0.0000 +vn -0.5958 0.7878 0.1559 +vn 0.5550 -0.8318 0.0000 +vn 0.5548 -0.8320 -0.0000 +vn 0.4476 -0.8942 -0.0000 +vn 0.4524 -0.8865 -0.0974 +vn 0.6397 -0.7686 0.0000 +vn 0.7070 -0.7072 0.0000 +vn 1.0000 0.0000 -0.0000 +vn 0.3716 -0.9284 -0.0000 +vn 0.6400 -0.7683 0.0000 +vn 0.7069 -0.7073 0.0000 +vn -0.6949 0.7052 0.1408 +vn 0.9220 -0.3679 -0.1209 +vn 0.8005 -0.5993 -0.0000 +vn 0.7996 -0.6005 0.0000 +vn 0.7684 -0.6399 0.0000 +vn 0.7074 -0.7068 0.0000 +vn 0.7683 -0.6401 0.0000 +vn -0.5306 0.8372 0.1326 +vn -0.5274 0.8438 0.0988 +vn 0.4439 -0.8887 -0.1148 +vn 0.0253 -0.6334 -0.7734 +vn 0.9957 0.0000 -0.0932 +vn -0.8238 -0.4136 -0.3877 +vn -0.1297 -0.6585 -0.7413 +vn 0.0000 -0.9544 -0.2984 +vn 0.3032 -0.9095 -0.2844 +vn 0.1567 -0.7887 -0.5944 +usemtl None +s off +f 720/690/692 707/691/692 722/692/692 +f 691/693/693 692/694/693 693/695/693 +f 691/693/694 694/696/694 695/697/694 +f 692/694/695 691/693/695 695/697/695 +f 690/698/696 694/696/696 696/699/696 +f 693/695/693 692/694/693 697/700/693 +f 693/695/697 696/699/697 698/701/697 +f 696/699/696 694/696/696 698/701/696 +f 694/696/696 690/698/696 699/702/696 +f 693/695/693 697/700/693 700/703/693 +f 691/693/693 693/695/693 701/704/693 +f 695/697/694 694/696/694 703/705/694 +f 694/696/696 699/702/696 703/705/696 +f 700/703/693 697/700/693 704/706/693 +f 694/696/694 691/693/694 705/707/694 +f 698/701/698 694/696/698 705/707/698 +f 701/704/699 693/695/699 705/707/699 +f 697/700/693 692/694/693 706/708/693 +f 699/702/700 697/700/700 706/708/700 +f 702/709/701 699/702/701 706/708/701 +f 702/709/702 706/708/702 707/691/702 +f 699/702/703 702/709/703 707/691/703 +f 699/702/696 690/698/696 709/710/696 +f 697/700/704 699/702/704 709/710/704 +f 690/698/705 704/706/705 709/710/705 +f 696/699/697 693/695/697 711/711/697 +f 693/695/693 700/703/693 711/711/693 +f 700/703/706 708/712/706 711/711/706 +f 700/703/693 704/706/693 712/713/693 +f 706/708/693 692/694/693 713/714/693 +f 707/691/702 706/708/702 713/714/702 +f 692/694/707 707/691/707 713/714/707 +f 704/706/693 697/700/693 714/715/693 +f 697/700/708 709/710/708 714/715/708 +f 709/710/709 704/706/709 714/715/709 +f 691/693/693 701/704/693 715/716/693 +f 705/707/694 691/693/694 715/716/694 +f 701/704/710 705/707/710 715/716/710 +f 690/698/696 696/699/696 716/717/696 +f 696/699/711 708/712/711 716/717/711 +f 708/712/712 700/703/712 716/717/712 +f 700/703/713 712/713/713 716/717/713 +f 716/717/714 712/713/714 717/718/714 +f 704/706/715 690/698/715 717/718/715 +f 712/713/693 704/706/693 717/718/693 +f 690/698/716 716/717/716 717/718/716 +f 693/695/697 698/701/697 718/719/697 +f 705/707/717 693/695/717 718/719/717 +f 698/701/718 705/707/718 718/719/718 +f 692/694/695 695/697/695 719/720/695 +f 707/691/707 692/694/707 719/720/707 +f 703/705/696 699/702/696 720/690/696 +f 699/702/719 707/691/719 720/690/719 +f 710/721/720 703/705/720 720/690/720 +f 708/712/721 696/699/721 721/722/721 +f 696/699/697 711/711/697 721/722/697 +f 711/711/706 708/712/706 721/722/706 +f 695/697/722 703/705/722 722/692/722 +f 703/705/723 710/721/723 722/692/723 +f 719/720/724 695/697/724 722/692/724 +f 707/691/725 719/720/725 722/692/725 +f 710/721/726 720/690/726 722/692/726 +o Cup_hull_29 +v -0.020392 -0.000377 0.015036 +v -0.016441 0.007259 -0.048198 +v -0.016441 0.006732 -0.048198 +v -0.020392 0.007259 -0.048198 +v -0.016441 0.007259 0.015036 +v -0.018022 -0.000377 -0.048198 +v -0.020392 0.007259 0.015036 +v -0.018022 -0.000377 0.015036 +v -0.020392 -0.000377 -0.048198 +v -0.016441 0.006732 0.013624 +vt 0.000000 0.000000 +vt 1.000000 0.930991 +vt 0.022318 0.930991 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vn 0.9762 -0.2170 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.9765 -0.2021 0.0755 +usemtl None +s off +f 730/723/727 725/724/727 732/725/727 +f 724/726/728 725/724/728 726/727/728 +f 725/724/729 724/726/729 727/728/729 +f 724/726/730 726/727/730 727/728/730 +f 726/727/728 725/724/728 728/729/728 +f 726/727/731 723/730/731 729/731/731 +f 723/730/732 727/728/732 729/731/732 +f 727/728/730 726/727/730 729/731/730 +f 727/728/732 723/730/732 730/723/732 +f 728/729/727 725/724/727 730/723/727 +f 723/730/733 728/729/733 730/723/733 +f 723/730/731 726/727/731 731/732/731 +f 726/727/728 728/729/728 731/732/728 +f 728/729/733 723/730/733 731/732/733 +f 725/724/729 727/728/729 732/725/729 +f 727/728/734 730/723/734 732/725/734 +o Cup_hull_30 +v 0.017529 0.018321 0.034429 +v 0.008314 0.022795 0.050166 +v 0.008314 0.023587 0.050166 +v 0.021217 0.013580 0.050166 +v 0.018582 0.013580 0.034429 +v 0.008314 0.021480 0.034429 +v 0.015686 0.019899 0.050166 +v 0.009894 0.023322 0.034429 +v 0.019899 0.013580 0.050166 +v 0.021217 0.013844 0.034429 +v 0.019899 0.015687 0.050166 +v 0.012527 0.022006 0.050166 +v 0.013843 0.021216 0.034429 +v 0.008314 0.023587 0.034429 +v 0.008314 0.021480 0.035553 +v 0.009105 0.023587 0.050166 +v 0.008314 0.022533 0.048477 +v 0.017793 0.018057 0.050166 +v 0.019899 0.015687 0.034429 +v 0.018582 0.013580 0.035553 +v 0.021217 0.013580 0.034429 +v 0.015686 0.019899 0.034429 +v 0.021217 0.013844 0.050166 +v 0.018319 0.017530 0.034429 +v 0.012527 0.022006 0.034429 +v 0.014633 0.020688 0.050166 +v 0.010421 0.023059 0.050166 +v 0.009105 0.023587 0.034429 +v 0.018319 0.017530 0.050166 +v 0.020689 0.014634 0.050166 +vt 0.000000 0.897905 +vt 0.000000 1.000000 +vt 0.000000 0.959084 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 1.000000 0.714174 +vt 1.000000 0.795810 +vt 0.000000 0.571359 +vt 1.000000 0.122455 +vt 0.000000 0.897905 +vt 1.000000 1.000000 +vt 0.000000 0.326547 +vt 1.000000 0.428543 +vt 1.000000 0.000000 +vt 0.928543 0.000000 +vt 0.000000 0.061276 +vt 0.107283 0.000000 +vt 0.000000 0.734632 +vt 1.000000 0.897905 +vt 0.928543 0.795810 +vt 1.000000 1.000000 +vt 1.000000 0.571359 +vt 1.000000 0.775450 +vt 1.000000 0.326547 +vt 0.000000 0.489722 +vt 0.000000 0.163273 +vt 1.000000 0.061276 +vt 0.000000 0.775450 +vn 0.0001 0.0000 1.0000 +vn 0.0000 0.0000 1.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.6098 -0.7926 0.0000 +vn 0.0000 1.0000 0.0000 +vn -0.6179 -0.7769 0.1208 +vn -0.6160 -0.7851 0.0640 +vn 0.6581 0.7529 0.0016 +vn -0.6089 -0.7914 0.0549 +vn 1.0000 0.0000 0.0000 +vn 0.6504 0.7596 0.0000 +vn 0.7070 0.7072 -0.0000 +vn 0.7593 0.6508 0.0000 +vn 0.4472 0.8945 0.0000 +vn 0.5144 0.8575 0.0000 +vn 0.5305 0.8477 0.0018 +vn 0.5997 0.8002 0.0000 +vn 0.5816 0.8135 -0.0019 +vn 0.4471 0.8945 0.0000 +vn 0.3723 0.9281 0.0031 +vn 0.3177 0.9482 0.0000 +vn 0.7073 0.7069 0.0000 +vn 0.8001 0.5998 0.0000 +vn 0.8136 0.5814 -0.0019 +vn 0.8316 0.5554 0.0000 +usemtl None +s off +f 743/733/735 755/734/735 762/735/735 +f 735/736/736 734/737/736 736/738/736 +f 734/737/737 735/736/737 738/739/737 +f 733/740/738 737/741/738 738/739/738 +f 735/736/736 736/738/736 739/742/736 +f 733/740/738 738/739/738 740/743/738 +f 736/738/736 734/737/736 741/744/736 +f 737/741/739 736/738/739 741/744/739 +f 737/741/738 733/740/738 742/745/738 +f 739/742/736 736/738/736 743/733/736 +f 735/736/736 739/742/736 744/746/736 +f 733/740/738 740/743/738 745/747/738 +f 738/739/737 735/736/737 746/748/737 +f 740/743/738 738/739/738 746/748/738 +f 734/737/737 738/739/737 747/749/737 +f 738/739/740 737/741/740 747/749/740 +f 735/736/736 744/746/736 748/750/736 +f 746/748/741 735/736/741 748/750/741 +f 741/744/742 734/737/742 749/751/742 +f 734/737/737 747/749/737 749/751/737 +f 747/749/743 741/744/743 749/751/743 +f 733/740/744 739/742/744 750/752/744 +f 739/742/736 743/733/736 750/752/736 +f 742/745/738 733/740/738 751/753/738 +f 737/741/739 741/744/739 752/754/739 +f 747/749/740 737/741/740 752/754/740 +f 741/744/745 747/749/745 752/754/745 +f 736/738/739 737/741/739 753/755/739 +f 742/745/746 736/738/746 753/755/746 +f 737/741/738 742/745/738 753/755/738 +f 739/742/747 733/740/747 754/756/747 +f 733/740/738 745/747/738 754/756/738 +f 736/738/746 742/745/746 755/734/746 +f 743/733/736 736/738/736 755/734/736 +f 733/740/748 750/752/748 756/757/748 +f 743/733/749 751/753/749 756/757/749 +f 751/753/738 733/740/738 756/757/738 +f 740/743/750 744/746/750 757/758/750 +f 745/747/738 740/743/738 757/758/738 +f 744/746/751 745/747/751 757/758/751 +f 744/746/736 739/742/736 758/759/736 +f 745/747/752 744/746/752 758/759/752 +f 739/742/753 754/756/753 758/759/753 +f 754/756/754 745/747/754 758/759/754 +f 744/746/755 740/743/755 759/760/755 +f 748/750/736 744/746/736 759/760/736 +f 740/743/756 748/750/756 759/760/756 +f 740/743/738 746/748/738 760/761/738 +f 748/750/757 740/743/757 760/761/757 +f 746/748/741 748/750/741 760/761/741 +f 750/752/736 743/733/736 761/762/736 +f 756/757/758 750/752/758 761/762/758 +f 743/733/749 756/757/749 761/762/749 +f 751/753/759 743/733/759 762/735/759 +f 742/745/760 751/753/760 762/735/760 +f 755/734/761 742/745/761 762/735/761 +o Cup_hull_31 +v 0.019899 0.015687 0.015038 +v 0.008313 0.021479 0.034427 +v 0.008313 0.023586 0.034427 +v 0.021215 0.013581 0.034427 +v 0.008577 0.015687 0.015038 +v 0.008313 0.023586 0.017568 +v 0.014633 0.020689 0.034427 +v 0.012262 0.013581 0.017568 +v 0.014896 0.020425 0.015038 +v 0.020425 0.013581 0.015038 +v 0.018319 0.013581 0.034143 +v 0.018319 0.017531 0.034427 +v 0.010421 0.023059 0.018129 +v 0.008313 0.020425 0.015038 +v 0.008313 0.016214 0.017006 +v 0.009894 0.023322 0.034427 +v 0.011737 0.013581 0.015038 +v 0.017793 0.018057 0.015038 +v 0.021215 0.013844 0.018410 +v 0.020689 0.014634 0.034427 +v 0.012526 0.022005 0.018129 +v 0.008313 0.021215 0.033862 +v 0.015685 0.019899 0.034427 +v 0.012526 0.022005 0.034427 +v 0.009104 0.023586 0.018129 +v 0.015686 0.019899 0.015038 +v 0.018583 0.013581 0.034427 +v 0.013844 0.021215 0.018410 +v 0.017529 0.018320 0.034427 +v 0.008841 0.022795 0.016725 +v 0.019899 0.015687 0.034427 +v 0.009104 0.023586 0.034427 +v 0.021215 0.013581 0.018410 +v 0.018319 0.017531 0.015038 +v 0.020425 0.014897 0.015038 +v 0.008313 0.015951 0.015038 +v 0.021215 0.013844 0.034427 +vt 0.826057 1.000000 +vt 0.000000 0.959275 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 0.869518 0.000000 +vt 0.000000 0.489868 +vt 1.000000 0.897993 +vt 1.000000 0.020460 +vt 1.000000 0.510230 +vt 1.000000 0.938815 +vt 0.869518 0.306118 +vt 0.014683 0.775526 +vt 0.000000 0.775526 +vt 1.000000 0.000000 +vt 0.898493 0.000000 +vt 0.000000 0.122565 +vt 1.000000 0.265394 +vt 1.000000 0.734802 +vt 0.840544 0.163387 +vt 0.840544 0.326579 +vt 0.029170 0.000000 +vt 0.000000 0.571415 +vt 0.000000 0.326579 +vt 0.840544 0.061282 +vt 1.000000 0.571512 +vt 0.000000 0.795986 +vt 0.826057 0.428683 +vt 0.000000 0.714342 +vt 0.912980 0.040920 +vt 0.000000 0.897993 +vt 0.000000 0.061282 +vt 0.826057 1.000000 +vt 1.000000 0.775526 +vt 1.000000 0.938815 +vt 1.000000 0.000000 +vn 0.8325 0.5541 0.0000 +vn 0.0000 0.0000 1.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.5631 -0.8140 0.1424 +vn -0.5630 -0.8004 0.2057 +vn -0.5511 -0.8266 0.1144 +vn 0.8154 0.5789 -0.0018 +vn 0.4447 0.8885 -0.1132 +vn -0.5754 -0.7414 0.3454 +vn -0.5946 -0.7708 0.2287 +vn 0.4476 0.8943 0.0000 +vn 0.4476 0.8942 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.2744 0.8807 -0.3862 +vn 0.3600 0.9000 -0.2456 +vn 0.3714 0.9285 -0.0030 +vn 0.6002 0.7999 0.0000 +vn -0.5307 -0.6901 0.4921 +vn 0.5196 0.8536 -0.0379 +vn 0.5299 0.8481 0.0018 +vn 0.5140 0.8578 0.0000 +vn 0.5792 0.8152 -0.0017 +vn 0.5537 0.8324 -0.0223 +vn 0.7071 0.7071 0.0000 +vn 0.6583 0.7528 -0.0013 +vn 0.6504 0.7596 0.0000 +vn 0.1198 0.7605 -0.6382 +vn -0.2966 0.5968 -0.7456 +vn 0.0000 0.5799 -0.8147 +vn 0.7592 0.6508 0.0000 +vn 0.7999 0.6001 0.0000 +vn 0.0001 0.0000 1.0000 +vn 0.3161 0.9487 0.0000 +vn 0.9737 0.0000 -0.2279 +vn 1.0000 0.0000 0.0000 +vn 0.7075 0.7067 0.0000 +vn 0.8320 0.5544 -0.0217 +vn -0.7033 -0.7046 0.0943 +usemtl None +s off +f 781/763/762 782/764/762 799/765/762 +f 765/766/763 764/767/763 766/768/763 +f 764/767/764 765/766/764 768/769/764 +f 765/766/763 766/768/763 769/770/763 +f 763/771/765 767/772/765 771/773/765 +f 767/772/765 763/771/765 772/774/765 +f 766/768/766 770/775/766 772/774/766 +f 770/775/766 766/768/766 773/776/766 +f 769/770/763 766/768/763 774/777/763 +f 764/767/764 768/769/764 776/778/764 +f 771/773/765 767/772/765 776/778/765 +f 767/772/767 770/775/767 777/779/767 +f 770/775/768 773/776/768 777/779/768 +f 764/767/764 776/778/764 777/779/764 +f 765/766/763 769/770/763 778/780/763 +f 770/775/769 767/772/769 779/781/769 +f 767/772/765 772/774/765 779/781/765 +f 772/774/766 770/775/766 779/781/766 +f 763/771/765 771/773/765 780/782/765 +f 774/777/763 766/768/763 782/764/763 +f 781/763/770 763/771/770 782/764/770 +f 771/773/771 775/783/771 783/784/771 +f 773/776/772 764/767/772 784/785/772 +f 764/767/764 777/779/764 784/785/764 +f 777/779/773 773/776/773 784/785/773 +f 769/770/763 774/777/763 785/786/763 +f 778/780/763 769/770/763 786/787/763 +f 775/783/774 778/780/774 786/787/774 +f 783/784/775 775/783/775 786/787/775 +f 768/769/776 765/766/776 787/788/776 +f 771/773/777 768/769/777 787/788/777 +f 775/783/778 771/773/778 787/788/778 +f 778/780/779 775/783/779 787/788/779 +f 780/782/765 771/773/765 788/789/765 +f 769/770/780 785/786/780 788/789/780 +f 766/768/763 764/767/763 789/790/763 +f 764/767/781 773/776/781 789/790/781 +f 773/776/766 766/768/766 789/790/766 +f 771/773/782 783/784/782 790/791/782 +f 786/787/783 769/770/783 790/791/783 +f 783/784/784 786/787/784 790/791/784 +f 769/770/785 788/789/785 790/791/785 +f 788/789/786 771/773/786 790/791/786 +f 774/777/787 780/782/787 791/792/787 +f 785/786/763 774/777/763 791/792/763 +f 780/782/788 788/789/788 791/792/788 +f 788/789/789 785/786/789 791/792/789 +f 768/769/790 771/773/790 792/793/790 +f 776/778/791 768/769/791 792/793/791 +f 771/773/792 776/778/792 792/793/792 +f 763/771/793 774/777/793 793/794/793 +f 782/764/794 763/771/794 793/794/794 +f 774/777/795 782/764/795 793/794/795 +f 765/766/763 778/780/763 794/795/763 +f 787/788/776 765/766/776 794/795/776 +f 778/780/796 787/788/796 794/795/796 +f 766/768/766 772/774/766 795/796/766 +f 772/774/797 781/763/797 795/796/797 +f 781/763/798 766/768/798 795/796/798 +f 774/777/793 763/771/793 796/797/793 +f 763/771/765 780/782/765 796/797/765 +f 780/782/799 774/777/799 796/797/799 +f 772/774/765 763/771/765 797/798/765 +f 763/771/800 781/763/800 797/798/800 +f 781/763/797 772/774/797 797/798/797 +f 776/778/765 767/772/765 798/799/765 +f 767/772/801 777/779/801 798/799/801 +f 777/779/764 776/778/764 798/799/764 +f 766/768/798 781/763/798 799/765/798 +f 782/764/763 766/768/763 799/765/763 +o Cup_hull_32 +v 0.004626 -0.019601 -0.043977 +v -0.002221 -0.020391 0.015036 +v 0.001203 -0.020392 -0.005762 +v 0.004626 -0.017495 0.015036 +v -0.002221 -0.017758 -0.048198 +v -0.002221 -0.020391 -0.048198 +v -0.002221 -0.017758 0.014751 +v 0.004626 -0.020392 0.015036 +v 0.004625 -0.017495 -0.048198 +v 0.004625 -0.020392 -0.048198 +v 0.003308 -0.017495 0.013624 +v 0.003308 -0.017495 -0.048198 +v -0.002221 -0.018022 0.015036 +vt 0.000000 1.000000 +vt 0.004503 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 1.000000 0.000000 +vt 0.328896 0.500000 +vt 0.000000 1.000000 +vt 0.933242 1.000000 +vt 1.000000 0.999902 +vt 1.000000 0.999902 +vt 0.022318 0.807557 +vt 1.000000 0.807557 +vn -0.0564 0.7329 0.6780 +vn -1.0000 0.0000 0.0000 +vn -0.0001 -1.0000 0.0000 +vn -0.0000 -1.0000 0.0000 +vn -0.0000 0.0000 1.0000 +vn 1.0000 0.0000 0.0000 +vn 1.0000 0.0003 -0.0000 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 -0.0008 -0.0000 +vn 1.0000 0.0000 -0.0002 +vn -0.0399 0.9985 0.0373 +vn -0.0475 0.9989 0.0000 +vn 0.0000 1.0000 0.0000 +usemtl None +s off +f 803/800/802 806/801/802 812/802/802 +f 801/803/803 804/804/803 805/805/803 +f 802/806/804 801/803/804 805/805/804 +f 804/804/803 801/803/803 806/801/803 +f 801/803/805 802/806/805 807/807/805 +f 803/800/806 801/803/806 807/807/806 +f 800/808/807 803/800/807 807/807/807 +f 803/800/808 800/808/808 808/809/808 +f 805/805/809 804/804/809 808/809/809 +f 802/806/805 805/805/805 809/810/805 +f 807/807/805 802/806/805 809/810/805 +f 800/808/810 807/807/810 809/810/810 +f 808/809/811 800/808/811 809/810/811 +f 805/805/809 808/809/809 809/810/809 +f 806/801/812 803/800/812 810/811/812 +f 804/804/813 806/801/813 810/811/813 +f 803/800/814 808/809/814 810/811/814 +f 810/811/814 808/809/814 811/812/814 +f 808/809/809 804/804/809 811/812/809 +f 804/804/813 810/811/813 811/812/813 +f 801/803/806 803/800/806 812/802/806 +f 806/801/803 801/803/803 812/802/803 +o Cup_hull_33 +v 0.011736 -0.013546 -0.048198 +v 0.004626 -0.020391 0.015036 +v 0.007524 -0.020392 0.007726 +v 0.012262 -0.013282 0.015036 +v 0.012263 -0.020392 -0.048192 +v 0.004626 -0.017231 -0.048198 +v 0.012262 -0.020392 0.015036 +v 0.004626 -0.020391 -0.048198 +v 0.004626 -0.017231 0.014751 +v 0.011999 -0.013282 -0.048192 +v 0.012263 -0.013282 -0.048192 +v 0.011473 -0.013546 0.008289 +v 0.011999 -0.013282 0.015036 +v 0.011473 -0.013546 -0.043420 +v 0.004890 -0.017231 0.015036 +vt 0.000000 0.965446 +vt 0.004503 0.000000 +vt 0.000000 0.034554 +vt 0.000000 0.000000 +vt 0.115603 0.379405 +vt 0.000000 0.999902 +vt 0.000000 0.999902 +vt 0.999902 1.000000 +vt 1.000000 0.000000 +vt 1.000000 0.930991 +vt 1.000000 0.000000 +vt 0.999902 0.965446 +vt 0.999902 1.000000 +vt 0.106695 0.896535 +vt 0.924432 0.896535 +vn -0.4428 0.7971 0.4104 +vn -0.0001 -1.0000 0.0001 +vn 0.0000 0.0000 1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.0002 -1.0000 0.0000 +vn 0.0008 -0.0008 -1.0000 +vn -0.0001 -1.0000 -0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.0000 0.0000 -1.0000 +vn -0.0252 0.0485 -0.9985 +vn 0.0000 1.0000 -0.0000 +vn 0.0118 0.0000 -0.9999 +vn 0.0000 0.0235 -0.9997 +vn -0.4740 0.8805 0.0000 +vn -0.4481 0.8940 0.0000 +vn -0.4722 0.8815 0.0024 +vn -0.4722 0.8815 -0.0034 +vn -0.7321 0.0611 0.6785 +usemtl None +s off +f 825/813/815 821/814/815 827/815/815 +f 814/816/816 815/817/816 819/818/816 +f 816/819/817 814/816/817 819/818/817 +f 817/820/818 816/819/818 819/818/818 +f 815/817/819 817/820/819 819/818/819 +f 815/817/820 814/816/820 820/821/820 +f 813/822/821 817/820/821 820/821/821 +f 817/820/822 815/817/822 820/821/822 +f 814/816/823 818/823/823 820/821/823 +f 818/823/824 813/822/824 820/821/824 +f 818/823/823 814/816/823 821/814/823 +f 813/822/825 818/823/825 822/824/825 +f 822/824/826 816/819/826 823/825/826 +f 817/820/827 813/822/827 823/825/827 +f 816/819/818 817/820/818 823/825/818 +f 813/822/828 822/824/828 823/825/828 +f 818/823/829 821/814/829 824/826/829 +f 822/824/830 824/826/830 825/813/830 +f 814/816/817 816/819/817 825/813/817 +f 816/819/826 822/824/826 825/813/826 +f 824/826/831 821/814/831 825/813/831 +f 822/824/832 818/823/832 826/827/832 +f 818/823/829 824/826/829 826/827/829 +f 824/826/830 822/824/830 826/827/830 +f 821/814/833 814/816/833 827/815/833 +f 814/816/817 825/813/817 827/815/817 diff --git a/cram_pr2/cram_pr2_pick_place_demo/resource/fork.dae b/cram_demos/cram_pr2_pick_place_demo/resource/fork.dae similarity index 100% rename from cram_pr2/cram_pr2_pick_place_demo/resource/fork.dae rename to cram_demos/cram_pr2_pick_place_demo/resource/fork.dae diff --git a/cram_boxy/cram_boxy_assembly_demo/resource/knife.dae b/cram_demos/cram_pr2_pick_place_demo/resource/knife.dae similarity index 100% rename from cram_boxy/cram_boxy_assembly_demo/resource/knife.dae rename to cram_demos/cram_pr2_pick_place_demo/resource/knife.dae diff --git a/cram_boxy/cram_boxy_assembly_demo/resource/milk.dae b/cram_demos/cram_pr2_pick_place_demo/resource/milk.dae similarity index 100% rename from cram_boxy/cram_boxy_assembly_demo/resource/milk.dae rename to cram_demos/cram_pr2_pick_place_demo/resource/milk.dae diff --git a/cram_boxy/cram_boxy_assembly_demo/resource/milk.stl b/cram_demos/cram_pr2_pick_place_demo/resource/milk.stl similarity index 100% rename from cram_boxy/cram_boxy_assembly_demo/resource/milk.stl rename to cram_demos/cram_pr2_pick_place_demo/resource/milk.stl diff --git a/cram_boxy/cram_boxy_assembly_demo/resource/red_metal_plate.stl b/cram_demos/cram_pr2_pick_place_demo/resource/red_metal_plate.stl similarity index 100% rename from cram_boxy/cram_boxy_assembly_demo/resource/red_metal_plate.stl rename to cram_demos/cram_pr2_pick_place_demo/resource/red_metal_plate.stl diff --git a/cram_boxy/cram_boxy_assembly_demo/resource/spoon.dae b/cram_demos/cram_pr2_pick_place_demo/resource/spoon.dae similarity index 100% rename from cram_boxy/cram_boxy_assembly_demo/resource/spoon.dae rename to cram_demos/cram_pr2_pick_place_demo/resource/spoon.dae diff --git a/cram_boxy/cram_boxy_assembly_demo/resource/spoon.stl b/cram_demos/cram_pr2_pick_place_demo/resource/spoon.stl similarity index 100% rename from cram_boxy/cram_boxy_assembly_demo/resource/spoon.stl rename to cram_demos/cram_pr2_pick_place_demo/resource/spoon.stl diff --git a/cram_pr2/cram_pr2_pick_place_demo/resource/tray-base.stl b/cram_demos/cram_pr2_pick_place_demo/resource/tray-base.stl similarity index 100% rename from cram_pr2/cram_pr2_pick_place_demo/resource/tray-base.stl rename to cram_demos/cram_pr2_pick_place_demo/resource/tray-base.stl diff --git a/cram_pr2/cram_pr2_pick_place_demo/resource/tray.stl b/cram_demos/cram_pr2_pick_place_demo/resource/tray.stl similarity index 100% rename from cram_pr2/cram_pr2_pick_place_demo/resource/tray.stl rename to cram_demos/cram_pr2_pick_place_demo/resource/tray.stl diff --git a/cram_demos/cram_pr2_pick_place_demo/src/costmaps.lisp b/cram_demos/cram_pr2_pick_place_demo/src/costmaps.lisp new file mode 100644 index 0000000000..42092c9286 --- /dev/null +++ b/cram_demos/cram_pr2_pick_place_demo/src/costmaps.lisp @@ -0,0 +1,70 @@ +;;; +;;; Copyright (c) 2017, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Intelligent Autonomous Systems Group/ +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software +;;; without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :demo) + +(defun make-restricted-area-cost-function () + (lambda (x y) + (if (> x 1.2) + 0.0 + (if (and (> x 0.5) (> y -1.5) (< y 2.0)) + 1.0 + (if (and (> x 0.0) (> y -1.5) (< y 1.0)) + 1.0 + (if (and (> x -1.5) (> y -1.5) (< y 2.5)) + 1.0 + (if (and (> x -4.0) (> y -1.0) (< y 1.0)) + 1.0 + 0.0))))))) + +(defmethod location-costmap:costmap-generator-name->score ((name (eql 'restricted-area))) 5) + +(def-fact-group demo-costmap (location-costmap:desig-costmap) + (<- (location-costmap:desig-costmap ?designator ?costmap) + (or (rob-int:visibility-designator ?designator) + (rob-int:reachability-designator ?designator)) + ;; make sure that the location is not on the robot itself + ;; if it is, don't generate a costmap + (once (or (and (desig:desig-prop ?designator (:object ?some-object)) + (desig:current-designator ?some-object ?object) + (lisp-fun man-int:get-object-pose-in-map ?object ?to-reach-pose) + (lisp-pred identity ?to-reach-pose) + (-> (desig:desig-prop ?object (:location ?loc)) + (not (man-int:location-always-reachable ?loc)) + (true))) + (and (desig:desig-prop ?designator (:location ?some-location)) + (desig:current-designator ?some-location ?location) + ;; if the location is on the robot itself, + ;; don't use the costmap + (not (man-int:location-always-reachable ?location))))) + (location-costmap:costmap ?costmap) + (location-costmap:costmap-add-function + restricted-area + (make-restricted-area-cost-function) + ?costmap))) diff --git a/cram_pr2/cram_pr2_pick_place_demo/src/data-generation-plan.lisp b/cram_demos/cram_pr2_pick_place_demo/src/data-generation-plan.lisp similarity index 96% rename from cram_pr2/cram_pr2_pick_place_demo/src/data-generation-plan.lisp rename to cram_demos/cram_pr2_pick_place_demo/src/data-generation-plan.lisp index bef2f334e5..d7b28f79bc 100644 --- a/cram_pr2/cram_pr2_pick_place_demo/src/data-generation-plan.lisp +++ b/cram_demos/cram_pr2_pick_place_demo/src/data-generation-plan.lisp @@ -78,7 +78,7 @@ "kitchen_sink_block_counter_top") (part-of kitchen))))) - :z-offset z/2) + :z z/2) :orientation orientation))) (setf (btr:pose btr-object) pose-for-grasping)))) objects) @@ -121,7 +121,7 @@ (type counter-top) (urdf-name sink-area-surface) (owl-name "kitchen_sink_block_counter_top") - (part-of kitchen))) + (part-of iai-kitchen))) (for ?object))) (?second-location (desig:a location @@ -130,7 +130,7 @@ (type counter-top) (urdf-name kitchen-island) (owl-name "kitchen_island_counter_top") - (part-of kitchen))) + (part-of iai-kitchen))) (for ?object)))) (exe:perform (desig:an action @@ -142,9 +142,7 @@ (arm ?arm-to-use))) (exe:perform (desig:an action - (type positioning-arm) - (left-configuration park) - (right-configuration park))) + (type parking-arms))) (btr:simulate btr:*current-bullet-world* 100) (let ((?new-object (exe:perform (desig:an action diff --git a/cram_pr2/cram_pr2_pick_place_demo/src/data-generation-script.lisp b/cram_demos/cram_pr2_pick_place_demo/src/data-generation-script.lisp similarity index 97% rename from cram_pr2/cram_pr2_pick_place_demo/src/data-generation-script.lisp rename to cram_demos/cram_pr2_pick_place_demo/src/data-generation-script.lisp index 3e9ba2299d..82367eef68 100644 --- a/cram_pr2/cram_pr2_pick_place_demo/src/data-generation-script.lisp +++ b/cram_demos/cram_pr2_pick_place_demo/src/data-generation-script.lisp @@ -41,9 +41,7 @@ (exe:perform (desig:an action - (type positioning-arm) - (left-configuration park) - (right-configuration park))) + (type parking-arms))) (let ((?pose (cl-transforms-stamped:make-pose-stamped "map" 0.0 @@ -173,9 +171,7 @@ -0.75 1.0 (+ 0.8573 z/2))))))) (exe:perform (desig:an action - (type positioning-arm) - (left-configuration park) - (right-configuration park))) + (type parking-arms))) (exe:perform (desig:a motion (type moving-torso) diff --git a/cram_demos/cram_pr2_pick_place_demo/src/demo.lisp b/cram_demos/cram_pr2_pick_place_demo/src/demo.lisp new file mode 100644 index 0000000000..054bac70ec --- /dev/null +++ b/cram_demos/cram_pr2_pick_place_demo/src/demo.lisp @@ -0,0 +1,194 @@ +;;; +;;; Copyright (c) 2017, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Intelligent Autonomous Systems Group/ +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software +;;; without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :demo) + +(defparameter *object-cad-models* + '(;; (:cup . "cup_eco_orange") + ;; (:bowl . "edeka_red_bowl") + )) + +(defparameter *object-colors* + '(;; (:spoon . "Black") + ;; (:spoon . "Blue") + ;; (:breakfast-cereal . "Yellow") + ;; (:milk . "Blue") + (:bowl . "Red") + (:cup . "Red"))) + +(defparameter *object-materials* + '((:spoon . "Steel"))) + +(defparameter *object-grasps* + '((:spoon . :top) + (:breakfast-cereal . :front) + (:milk . :front) + (:cup . :top) + (:bowl . :top))) + +(defun park-robot () + (cpl:with-failure-handling + ((cpl:plan-failure (e) + (declare (ignore e)) + (return))) + (exe:perform + (desig:an action + (type moving-torso) + (joint-angle upper-limit))) + (cpl:par + (exe:perform + (desig:an action + (type positioning-arm) + (left-configuration park) + (right-configuration park))) + (exe:perform (desig:an action (type opening-gripper) (gripper (left right)))) + (exe:perform (desig:an action (type looking) (direction forward)))) + (let ((?pose (cl-transforms-stamped:make-pose-stamped + cram-tf:*fixed-frame* + 0.0 + (cl-transforms:make-identity-vector) + (cl-transforms:make-identity-rotation)))) + (exe:perform + (desig:an action + (type going) + (target (desig:a location (pose ?pose)))))))) + +(defun start-logging () + (setf ccl::*is-logging-enabled* t) + (ccl::init-logging) + (ccl::start-episode)) + +(defun initialize () + (sb-ext:gc :full t) + + ;; (setf proj-reasoning::*projection-checks-enabled* t) + + (btr:detach-all-objects (btr:get-robot-object)) + (btr:detach-all-objects (btr:get-environment-object)) + (btr-utils:kill-all-objects) + (setf (btr:joint-state (btr:get-environment-object) + "sink_area_left_upper_drawer_main_joint") + 0.0 + (btr:joint-state (btr:get-environment-object) + "sink_area_left_middle_drawer_main_joint") + 0.0 + (btr:joint-state (btr:get-environment-object) + "sink_area_left_bottom_drawer_main_joint") + 0.0 + (btr:joint-state (btr:get-environment-object) + "iai_fridge_door_joint") + 0.0 + (btr:joint-state (btr:get-environment-object) + "sink_area_dish_washer_door_joint") + 0.0 + (btr:joint-state (btr:get-environment-object) + "sink_area_dish_washer_tray_main") + 0.0 + (btr:joint-state (btr:get-environment-object) + "oven_area_area_right_drawer_main_joint") + 0.0 + (btr:joint-state (btr:get-environment-object) + "sink_area_trash_drawer_main_joint") + 0.0 + (btr:joint-state (btr:get-environment-object) + "kitchen_island_left_upper_drawer_main_joint") + 0.0) + (btr-belief::publish-environment-joint-state + (btr:joint-states (btr:get-environment-object))) + + (setf desig::*designators* (tg:make-weak-hash-table :weakness :key)) + + (coe:clear-belief) + + (btr:clear-costmap-vis-object)) + +(defun finalize () + ;; (setf proj-reasoning::*projection-reasoning-enabled* nil) + + (sb-ext:gc :full t)) + +(defun stop-logging () + (ccl::stop-episode)) + + +(cpl:def-cram-function demo-random (&optional + (random + nil) + (list-of-objects + '(:bowl :spoon :cup :milk :breakfast-cereal))) + + (initialize) + (when cram-projection:*projection-environment* + (spawn-objects-on-sink-counter :random random)) + + (park-robot) + + (dolist (?object-type list-of-objects) + (let* ((?arm-to-use + (cdr (assoc ?object-type *object-grasping-arms*))) + (?cad-model + (cdr (assoc ?object-type *object-cad-models*))) + (?color + (cdr (assoc ?object-type *object-colors*))) + (?material + (cdr (assoc ?object-type *object-materials*))) + (?object-to-fetch + (desig:an object + (type ?object-type) + (desig:when ?cad-model + (cad-model ?cad-model)) + (desig:when ?color + (color ?color)) + (desig:when ?material + (material ?material))))) + + (cpl:with-failure-handling + ((common-fail:high-level-failure (e) + (roslisp:ros-warn (pp-plans demo) "Failure happened: ~a~%Skipping..." e) + (return))) + + (exe:perform + (desig:an action + (type transporting) + (context table-setting-counter) + (object ?object-to-fetch) + ;; (desig:when ?arm-to-use + ;; (arms (?arm-to-use))) + ))) + + ;; (setf proj-reasoning::*projection-reasoning-enabled* nil) + )) + + ;; (setf proj-reasoning::*projection-reasoning-enabled* nil) + + (park-robot) + + (finalize) + + cpl:*current-path*) diff --git a/cram_pr2/cram_pr2_pick_place_demo/src/evaluation-plan.lisp b/cram_demos/cram_pr2_pick_place_demo/src/evaluation-plan.lisp similarity index 100% rename from cram_pr2/cram_pr2_pick_place_demo/src/evaluation-plan.lisp rename to cram_demos/cram_pr2_pick_place_demo/src/evaluation-plan.lisp diff --git a/cram_demos/cram_pr2_pick_place_demo/src/milestone-projection-demo.lisp b/cram_demos/cram_pr2_pick_place_demo/src/milestone-projection-demo.lisp new file mode 100644 index 0000000000..e760791a8f --- /dev/null +++ b/cram_demos/cram_pr2_pick_place_demo/src/milestone-projection-demo.lisp @@ -0,0 +1,214 @@ +;;; +;;; Copyright (c) 2017, Gayane Kazhoyan +;;; Amar Fayaz +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Intelligent Autonomous Systems Group/ +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software +;;; without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :demo) + +(defparameter *demo-object-spawning-poses* + '((:bowl + "sink_area_left_middle_drawer_main" + ((0.10 -0.1505 -0.062256) (0 0 -1 0))) + ;; (:cup + ;; "sink_area_left_bottom_drawer_main" + ;; ((0.11 0.12 -0.0547167) (0 0 -1 0))) + (:cup + "kitchen_island_left_upper_drawer_main" + ((0.11 0.08 -0.0547167) (0 0 -1 0))) + (:spoon + ;; "oven_area_area_middle_upper_drawer_main" + "sink_area_left_upper_drawer_main" + ((0.125 0 -0.0136) (0 -0.053938 -0.998538 -0.003418))) + ;; So far only this orientation works + (:breakfast-cereal + "oven_area_area_right_drawer_board_3_link" + ((0.123 -0.03 0.11) (0.0087786 0.005395 -0.838767 -0.544393))) + ;; ((:breakfast-cereal . ((1.398 1.490 1.2558) (0 0 0.7071 0.7071))) + ;; (:breakfast-cereal . ((1.1 1.49 1.25) (0 0 0.7071 0.7071))) + (:milk + ;; "iai_fridge_main_middle_level" + ;; ((0.10355 0.022 0.094) (0.00939 -0.00636 -0.96978 -0.2437)) + "iai_fridge_door_shelf1_bottom" + ((-0.01 -0.05 0.094) (0 0 0 1))))) + + +(defparameter *delivery-poses-relative* + `((:bowl + "kitchen_island_surface" + ((0.24 -0.5 0.0432199478149414d0) + (0.0 0.0 0.33465 0.94234))) + (:cup + "kitchen_island_surface" + ((0.21 -0.20 0.06) + (0.0 0.0 0.33465 0.94234))) + (:spoon + "kitchen_island_surface" + ((0.26 -0.32 0.025) + (0.0 0.0 1 0))) + (:milk + "kitchen_island_surface" + ((0.25 0 0.0983174006144206d0) + (0.0 0.0 -0.9 0.7))) + (:breakfast-cereal + "kitchen_island_surface" + ((0.32 -0.9 0.1) (0 0 0.6 0.4))))) + + +(defparameter *delivery-poses* + `((:bowl . ((-0.8399440765380859d0 1.2002920786539713d0 0.8932199478149414d0) + (0.0 0.0 0.33465 0.94234))) + (:cup . ((-0.8908212025960287d0 1.4991984049479166d0 0.9027448018391927d0) + (0.0 0.0 0.33465 0.94234))) + (:spoon . ((-0.8409400304158529d0 1.38009208679199219d0 0.8673268000284831d0) + (0.0 0.0 1 0))) + (:milk . ((-0.8495257695515951d0 1.6991498311360678d0 0.9483174006144206d0) + (0.0 0.0 -0.9 0.7))) + (:breakfast-cereal . ((-0.78 0.8 0.95) (0 0 0.6 0.4))))) + +(defparameter *cleaning-deliver-poses* + `((:bowl . ((1.45 -0.4 1.0) (0 0 0 1))) + (:cup . ((1.45 -0.4 1.0) (0 0 0 1))) + (:spoon . ((1.45 -0.4 1.0) (0 0 0 1))) + (:milk . ((1.2 -0.5 0.8) (0 0 1 0))) + (:breakfast-cereal . ((1.15 -0.5 0.8) (0 0 1 0))))) + + +(defun attach-object-to-the-world (object-type) + (when *demo-object-spawning-poses* + (btr:attach-object (btr:get-environment-object) + (btr:object btr:*current-bullet-world* + (intern (format nil "~a-1" object-type) :keyword)) + :link (second (find object-type + *demo-object-spawning-poses* + :key #'car))))) + +(defun make-poses-list-relative (spawning-poses-list) + "Gets a list of ((:type \"frame\" cords-list) ...) +Converts these coordinates into CRAM-TF:*FIXED-FRAME* frame and returns a list in form + ((TYPE . POSE) ...)." + (when spawning-poses-list + (mapcar (lambda (type-and-frame-and-pose-list) + (destructuring-bind (type frame pose-list) + type-and-frame-and-pose-list + (let* ((map-T-surface + (cl-transforms:pose->transform + (btr:link-pose (btr:get-environment-object) frame))) + (surface-T-object + (cl-transforms:pose->transform + (cram-tf:list->pose pose-list))) + (map-T-object + (cl-transforms:transform* map-T-surface surface-T-object)) + (map-P-object + (cl-transforms:transform->pose map-T-object))) + `(,type . ,map-P-object)))) + spawning-poses-list))) + +(defun spawn-objects-on-fixed-spots (&key + (spawning-poses-relative + *demo-object-spawning-poses*) + (object-types + '(:breakfast-cereal :cup :bowl :spoon :milk))) + (btr-utils:kill-all-objects) + (btr:add-objects-to-mesh-list "cram_pr2_pick_place_demo") + (btr:detach-all-objects (btr:get-robot-object)) + ;; spawn objects at default poses + (let* ((spawning-poses-absolute + (make-poses-list-relative spawning-poses-relative)) + (objects (mapcar (lambda (object-type) + (btr-utils:spawn-object + (intern (format nil "~a-1" object-type) :keyword) + object-type + :pose (cdr (assoc object-type + ;; *demo-object-spawning-poses* + spawning-poses-absolute + )))) + object-types))) + ;; stabilize world + ;; (btr:simulate btr:*current-bullet-world* 100) + objects) + + (mapcar #'attach-object-to-the-world object-types)) + + + +(defun setting-demo (&optional (object-list '(:bowl :spoon :cup + :milk :breakfast-cereal))) + (initialize) + (setf btr:*visibility-threshold* 0.7) + (when (or cram-projection:*projection-environment* + ;; dont want to add dependency on sim PMs, thus this stupid hack + (roslisp:get-param "/base_simulator/sim_frequency" nil)) + (spawn-objects-on-fixed-spots + :object-types object-list + :spawning-poses-relative *demo-object-spawning-poses*)) + ;; (park-robot) + + (dolist (?object-type object-list) + (let* ((?deliver-pose (cram-tf:ensure-pose-in-frame + (btr:ensure-pose + (cdr (assoc ?object-type *delivery-poses*))) + cram-tf:*fixed-frame*)) + (?deliver-location (a location (pose ?deliver-pose))) + (?color (cdr (assoc ?object-type *object-colors*))) + (?material (cdr (assoc ?object-type *object-materials*))) + ;; (?grasp (cdr (assoc ?object-type *object-grasps*))) + (?object (an object + (type ?object-type) + ;; (location ?fetch-location) + (desig:when ?color + (color ?color)) + (desig:when ?material + (material ?material))))) + (exe:perform + (an action + (type transporting) + (object ?object) + (context :table-setting) + ;; (grasps (:back :top :front)) + ;; (arms (left right)) + ;; (desig:when ?grasp + ;; (grasp ?grasp)) + ;; (target ?deliver-location) + ))))) + +(defun cleaning-demo (&optional (object-list '(:milk :breakfast-cereal + :bowl :spoon :cup))) + "Cleans up object to the designated locations by iterating over +`object-list' " + ;; (setup-for-demo object-list) + (when cram-projection:*projection-environment* + (spawn-objects-on-fixed-spots + :object-types object-list + :spawning-poses-relative *delivery-poses-relative*)) + + (dolist (?object-type object-list) + (exe:perform + (desig:an action + (type transporting) + (object (desig:an object (type ?object-type))) + (context table-cleaning))))) diff --git a/cram_pr2/cram_pr2_pick_place_demo/src/package.lisp b/cram_demos/cram_pr2_pick_place_demo/src/package.lisp similarity index 100% rename from cram_pr2/cram_pr2_pick_place_demo/src/package.lisp rename to cram_demos/cram_pr2_pick_place_demo/src/package.lisp diff --git a/cram_pr2/cram_pr2_pick_place_demo/src/projection-demo.lisp b/cram_demos/cram_pr2_pick_place_demo/src/projection-demo.lisp similarity index 95% rename from cram_pr2/cram_pr2_pick_place_demo/src/projection-demo.lisp rename to cram_demos/cram_pr2_pick_place_demo/src/projection-demo.lisp index d773d947ae..040ba432f6 100644 --- a/cram_pr2/cram_pr2_pick_place_demo/src/projection-demo.lisp +++ b/cram_demos/cram_pr2_pick_place_demo/src/projection-demo.lisp @@ -92,7 +92,7 @@ Converts these coordinates into CRAM-TF:*FIXED-FRAME* frame and returns a list i (map-T-object (cl-transforms:transform* map-T-surface surface-T-object)) (map-P-object - (cl-tf:transform->pose map-T-object))) + (cl-transforms:transform->pose map-T-object))) `(,type . ,map-P-object)))) (second spawning-poses))))) @@ -138,7 +138,7 @@ Converts these coordinates into CRAM-TF:*FIXED-FRAME* frame and returns a list i (type drawer) (urdf-name sink-area-left-upper-drawer-main) - (part-of kitchen))) + (part-of iai-kitchen))) (side front) (range 0.2) (range-invert 0.12)) @@ -146,12 +146,12 @@ Converts these coordinates into CRAM-TF:*FIXED-FRAME* frame and returns a list i (on (desig:an object (type counter-top) (urdf-name sink-area-surface) - (part-of kitchen))) + (part-of iai-kitchen))) ;; below only works for knowrob sem-map ;; (centered-with-padding 0.1) (side left) (side front)))) - :z-offset (/ aabb-z 2.0))) + :z (/ aabb-z 2.0))) ;; take the pose from the function input list (cdr (assoc object-type spawning-poses-absolute)))) ;; rotate new pose randomly around Z @@ -167,14 +167,15 @@ Converts these coordinates into CRAM-TF:*FIXED-FRAME* frame and returns a list i ;; make sure generated poses are stable, especially important for random ones ;; TDOO: if unstable, call itself + ;; attach spoon to the drawer + (when (btr:object btr:*current-bullet-world* :spoon-1) + (btr:attach-object (btr:get-environment-object) + (btr:object btr:*current-bullet-world* :spoon-1) + :link "sink_area_left_upper_drawer_main")) + ;; stabilize world (btr:simulate btr:*current-bullet-world* 100) - ;; attach spoon to the drawer - (btr:attach-object (btr:object btr:*current-bullet-world* :kitchen) - (btr:object btr:*current-bullet-world* :spoon-1) - :link "sink_area_left_upper_drawer_main") - ;; return list of BTR objects objects)) @@ -187,9 +188,7 @@ Converts these coordinates into CRAM-TF:*FIXED-FRAME* frame and returns a list i (?ptu-goal *look-goal*)) (cpl:par (exe:perform (desig:an action - (type positioning-arm) - (left-configuration park) - (right-configuration park))) + (type parking-arms))) (exe:perform (desig:a motion (type going) (pose ?navigation-goal)))) @@ -256,7 +255,7 @@ Converts these coordinates into CRAM-TF:*FIXED-FRAME* frame and returns a list i ;; (proj:with-projection-environment urdf-proj:urdf-bullet-projection-environment ;; (cpl:top-level ;; (exe:perform -;; (let ((?pose (cl-tf:make-pose-stamped +;; (let ((?pose (cl-transforms-stamped:make-pose-stamped ;; cram-tf:*robot-base-frame* 0.0 ;; (cl-transforms:make-3d-vector -0.5 0 0) ;; (cl-transforms:make-identity-rotation)))) @@ -268,7 +267,7 @@ Converts these coordinates into CRAM-TF:*FIXED-FRAME* frame and returns a list i ;; (exe:perform ;; (desig:a motion (type looking) (direction forward))) ;; (exe:perform -;; (let ((?pose (cl-tf:make-pose-stamped +;; (let ((?pose (cl-transforms-stamped:make-pose-stamped ;; cram-tf:*robot-base-frame* 0.0 ;; (cl-transforms:make-3d-vector 0.7 0.3 0.85) ;; (cl-transforms:make-identity-rotation)))) @@ -309,7 +308,7 @@ Converts these coordinates into CRAM-TF:*FIXED-FRAME* frame and returns a list i ;; (desig:a location ;; (on "CounterTop") ;; (name "iai_kitchen_meal_table_counter_top"))) -;; :z-offset (/ aabb-z 2.0)))) +;; :z (/ aabb-z 2.0)))) ;; (btr-utils:move-object (btr:name btr-object) new-pose))) ;; objects) ;; ;; bottle gets special treatment @@ -362,9 +361,7 @@ Converts these coordinates into CRAM-TF:*FIXED-FRAME* frame and returns a list i ;; (cpl:par ;; (exe:perform ;; (desig:an action -;; (type positioning-arm) -;; (left-configuration park) -;; (right-configuration park))) +;; (type parking-arms))) ;; (exe:perform (desig:a motion ;; (type going) ;; (pose ?navigation-goal)))) diff --git a/cram_pr2/cram_pr2_pick_place_demo/src/setup.lisp b/cram_demos/cram_pr2_pick_place_demo/src/setup.lisp similarity index 76% rename from cram_pr2/cram_pr2_pick_place_demo/src/setup.lisp rename to cram_demos/cram_pr2_pick_place_demo/src/setup.lisp index 25b83077a4..2c9a6c63bb 100644 --- a/cram_pr2/cram_pr2_pick_place_demo/src/setup.lisp +++ b/cram_demos/cram_pr2_pick_place_demo/src/setup.lisp @@ -32,27 +32,13 @@ ;; roslaunch cram_pr2_pick_place_demo sandbox.launch (defun init-projection () - (def-fact-group costmap-metadata (costmap:costmap-size - costmap:costmap-origin - costmap:costmap-resolution - costmap:orientation-samples - costmap:orientation-sample-step) - (<- (costmap:costmap-size 12 12)) - (<- (costmap:costmap-origin -6 -6)) - (<- (costmap:costmap-resolution 0.04)) - (<- (costmap:orientation-samples 2)) - (<- (costmap:orientation-sample-step 0.3))) - - (setf cram-bullet-reasoning-belief-state:*robot-parameter* "robot_description") - (setf cram-bullet-reasoning-belief-state:*kitchen-parameter* "kitchen_description") - - (cram-occasions-events:clear-belief) + (coe:clear-belief) (setf cram-tf:*tf-default-timeout* 2.0) (setf prolog:*break-on-lisp-errors* t) - (cram-bullet-reasoning:clear-costmap-vis-object) + (btr:clear-costmap-vis-object) ;; (setf cram-tf:*tf-broadcasting-enabled* t) diff --git a/cram_pr2/cram_pr2_pick_place_demo/tests/package.lisp b/cram_demos/cram_pr2_pick_place_demo/tests/package.lisp similarity index 100% rename from cram_pr2/cram_pr2_pick_place_demo/tests/package.lisp rename to cram_demos/cram_pr2_pick_place_demo/tests/package.lisp diff --git a/cram_pr2/cram_pr2_pick_place_demo/tests/projection-demo-tests.lisp b/cram_demos/cram_pr2_pick_place_demo/tests/projection-demo-tests.lisp similarity index 96% rename from cram_pr2/cram_pr2_pick_place_demo/tests/projection-demo-tests.lisp rename to cram_demos/cram_pr2_pick_place_demo/tests/projection-demo-tests.lisp index fda7101529..bae7e55195 100644 --- a/cram_pr2/cram_pr2_pick_place_demo/tests/projection-demo-tests.lisp +++ b/cram_demos/cram_pr2_pick_place_demo/tests/projection-demo-tests.lisp @@ -24,9 +24,7 @@ (defun move-surface (&key (x 0) (y 0) (z 0) (alpha 0.0)) (let* ((old-pose (btr:link-pose (btr:get-environment-object) "sink_area_surface")) (rotated-pose (cram-tf:rotate-pose old-pose :z alpha)) - (new-pose (cram-tf:translate-pose - rotated-pose - :x-offset x :y-offset y :z-offset z))) + (new-pose (cram-tf:translate-pose rotated-pose :x x :y y :z z))) (setf (btr:link-pose (btr:get-environment-object) "sink_area_surface") new-pose))) diff --git a/cram_pr2/cram_pr2_shopping_demo/CMakeLists.txt b/cram_demos/cram_pr2_shopping_demo/CMakeLists.txt similarity index 100% rename from cram_pr2/cram_pr2_shopping_demo/CMakeLists.txt rename to cram_demos/cram_pr2_shopping_demo/CMakeLists.txt diff --git a/cram_pr2/cram_pr2_shopping_demo/cram-pr2-shopping-demo.asd b/cram_demos/cram_pr2_shopping_demo/cram-pr2-shopping-demo.asd similarity index 90% rename from cram_pr2/cram_pr2_shopping_demo/cram-pr2-shopping-demo.asd rename to cram_demos/cram_pr2_shopping_demo/cram-pr2-shopping-demo.asd index a6387fffad..d038cc7d1d 100644 --- a/cram_pr2/cram_pr2_shopping_demo/cram-pr2-shopping-demo.asd +++ b/cram_demos/cram_pr2_shopping_demo/cram-pr2-shopping-demo.asd @@ -36,33 +36,35 @@ :depends-on (roslisp-utilities cl-transforms cl-transforms-stamped - cl-tf - cram-tf cram-language cram-executive cram-designators cram-prolog cram-projection cram-occasions-events + cram-common-failures + cram-object-knowledge cram-manipulation-interfaces - cram-physics-utils - cl-bullet + cram-tf + cram-bullet-reasoning cram-bullet-reasoning-belief-state cram-bullet-reasoning-utilities + + cram-location-costmap cram-btr-visibility-costmap + cram-btr-spatial-relations-costmap cram-robot-pose-gaussian-costmap - cram-location-costmap + cram-urdf-projection cram-mobile-pick-place-plans cram-pr2-description - cram-object-knowledge) + cram-fetch-deliver-plans) :components ((:module "src" :components ((:file "package") - (:file "grasping" :depends-on ("package")) - (:file "utils" :depends-on ("package")) - (:file "plans" :depends-on ("package" "utils" "grasping")))))) + (:file "setup" :depends-on ("package")) + (:file "plans" :depends-on ("package" "setup")))))) diff --git a/cram_demos/cram_pr2_shopping_demo/launch/world.launch b/cram_demos/cram_pr2_shopping_demo/launch/world.launch new file mode 100644 index 0000000000..bc59eca846 --- /dev/null +++ b/cram_demos/cram_pr2_shopping_demo/launch/world.launch @@ -0,0 +1,76 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - /kitchen/cram_joint_states + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/cram_pr2/cram_pr2_shopping_demo/package.xml b/cram_demos/cram_pr2_shopping_demo/package.xml similarity index 86% rename from cram_pr2/cram_pr2_shopping_demo/package.xml rename to cram_demos/cram_pr2_shopping_demo/package.xml index 8db461b5b3..208c4bb348 100644 --- a/cram_pr2/cram_pr2_shopping_demo/package.xml +++ b/cram_demos/cram_pr2_shopping_demo/package.xml @@ -13,8 +13,6 @@ roslisp_utilities cl_transforms cl_transforms_stamped - cl_tf - cram_tf cram_language cram_executive cram_designators @@ -22,21 +20,25 @@ cram_projection cram_occasions_events cram_common_failures + cram_object_knowledge cram_manipulation_interfaces - cram_physics_utils - cl_bullet + cram_tf cram_bullet_reasoning cram_bullet_reasoning_belief_state cram_bullet_reasoning_utilities + cram_location_costmap cram_btr_visibility_costmap + cram_btr_spatial_relations_costmap cram_robot_pose_gaussian_costmap - cram_location_costmap cram_urdf_projection cram_mobile_pick_place_plans cram_pr2_description - cram_object_knowledge + cram_fetch_deliver_plans robot_state_publisher + joint_state_publisher + tf pr2_description pr2_arm_kinematics + iai_refills_lab diff --git a/cram_demos/cram_pr2_shopping_demo/resource/basket1.stl b/cram_demos/cram_pr2_shopping_demo/resource/basket1.stl new file mode 100644 index 0000000000..cd7a972583 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/basket1.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/basket2.dae b/cram_demos/cram_pr2_shopping_demo/resource/basket2.dae new file mode 100644 index 0000000000..48279188d2 --- /dev/null +++ b/cram_demos/cram_pr2_shopping_demo/resource/basket2.dae @@ -0,0 +1,1341 @@ + + + + + SketchUp 6.4.245 + + 2017-12-17T21:50:06Z + 2017-12-17T21:50:06Z + + Z_UP + + + + + + + 35 + 0 + 1 + 1000 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0.8463224 -0.02189584 0.5322208 126.0873 0.5326711 0.03478871 -0.845607 -34.08389 -3.469447e-18 0.9991548 0.04110575 42.55851 0 0 0 1 + + + + 0.8463223 -0.5326711 0 10.28253 0.5326711 0.8463223 0 10.99287 -0 0 1 0 0 0 0 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 3.892457 -7.11058e-17 2.866858 3.655764 -7.11058e-17 3.073114 3.949213 -7.11058e-17 2.185975 3.503039 -2.931504e-16 3.627106 3.050582 -7.11058e-17 3.600473 2.07298 -2.931504e-16 3.972726 3.149508 -7.11058e-17 3.956831 2.310179 -2.931504e-16 4.465705 1.095378 -7.11058e-17 3.988236 0.2256372 -7.11058e-17 4.084641 0.8791916 -2.931504e-16 4.451951 1.512129 -2.931504e-16 4.561978 -0.2391257 -7.11058e-17 3.026582 -0.4186123 -7.11058e-17 3.186904 -0.3632656 -7.11058e-17 2.39065 0.2574336 -2.931504e-16 3.569452 + + + + + + + + + + -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 4 3 5 5 3 6 5 6 7 5 7 8 8 7 9 9 7 10 10 7 11 12 13 14 13 12 15 13 15 9 9 15 8

+
+
+
+ + + + 1.376066 -3.623819e-15 58.88633 0.9739964 -4.511998e-15 59.11934 -0.3285532 -4.511998e-15 58.91904 3.016875 -3.401775e-15 59.99305 3.112569 -3.401775e-15 60.10702 0.2914635 -4.511998e-15 58.62689 -1.487429 -3.623819e-15 58.66472 -0.7282479 -2.957686e-15 58.56203 -2.716527 -2.735641e-15 59.17059 + + + + + + + + + + -2.458718e-16 -1 8.634661e-16 -2.458718e-16 -1 8.634661e-16 -2.458718e-16 -1 8.634661e-16 -2.458718e-16 -1 8.634661e-16 -2.458718e-16 -1 8.634661e-16 -2.458718e-16 -1 8.634661e-16 -2.458718e-16 -1 8.634661e-16 -2.458718e-16 -1 8.634661e-16 -2.458718e-16 -1 8.634661e-16 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 5 6 7 6 5 0 6 0 2 6 2 8

+
+
+
+ + + + -8.699609 -2.069507e-15 30.24236 -9.150825 -1.181329e-15 30.18223 -8.880096 -7.372396e-16 30.07699 -8.541683 -1.847463e-15 31.73071 -9.60956 -3.623819e-15 32.13662 -9.083142 -1.847463e-15 31.72319 -8.383758 -2.291552e-15 31.89608 -9.150825 -2.957686e-15 33.29422 -10.34655 -3.845864e-15 33.88806 -9.556919 -2.735641e-15 34.85022 -9.635688 -2.957686e-15 30.08142 -9.272521 -3.17973e-15 30.0436 -10.97487 -2.957686e-15 30.64861 -8.73721 -1.181329e-15 30.51297 -9.353872 -1.181329e-15 30.95647 -11.0602 -1.625418e-15 30.76447 -12.15346 -2.735641e-15 32.24876 -9.88781 3.729834e-16 31.52775 -10.30142 -1.847463e-15 32.17421 -10.49695 -1.181329e-15 32.89583 -12.3897 -2.735641e-15 32.56951 -12.46521 -2.291552e-15 35.09825 -9.855484 -1.403373e-15 35.28573 -11.08748 -2.069507e-15 35.49858 -12.15346 -2.735641e-15 32.24876 -11.28507 -2.069507e-15 30.8528 -11.0602 -1.625418e-15 30.76447 -12.09463 -5.15195e-16 31.85106 + + + + + + + + + + 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 -5.621437e-15 -1 -4.277625e-15 -5.621437e-15 -1 -4.277625e-15 -5.621437e-15 -1 -4.277625e-15 -5.621437e-15 -1 -4.277625e-15 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.2004856 -3.623819e-15 64.85642 -0.6044442 -3.845864e-15 63.77693 -0.08506865 -6.510399e-15 63.5462 -0.6703965 -9.592842e-16 64.55976 -1.049623 -6.288355e-15 65.17779 0.02359036 -6.288355e-15 65.37478 -1.338165 -2.513596e-15 65.51565 0.5208183 -7.842667e-15 66.08923 -1.700903 -5.178132e-15 65.75462 4.555837 -3.845864e-15 68.42454 4.330499 -4.067909e-15 68.05356 4.913725 -1.403373e-15 67.88132 3.063003 -1.181329e-15 68.24538 1.822798 -2.957686e-15 68.30372 0.7139095 -5.622221e-15 68.49332 5.059532 -2.069507e-15 68.66302 3.9461 -5.400176e-15 70.18668 3.124282 -4.511998e-15 69.9747 3.985866 -2.735641e-15 69.68321 2.050616 -4.511998e-15 70.7299 0.9902048 -3.623819e-15 70.51791 1.997595 -3.623819e-15 70.34567 0.9504393 -2.735641e-15 70.79615 -0.3618191 -9.592842e-16 70.58416 -1.91076 -4.734043e-15 63.64485 -2.816906 -2.957686e-15 63.16121 -2.544323 -1.181329e-15 62.97352 -3.16951 -2.735641e-15 64.75897 -2.038909 -4.734043e-15 63.80165 -2.426379 -4.511998e-15 64.69161 -2.426379 -7.11058e-17 65.30964 -3.639648 -5.178132e-15 66.25099 -2.129594 -2.513596e-15 65.69693 0.4275881 -4.956087e-15 66.82438 -3.486853 -4.956087e-15 67.89573 0.8626627 -4.956087e-15 68.0669 -2.84053 -3.845864e-15 69.35198 4.650138 -3.845864e-15 69.20109 4.87396 -4.734043e-15 69.31223 -1.634312 -1.847463e-15 70.27943 3.044751 -7.176533e-15 70.30593 -0.7594733 -4.511998e-15 70.7829 -0.2097926 -2.513596e-15 71.09924 3.968377 -4.067909e-15 67.77191 + + + + + + + + + + -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.07751133 -2.931504e-16 1.290536 -0.6875039 -7.11058e-17 1.261942 -0.5625031 -7.11058e-17 0.8246356 -0.6312535 -7.11058e-17 1.443112 -0.2035019 -7.11058e-17 1.524609 -0.2856781 -7.11058e-17 1.81676 -0.3632656 -7.11058e-17 2.39065 + + + + + + + + + + -2.53243e-16 -1 6.170692e-17 -2.53243e-16 -1 6.170692e-17 -2.53243e-16 -1 6.170692e-17 -2.53243e-16 -1 6.170692e-17 -2.53243e-16 -1 6.170692e-17 -2.53243e-16 -1 6.170692e-17 -2.53243e-16 -1 6.170692e-17 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 0 4 3 4 5 3 5 6

+
+
+
+ + + + 0.02499985 -7.11058e-17 0.5747459 -0.6125033 -7.11058e-17 0.4747901 -0.4750025 -7.11058e-17 0.1749228 -0.5851946 -7.11058e-17 0.6658659 0.4500021 -7.11058e-17 0.6122292 0.6125033 -7.11058e-17 0.787152 -0.5625031 -7.11058e-17 0.8246356 0.4365828 -7.11058e-17 1.118883 0.07751133 -2.931504e-16 1.290536 0 -7.11058e-17 0 -2.229968 -7.11058e-17 -0.08746155 -0.6332961 -7.11058e-17 -0.08746155 -2.61632 -7.11058e-17 0.5809267 -0.4750025 -7.11058e-17 0.1749228 -0.6125033 -7.11058e-17 0.4747901 -0.5851946 -7.11058e-17 0.6658659 -1.937342 -7.11058e-17 0.7194317 + + + + + + + + + + 3.162529e-17 -1 -1.616798e-16 3.162529e-17 -1 -1.616798e-16 3.162529e-17 -1 -1.616798e-16 3.162529e-17 -1 -1.616798e-16 3.162529e-17 -1 -1.616798e-16 3.162529e-17 -1 -1.616798e-16 3.162529e-17 -1 -1.616798e-16 3.162529e-17 -1 -1.616798e-16 3.162529e-17 -1 -1.616798e-16 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 0 4 3 4 5 3 5 6 6 5 7 6 7 8 9 10 11 10 9 12 12 9 13 12 13 14 12 14 15 12 15 16

+
+
+
+ + + + 8.686465 -4.511998e-15 34.776 8.311984 -9.592842e-16 37.6255 8.436186 -1.847463e-15 34.74946 11.25639 -1.847463e-15 34.94384 11.62401 -1.403373e-15 34.95637 11.48848 -3.17973e-15 37.7923 7.732379 -1.847463e-15 42.30165 11.62351 -2.957686e-15 38.84664 11.62331 -3.623819e-15 40.35734 11.26292 -3.17973e-15 45.09838 7.2268 5.95028e-16 46.52386 11.01484 -2.069507e-15 46.76356 6.412227 -5.400176e-15 48.64962 6.967613 -4.511998e-15 48.73178 10.28516 -2.513596e-15 49.99597 + + + + + + + + + + 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 1 4 5 1 5 6 6 5 7 6 7 8 6 8 9 6 9 10 10 9 11 10 11 12 12 11 13 13 11 14

+
+
+
+ + + + 2.200012 -7.11058e-17 0 0 -7.11058e-17 0 1.062505 -7.11058e-17 -0.08746155 3.200017 -7.11058e-17 0.8371299 -0.4750025 -7.11058e-17 0.1749228 0.02499985 -7.11058e-17 0.5747459 0.4500021 -7.11058e-17 0.6122292 0.6125033 -7.11058e-17 0.787152 0.4365828 -7.11058e-17 1.118883 3.810939 -7.11058e-17 1.925333 0.07751133 -2.931504e-16 1.290536 -0.2035019 -7.11058e-17 1.524609 -0.2856781 -7.11058e-17 1.81676 -0.03739845 -7.11058e-17 2.375139 3.143686 -7.11058e-17 2.607797 0.676406 -7.11058e-17 2.871477 2.445399 -7.11058e-17 2.902498 1.51435 -7.11058e-17 3.042093 + + + + + + + + + + 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 4 3 5 5 3 6 6 3 7 7 3 8 8 3 9 8 9 10 10 9 11 11 9 12 12 9 13 13 9 14 13 14 15 15 14 16 15 16 17

+
+
+
+ + + + 4.148516 -2.735641e-15 64.18445 -0.08506865 -6.510399e-15 63.5462 4.624403 -3.623819e-15 63.02912 -0.2004856 -3.623819e-15 64.85642 4.119428 -1.847463e-15 64.75432 4.538299 -6.06631e-15 65.44632 0.02359036 -6.288355e-15 65.37478 0.5208183 -7.842667e-15 66.08923 4.317228 -6.954489e-15 66.44069 0.4275881 -4.956087e-15 66.82438 4.194989 -3.17973e-15 67.39926 0.8626627 -4.956087e-15 68.0669 3.968377 -4.067909e-15 67.77191 3.063003 -1.181329e-15 68.24538 1.822798 -2.957686e-15 68.30372 0.7139095 -5.622221e-15 68.49332 0.9739964 -4.511998e-15 59.11934 -2.716527 -2.735641e-15 59.17059 -0.3285532 -4.511998e-15 58.91904 3.112569 -3.401775e-15 60.10702 -3.627505 -4.289953e-15 60.13898 3.319971 -2.735641e-15 60.35404 -3.584125 -5.178132e-15 60.4425 3.213513 -2.513596e-15 60.37299 3.410831 1.509388e-16 60.62535 -3.237086 -1.625418e-15 60.76048 3.400432 -5.178132e-15 61.167 -2.835603 -2.513596e-15 61.19022 3.785802 -4.956087e-15 62.17978 -2.544323 -1.181329e-15 62.97352 3.84089 -3.17973e-15 62.64231 4.5795 -3.623819e-15 62.78329 -1.91076 -4.734043e-15 63.64485 -0.6044442 -3.845864e-15 63.77693 -2.038909 -4.734043e-15 63.80165 -0.6703965 -9.592842e-16 64.55976 -2.426379 -4.511998e-15 64.69161 -1.049623 -6.288355e-15 65.17779 -2.426379 -7.11058e-17 65.30964 -1.338165 -2.513596e-15 65.51565 -2.129594 -2.513596e-15 65.69693 -1.700903 -5.178132e-15 65.75462 + + + + + + + + + + -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 9.02875 -5.15195e-16 29.68473 8.775303 -2.931504e-16 30.05464 8.933047 -9.592842e-16 29.59148 9.242663 -1.847463e-15 29.6977 10.45619 -2.069507e-15 30.56953 9.356983 -2.069507e-15 30.84301 11.42322 -2.291552e-15 32.49641 9.652752 -2.291552e-15 31.72007 9.613316 -9.592842e-16 32.43945 9.366842 -1.625418e-15 33.30665 11.48522 -2.513596e-15 33.99952 8.864034 -2.513596e-15 30.99083 8.371085 -2.957686e-15 30.95141 8.548547 -3.401775e-15 30.85286 8.292213 -1.403373e-15 32.20294 9.130226 -1.847463e-15 31.84818 9.120367 -2.291552e-15 32.40989 8.42038 -2.291552e-15 34.21327 11.25639 -1.847463e-15 34.94384 8.686465 -4.511998e-15 34.776 + + + + + + + + + + 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 1 4 5 5 4 6 5 6 7 7 6 8 8 6 9 9 6 10 11 12 13 12 11 14 14 11 15 14 15 16 14 16 17 17 16 9 17 9 10 17 10 18 17 18 19

+
+
+
+ + + + 3.949213 -7.11058e-17 2.185975 3.143686 -7.11058e-17 2.607797 3.810939 -7.11058e-17 1.925333 3.655764 -7.11058e-17 3.073114 2.445399 -7.11058e-17 2.902498 1.51435 -7.11058e-17 3.042093 -0.03739845 -7.11058e-17 2.375139 -0.3632656 -7.11058e-17 2.39065 -0.2856781 -7.11058e-17 1.81676 0.676406 -7.11058e-17 2.871477 -0.2391257 -7.11058e-17 3.026582 0.2574336 -2.931504e-16 3.569452 3.050582 -7.11058e-17 3.600473 1.095378 -7.11058e-17 3.988236 2.07298 -2.931504e-16 3.972726 + + + + + + + + + + 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 4 3 5 6 7 8 7 6 9 7 9 10 10 9 5 10 5 11 11 5 3 11 3 12 11 12 13 13 12 14

+
+
+
+ + + + -0.5625031 -7.11058e-17 0.8246356 -1.937342 -7.11058e-17 0.7194317 -0.5851946 -7.11058e-17 0.6658659 -2.385319 -7.11058e-17 1.360664 -2.61632 -7.11058e-17 0.5809267 -0.8026566 -7.11058e-17 0.9194414 -0.9599727 -7.11058e-17 1.717766 -1.663174 -7.11058e-17 1.962182 -1.024971 -7.11058e-17 2.047612 + + + + + + + + + + 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 + + + + + + + + + + + + + + +

0 1 2 1 3 4 3 1 0 3 0 5 3 5 6 3 6 7 7 6 8

+
+
+
+ + + + 7.129938 -3.401775e-15 39.03096 7.024295 -3.845864e-15 35.60014 7.377742 -1.181329e-15 35.57307 6.080943 -1.181329e-15 35.6724 -7.087642 -1.181329e-15 36.4229 -6.584432 -2.735641e-15 42.71022 6.646375 -3.401775e-15 44.69384 -6.761216 -9.592842e-16 49.32586 6.276589 -1.847463e-15 48.62955 6.412227 -5.400176e-15 48.64962 6.967613 -4.511998e-15 48.73178 10.28516 -2.513596e-15 49.99597 -6.636205 -3.17973e-15 34.80158 -7.294847 -7.11058e-17 34.60328 1.121015 -2.735641e-15 35.10383 -6.978891 -1.181329e-15 49.32048 -10.9849 -6.732444e-15 50.95156 -7.433722 -4.289953e-15 49.31781 -6.870616 -9.592842e-16 49.32112 10.5565 -2.513596e-15 50.10338 9.094294 -5.178132e-15 55.81307 -11.74802 -1.403373e-15 51.30264 -9.127466 -1.181329e-15 57.58239 8.381689 -2.957686e-15 57.61984 -8.481249 -4.734043e-15 58.46157 -0.7282479 -2.957686e-15 58.56203 7.182426 -4.511998e-15 58.8012 0.2914635 -4.511998e-15 58.62689 1.376066 -3.623819e-15 58.88633 3.845346 -2.513596e-15 60.26052 3.016875 -3.401775e-15 59.99305 3.112569 -3.401775e-15 60.10702 3.319971 -2.735641e-15 60.35404 -7.027259 -2.735641e-15 59.39458 -1.487429 -3.623819e-15 58.66472 -2.716527 -2.735641e-15 59.17059 -3.627505 -4.289953e-15 60.13898 -4.061304 -4.289953e-15 60.61594 -3.584125 -5.178132e-15 60.4425 -3.237086 -1.625418e-15 60.76048 + + + + + + + + + + -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -9.658083 -1.403373e-15 36.97898 -9.855484 -1.403373e-15 35.28573 -9.692526 -1.847463e-15 35.25758 -11.08748 -2.069507e-15 35.49858 -6.978891 -1.181329e-15 49.32048 -7.433722 -4.289953e-15 49.31781 -8.550982 -3.623819e-15 43.58936 -12.46521 -2.291552e-15 35.09825 -12.71122 -1.181329e-15 42.07124 -12.93021 -2.291552e-15 34.72395 -9.279205 -2.735641e-15 37.75361 -8.848663 -3.17973e-15 40.50785 -10.9849 -6.732444e-15 50.95156 + + + + + + + + + + 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 7 8 9 8 7 3 8 3 0 8 0 10 8 10 11 8 11 6 8 6 12 12 6 5

+
+
+
+ + + + -0.6875039 -7.11058e-17 1.261942 -0.8026566 -7.11058e-17 0.9194414 -0.5625031 -7.11058e-17 0.8246356 -0.9599727 -7.11058e-17 1.717766 -0.6312535 -7.11058e-17 1.443112 -0.3632656 -7.11058e-17 2.39065 -1.024971 -7.11058e-17 2.047612 4.011514 -7.11058e-17 3.996891 3.892457 -7.11058e-17 2.866858 4.26624 -7.11058e-17 2.773632 3.503039 -2.931504e-16 3.627106 3.149508 -7.11058e-17 3.956831 2.310179 -2.931504e-16 4.465705 5.003464 -7.372396e-16 8.475154 1.512129 -2.931504e-16 4.561978 -1.549515 -5.15195e-16 6.546715 -1.937112 -5.15195e-16 7.012807 -4.260262 -7.372396e-16 15.9837 5.509694 -7.372396e-16 13.80151 5.349832 -2.069507e-15 17.3968 -4.041846 -7.372396e-16 16.73789 -3.595336 -7.372396e-16 17.0419 -6.350576 -2.069507e-15 27.75496 5.330935 -1.403373e-15 19.75652 6.204863 -1.403373e-15 23.99185 6.602104 -2.291552e-15 29.70955 -6.686256 -2.735641e-15 29.92575 6.867097 -2.957686e-15 31.1451 -6.636205 -3.17973e-15 34.80158 1.121015 -2.735641e-15 35.10383 7.024295 -3.845864e-15 35.60014 6.080943 -1.181329e-15 35.6724 -1.663174 -7.11058e-17 1.962182 -1.840465 -7.11058e-17 2.68922 -2.20437 -7.11058e-17 1.793184 -0.4186123 -7.11058e-17 3.186904 0.2256372 -7.11058e-17 4.084641 0.8791916 -2.931504e-16 4.451951 + + + + + + + + + + -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.2300517 -4.067909e-15 61.41776 1.349407 -2.513596e-15 60.31828 2.266968 -3.401775e-15 60.17539 3.016875 -1.625418e-15 60.23916 3.213513 -2.513596e-15 60.37299 + + + + + + + + + + + + + +

1 0 1 2 2 3 3 4

+
+
+
+ + + + 10.10626 -1.181329e-15 30.73461 9.02875 -5.15195e-16 29.68473 10.73724 -2.735641e-15 32.17338 + + + + + + + + + + + + + +

1 0 0 2

+
+
+
+ + + + -10.31646 -1.181329e-15 30.73096 -9.150825 -1.181329e-15 30.18223 -11.60995 -1.847463e-15 32.4373 + + + + + + + + + + + + + +

1 0 0 2

+
+
+
+ + + + -1.560754 -2.957686e-15 63.21658 -1.91076 -4.734043e-15 63.64485 -1.263968 -2.957686e-15 63.21658 -1.016647 -5.622221e-15 63.45555 + + + + + + + + + + + + + +

1 0 0 2 2 3

+
+
+
+ + + + -1.389596 -7.11058e-17 3.897956 -1.024971 -7.11058e-17 2.047612 -1.161918 -7.11058e-17 6.080624 -0.6226979 -2.931504e-16 13.67195 -0.02460687 -7.11058e-17 17.17918 -0.3037158 -2.069507e-15 23.11756 0.01526583 -2.291552e-15 29.73348 + + + + + + + + + + + + + +

1 0 0 2 2 3 3 4 4 5 5 6

+
+
+
+ + + + 6.262331 -4.067909e-15 52.07277 6.276589 -1.847463e-15 48.62955 + + + + + + + + + + + + + +

1 0

+
+
+
+ + + + -2.671783 -1.181329e-15 17.6707 -3.595336 -7.372396e-16 17.0419 + + + + + + + + + + + + + +

1 0

+
+
+
+ + + + -6.904132 5.95028e-16 52.62575 -6.761216 -9.592842e-16 49.32586 + + + + + + + + + + + + + +

1 0

+
+
+
+ + + + 71.18867 63.3252 16.32867 50.88542 44.44507 16.32867 50.88542 63.3252 16.32867 71.18867 44.44507 16.32867 71.18867 44.44507 16.32867 71.18867 63.3252 16.32867 50.88542 44.44507 16.32867 50.88542 63.3252 16.32867 + + + + + + + + + + 0 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 2 1 0 3

+
+ + +

4 5 6 7 6 5

+
+
+
+ + + + 58.80693 57.69237 36.58725 59.15071 57.69237 36.58725 58.97882 57.69237 36.56462 58.64676 57.69237 36.6536 59.31088 57.69237 36.6536 58.50921 57.69237 36.75914 59.44843 57.69237 36.75914 58.40367 57.69237 36.89669 59.55397 57.69237 36.89669 58.33733 57.69237 37.05686 59.62032 57.69237 37.05686 58.3147 57.69237 37.22875 59.64295 57.69237 37.22875 58.33733 57.69237 37.40064 59.62032 57.69237 37.40064 58.40367 57.69237 37.56081 59.55397 57.69237 37.56081 58.50921 57.69237 37.69836 59.44843 57.69237 37.69836 58.64676 57.69237 37.8039 59.31088 57.69237 37.8039 58.80693 57.69237 37.87025 59.15071 57.69237 37.87025 58.97882 57.69237 37.89287 59.64295 57.69237 37.22875 59.62032 50.67162 37.40064 59.64295 50.67162 37.22875 59.62032 57.69237 37.40064 59.62032 57.69237 37.05686 59.62032 50.67162 37.05686 59.55397 57.69237 36.89669 59.55397 50.67162 36.89669 59.44843 57.69237 36.75914 59.44843 50.67162 36.75914 59.31088 50.67162 36.6536 59.31088 57.69237 36.6536 59.15071 50.67162 36.58725 59.15071 57.69237 36.58725 58.97882 50.67162 36.56462 58.97882 57.69237 36.56462 58.80693 50.67162 36.58725 58.80693 57.69237 36.58725 58.64676 50.67162 36.6536 58.64676 57.69237 36.6536 58.50921 50.67162 36.75914 58.50921 57.69237 36.75914 58.40367 57.69237 36.89669 58.40367 50.67162 36.89669 58.33733 57.69237 37.05686 58.33733 50.67162 37.05686 58.3147 57.69237 37.22875 58.3147 50.67162 37.22875 58.33733 57.69237 37.40064 58.33733 50.67162 37.40064 58.40367 57.69237 37.56081 58.40367 50.67162 37.56081 58.50921 57.69237 37.69836 58.50921 50.67162 37.69836 58.64676 50.67162 37.8039 58.64676 57.69237 37.8039 58.80693 50.67162 37.87025 58.80693 57.69237 37.87025 58.97882 50.67162 37.89287 58.97882 57.69237 37.89287 59.15071 50.67162 37.87025 59.15071 57.69237 37.87025 59.31088 50.67162 37.8039 59.31088 57.69237 37.8039 59.44843 50.67162 37.69836 59.44843 57.69237 37.69836 59.55397 57.69237 37.56081 59.55397 50.67162 37.56081 59.15071 50.67162 36.58725 58.80693 50.67162 36.58725 58.97882 50.67162 36.56462 59.31088 50.67162 36.6536 58.64676 50.67162 36.6536 59.44843 50.67162 36.75914 58.50921 50.67162 36.75914 59.55397 50.67162 36.89669 58.40367 50.67162 36.89669 59.62032 50.67162 37.05686 58.33733 50.67162 37.05686 59.64295 50.67162 37.22875 58.3147 50.67162 37.22875 59.62032 50.67162 37.40064 58.33733 50.67162 37.40064 59.55397 50.67162 37.56081 58.40367 50.67162 37.56081 59.44843 50.67162 37.69836 58.50921 50.67162 37.69836 59.31088 50.67162 37.8039 58.64676 50.67162 37.8039 59.15071 50.67162 37.87025 58.80693 50.67162 37.87025 58.97882 50.67162 37.89287 + + + + + + + + + + -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -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 1.069333e-14 0.9659258 0 0.258819 1 0 1.069333e-14 0.9659258 0 0.258819 0.9659258 0 -0.258819 0.9659258 0 -0.258819 0.8660254 0 -0.5 0.8660254 0 -0.5 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.5 0 -0.8660254 0.5 0 -0.8660254 0.258819 0 -0.9659258 0.258819 0 -0.9659258 5.337755e-15 0 -1 5.337755e-15 0 -1 -0.258819 0 -0.9659258 -0.258819 0 -0.9659258 -0.5 0 -0.8660254 -0.5 0 -0.8660254 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.8660254 0 -0.5 -0.8660254 0 -0.5 -0.9659258 0 -0.258819 -0.9659258 0 -0.258819 -1 0 1.070224e-14 -1 0 1.070224e-14 -0.9659258 0 0.258819 -0.9659258 0 0.258819 -0.8660254 0 0.5 -0.8660254 0 0.5 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.5 0 0.8660254 -0.5 0 0.8660254 -0.258819 0 0.9659258 -0.258819 0 0.9659258 5.346666e-15 0 1 5.346666e-15 0 1 0.258819 0 0.9659258 0.258819 0 0.9659258 0.5 0 0.8660254 0.5 0 0.8660254 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.8660254 0 0.5 0.8660254 0 0.5 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 4 3 5 4 5 6 6 5 7 6 7 8 8 7 9 8 9 10 10 9 11 10 11 12 12 11 13 12 13 14 14 13 15 14 15 16 16 15 17 16 17 18 18 17 19 18 19 20 20 19 21 20 21 22 22 21 23 24 25 26 25 24 27 28 26 29 26 28 24 30 29 31 29 30 28 32 31 33 31 32 30 32 34 35 34 32 33 35 36 37 36 35 34 37 38 39 38 37 36 39 40 41 40 39 38 41 42 43 42 41 40 43 44 45 44 43 42 46 44 47 44 46 45 48 47 49 47 48 46 50 49 51 49 50 48 52 51 53 51 52 50 54 53 55 53 54 52 56 55 57 55 56 54 58 56 57 56 58 59 60 59 58 59 60 61 62 61 60 61 62 63 64 63 62 63 64 65 66 65 64 65 66 67 68 67 66 67 68 69 70 68 71 68 70 69 27 71 25 71 27 70 72 73 74 73 72 75 73 75 76 76 75 77 76 77 78 78 77 79 78 79 80 80 79 81 80 81 82 82 81 83 82 83 84 84 83 85 84 85 86 86 85 87 86 87 88 88 87 89 88 89 90 90 89 91 90 91 92 92 91 93 92 93 94 94 93 95

+
+
+
+ + + + 63.58951 57.78542 36.58725 63.42933 50.76467 36.6536 63.42933 57.78542 36.6536 63.58951 50.76467 36.58725 63.58951 57.78542 36.58725 63.93328 57.78542 36.58725 63.76139 57.78542 36.56462 63.42933 57.78542 36.6536 64.09346 57.78542 36.6536 63.29179 57.78542 36.75914 64.231 57.78542 36.75914 63.18624 57.78542 36.89669 64.33654 57.78542 36.89669 63.1199 57.78542 37.05686 64.40289 57.78542 37.05686 63.09727 57.78542 37.22875 64.42552 57.78542 37.22875 63.1199 57.78542 37.40064 64.40289 57.78542 37.40064 63.18624 57.78542 37.56081 64.33654 57.78542 37.56081 63.29179 57.78542 37.69836 64.231 57.78542 37.69836 63.42933 57.78542 37.8039 64.09346 57.78542 37.8039 63.58951 57.78542 37.87025 63.93328 57.78542 37.87025 63.76139 57.78542 37.89287 63.76139 57.78542 36.56462 63.76139 50.76467 36.56462 63.93328 50.76467 36.58725 63.58951 50.76467 36.58725 63.76139 50.76467 36.56462 64.09346 50.76467 36.6536 63.42933 50.76467 36.6536 64.231 50.76467 36.75914 63.29179 50.76467 36.75914 64.33654 50.76467 36.89669 63.18624 50.76467 36.89669 64.40289 50.76467 37.05686 63.1199 50.76467 37.05686 64.42552 50.76467 37.22875 63.09727 50.76467 37.22875 64.40289 50.76467 37.40064 63.1199 50.76467 37.40064 64.33654 50.76467 37.56081 63.18624 50.76467 37.56081 64.231 50.76467 37.69836 63.29179 50.76467 37.69836 64.09346 50.76467 37.8039 63.42933 50.76467 37.8039 63.93328 50.76467 37.87025 63.58951 50.76467 37.87025 63.76139 50.76467 37.89287 63.29179 50.76467 36.75914 63.29179 57.78542 36.75914 64.42552 57.78542 37.22875 64.40289 50.76467 37.40064 64.42552 50.76467 37.22875 64.40289 57.78542 37.40064 64.40289 57.78542 37.05686 64.40289 50.76467 37.05686 64.33654 57.78542 36.89669 64.33654 50.76467 36.89669 64.231 57.78542 36.75914 64.231 50.76467 36.75914 64.09346 50.76467 36.6536 64.09346 57.78542 36.6536 63.93328 50.76467 36.58725 63.93328 57.78542 36.58725 63.18624 57.78542 36.89669 63.18624 50.76467 36.89669 63.1199 57.78542 37.05686 63.1199 50.76467 37.05686 63.09727 57.78542 37.22875 63.09727 50.76467 37.22875 63.1199 57.78542 37.40064 63.1199 50.76467 37.40064 63.18624 57.78542 37.56081 63.18624 50.76467 37.56081 63.29179 57.78542 37.69836 63.29179 50.76467 37.69836 63.42933 50.76467 37.8039 63.42933 57.78542 37.8039 63.58951 50.76467 37.87025 63.58951 57.78542 37.87025 63.76139 50.76467 37.89287 63.76139 57.78542 37.89287 63.93328 50.76467 37.87025 63.93328 57.78542 37.87025 64.09346 50.76467 37.8039 64.09346 57.78542 37.8039 64.231 50.76467 37.69836 64.231 57.78542 37.69836 64.33654 57.78542 37.56081 64.33654 50.76467 37.56081 + + + + + + + + + + -0.258819 0 -0.9659258 -0.5 0 -0.8660254 -0.5 0 -0.8660254 -0.258819 0 -0.9659258 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -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.069333e-14 0 -1 -1.069333e-14 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.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 1 0 5.346666e-15 0.9659258 0 0.258819 1 0 5.346666e-15 0.9659258 0 0.258819 0.9659258 0 -0.258819 0.9659258 0 -0.258819 0.8660254 0 -0.5 0.8660254 0 -0.5 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.5 0 -0.8660254 0.5 0 -0.8660254 0.258819 0 -0.9659258 0.258819 0 -0.9659258 -0.8660254 0 -0.5 -0.8660254 0 -0.5 -0.9659258 0 -0.258819 -0.9659258 0 -0.258819 -1 0 5.346666e-15 -1 0 5.346666e-15 -0.9659258 0 0.258819 -0.9659258 0 0.258819 -0.8660254 0 0.5 -0.8660254 0 0.5 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.5 0 0.8660254 -0.5 0 0.8660254 -0.258819 0 0.9659258 -0.258819 0 0.9659258 -1.069333e-14 0 1 -1.069333e-14 0 1 0.258819 0 0.9659258 0.258819 0 0.9659258 0.5 0 0.8660254 0.5 0 0.8660254 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.8660254 0 0.5 0.8660254 0 0.5 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 5 4 7 5 7 8 8 7 9 8 9 10 10 9 11 10 11 12 12 11 13 12 13 14 14 13 15 14 15 16 16 15 17 16 17 18 18 17 19 18 19 20 20 19 21 20 21 22 22 21 23 22 23 24 24 23 25 24 25 26 26 25 27 28 3 0 3 28 29 30 31 32 31 30 33 31 33 34 34 33 35 34 35 36 36 35 37 36 37 38 38 37 39 38 39 40 40 39 41 40 41 42 42 41 43 42 43 44 44 43 45 44 45 46 46 45 47 46 47 48 48 47 49 48 49 50 50 49 51 50 51 52 52 51 53 2 54 55 54 2 1 56 57 58 57 56 59 60 58 61 58 60 56 62 61 63 61 62 60 64 63 65 63 64 62 64 66 67 66 64 65 67 68 69 68 67 66 69 29 28 29 69 68 70 54 71 54 70 55 72 71 73 71 72 70 74 73 75 73 74 72 76 75 77 75 76 74 78 77 79 77 78 76 80 79 81 79 80 78 82 80 81 80 82 83 84 83 82 83 84 85 86 85 84 85 86 87 88 87 86 87 88 89 90 89 88 89 90 91 92 91 90 91 92 93 94 92 95 92 94 93 59 95 57 95 59 94

+
+
+
+ + + + 62.43954 44.44507 16.81251 63.25985 44.44507 16.8197 62.43954 44.44507 20.60751 64.49323 44.44507 16.8197 63.25985 44.44507 20.6147 61.20616 44.44507 20.60751 65.1287 44.44507 16.82624 64.49323 44.44507 20.6147 67.36574 44.44507 16.82465 68.50424 44.44507 16.82465 66.36207 44.44507 16.82624 65.1287 44.44507 20.62124 69.09191 44.44507 16.82564 68.50424 44.44507 20.61965 70.32528 44.44507 16.82564 69.09191 44.44507 20.62064 67.36574 44.44507 20.61965 55.5985 44.44507 16.84117 56.71984 44.44507 16.9052 55.5985 44.44507 20.63617 57.95322 44.44507 16.9052 56.71984 44.44507 20.7002 54.36512 44.44507 20.63617 53.30409 44.44507 20.65508 52.07072 44.44507 20.65508 53.30409 44.44507 16.86008 54.36512 44.44507 16.84117 58.93008 44.44507 16.84062 58.93008 44.44507 20.63562 57.95322 44.44507 20.7002 60.16345 44.44507 16.84062 61.20616 44.44507 16.81251 60.16345 44.44507 20.63562 66.36207 44.44507 20.62124 62.34295 44.44507 21.08863 63.16326 44.44507 21.09582 62.34295 44.44507 24.88363 64.39663 44.44507 21.09582 63.16326 44.44507 24.89082 61.10957 44.44507 24.88363 65.0321 44.44507 21.10236 64.39663 44.44507 24.89082 67.26915 44.44507 21.10077 68.40765 44.44507 21.10077 66.26548 44.44507 21.10236 65.0321 44.44507 24.89736 68.99532 44.44507 21.10177 68.40765 44.44507 24.89577 70.22869 44.44507 21.10177 68.99532 44.44507 24.89677 67.26915 44.44507 24.89577 55.50191 44.44507 21.11729 56.62325 44.44507 21.18132 55.50191 44.44507 24.91229 57.85663 44.44507 21.18132 56.62325 44.44507 24.97632 54.26853 44.44507 24.91229 53.2075 44.44507 24.9312 51.97412 44.44507 24.9312 53.2075 44.44507 21.1362 54.26853 44.44507 21.11729 58.83349 44.44507 21.11675 58.83349 44.44507 24.91175 57.85663 44.44507 24.97632 60.06686 44.44507 21.11675 61.10957 44.44507 21.08863 60.06686 44.44507 24.91175 66.26548 44.44507 24.89736 62.30036 44.44507 25.47136 63.12067 44.44507 25.47855 62.30036 44.44507 29.26636 64.35405 44.44507 25.47855 63.12067 44.44507 29.27355 61.06698 44.44507 29.26636 64.98952 44.44507 25.48509 64.35405 44.44507 29.27355 67.22656 44.44507 25.4835 68.36506 44.44507 25.4835 66.22289 44.44507 25.48509 64.98952 44.44507 29.28009 68.95273 44.44507 25.48449 68.36506 44.44507 29.2785 70.18611 44.44507 25.48449 68.95273 44.44507 29.27949 67.22656 44.44507 29.2785 55.45932 44.44507 25.50002 56.58066 44.44507 25.56405 55.45932 44.44507 29.29502 57.81404 44.44507 25.56405 56.58066 44.44507 29.35905 54.22594 44.44507 29.29502 53.16491 44.44507 29.31393 51.93154 44.44507 29.31393 71.18867 44.44507 16.32867 50.88542 44.44507 16.32867 71.18867 44.44507 30.46505 70.32528 44.44507 20.62064 70.22869 44.44507 24.89677 70.18611 44.44507 29.27949 66.22289 44.44507 29.28009 60.02427 44.44507 29.29447 58.7909 44.44507 29.29447 57.81404 44.44507 29.35905 52.07072 44.44507 16.86008 50.88542 44.44507 30.46505 51.97412 44.44507 21.1362 51.93154 44.44507 25.51893 54.22594 44.44507 25.50002 61.06698 44.44507 25.47136 58.7909 44.44507 25.49947 60.02427 44.44507 25.49947 53.16491 44.44507 25.51893 68.95273 44.44507 29.27949 67.22656 44.44507 29.2785 66.22289 44.44507 29.28009 66.22289 44.44507 25.48509 67.22656 44.44507 25.4835 64.98952 44.44507 29.28009 63.12067 44.44507 29.27355 60.02427 44.44507 29.29447 61.06698 44.44507 29.26636 60.02427 44.44507 25.49947 61.06698 44.44507 25.47136 57.81404 44.44507 29.35905 58.7909 44.44507 29.29447 57.81404 44.44507 25.56405 58.7909 44.44507 25.49947 55.45932 44.44507 25.50002 53.16491 44.44507 29.31393 54.22594 44.44507 29.29502 53.16491 44.44507 25.51893 54.22594 44.44507 25.50002 71.18867 44.44507 30.46505 56.58066 44.44507 29.35905 50.88542 44.44507 30.46505 51.93154 44.44507 29.31393 51.93154 44.44507 25.51893 62.30036 44.44507 25.47136 56.62325 44.44507 24.97632 51.97412 44.44507 24.9312 51.97412 44.44507 21.1362 53.2075 44.44507 21.1362 54.26853 44.44507 21.11729 55.50191 44.44507 21.11729 58.83349 44.44507 21.11675 60.06686 44.44507 21.11675 61.10957 44.44507 21.08863 62.34295 44.44507 21.08863 56.71984 44.44507 20.7002 52.07072 44.44507 20.65508 52.07072 44.44507 16.86008 53.30409 44.44507 16.86008 54.36512 44.44507 16.84117 55.5985 44.44507 16.84117 58.93008 44.44507 16.84062 60.16345 44.44507 16.84062 61.20616 44.44507 16.81251 62.43954 44.44507 16.81251 50.88542 44.44507 16.32867 70.18611 44.44507 29.27949 70.18611 44.44507 25.48449 68.36506 44.44507 25.4835 64.35405 44.44507 25.47855 57.85663 44.44507 24.97632 58.83349 44.44507 24.91175 60.06686 44.44507 24.91175 65.0321 44.44507 24.89736 66.26548 44.44507 24.89736 68.99532 44.44507 24.89677 70.22869 44.44507 24.89677 70.22869 44.44507 21.10177 68.40765 44.44507 21.10077 64.39663 44.44507 21.09582 57.95322 44.44507 20.7002 58.93008 44.44507 20.63562 60.16345 44.44507 20.63562 65.1287 44.44507 20.62124 66.36207 44.44507 20.62124 69.09191 44.44507 20.62064 70.32528 44.44507 20.62064 70.32528 44.44507 16.82564 68.50424 44.44507 16.82465 64.49323 44.44507 16.8197 71.18867 44.44507 16.32867 55.45932 44.44507 29.29502 56.58066 44.44507 25.56405 68.36506 44.44507 29.2785 68.95273 44.44507 25.48449 64.35405 44.44507 29.27355 64.98952 44.44507 25.48509 62.30036 44.44507 29.26636 63.12067 44.44507 25.47855 67.26915 44.44507 24.89577 66.26548 44.44507 21.10236 67.26915 44.44507 21.10077 63.16326 44.44507 24.89082 61.10957 44.44507 24.88363 57.85663 44.44507 21.18132 53.2075 44.44507 24.9312 54.26853 44.44507 24.91229 55.50191 44.44507 24.91229 56.62325 44.44507 21.18132 68.40765 44.44507 24.89577 68.99532 44.44507 21.10177 64.39663 44.44507 24.89082 65.0321 44.44507 21.10236 62.34295 44.44507 24.88363 63.16326 44.44507 21.09582 67.36574 44.44507 20.61965 66.36207 44.44507 16.82624 67.36574 44.44507 16.82465 63.25985 44.44507 20.6147 61.20616 44.44507 20.60751 57.95322 44.44507 16.9052 53.30409 44.44507 20.65508 54.36512 44.44507 20.63617 55.5985 44.44507 20.63617 56.71984 44.44507 16.9052 68.50424 44.44507 20.61965 69.09191 44.44507 16.82564 64.49323 44.44507 20.6147 65.1287 44.44507 16.82624 62.43954 44.44507 20.60751 63.25985 44.44507 16.8197 71.18867 60.03814 25.60448 71.18867 60.08073 25.01675 71.18867 61.17664 25.60448 71.18867 60.08073 21.22175 71.18867 61.21923 25.01675 71.18867 61.17664 29.39948 71.18867 60.17732 20.74063 71.18867 61.21923 21.22175 71.18867 60.17732 16.94563 71.18867 61.31582 20.74063 71.18867 61.76431 25.60548 71.18867 61.8069 25.01775 71.18867 62.99769 25.60548 71.18867 61.8069 21.22275 71.18867 63.04027 25.01775 71.18867 62.99769 29.40048 71.18867 61.90349 20.74163 71.18867 63.04027 21.22275 71.18867 61.90349 16.94663 71.18867 63.13687 20.74163 71.18867 44.44507 16.32867 71.18867 44.8823 16.98106 71.18867 44.44507 30.46505 71.18867 63.3252 16.32867 71.18867 44.78571 21.25719 71.18867 44.74312 25.63991 71.18867 46.11567 16.98106 71.18867 47.1767 16.96215 71.18867 46.11567 20.77606 71.18867 47.08011 21.23827 71.18867 47.03753 25.621 71.18867 48.41008 16.96215 71.18867 49.53142 17.02618 71.18867 48.41008 20.75715 71.18867 49.43483 21.30231 71.18867 49.39224 25.68503 71.18867 51.74166 16.96161 71.18867 50.7648 17.02618 71.18867 50.7648 20.82118 71.18867 51.64507 21.23773 71.18867 51.60248 25.62046 71.18867 52.97503 16.96161 71.18867 54.01774 16.93349 71.18867 52.97503 20.75661 71.18867 53.92115 21.20962 71.18867 53.87857 25.59234 71.18867 55.25112 16.93349 71.18867 56.07143 16.94068 71.18867 55.25112 20.72849 71.18867 55.97484 21.2168 71.18867 55.93225 25.59953 71.18867 57.30481 16.94068 71.18867 57.94028 16.94722 71.18867 57.30481 20.73568 71.18867 57.84368 21.22334 71.18867 57.8011 25.60607 71.18867 59.17365 16.94722 71.18867 59.17365 20.74222 71.18867 61.31582 16.94563 71.18867 63.13687 16.94663 71.18867 44.74312 29.43491 71.18867 63.3252 30.46505 71.18867 45.97649 29.43491 71.18867 47.03753 29.416 71.18867 46.01908 25.05219 71.18867 48.2709 29.416 71.18867 49.39224 29.48003 71.18867 48.31349 25.03327 71.18867 50.62562 29.48003 71.18867 51.60248 29.41546 71.18867 50.66821 25.09731 71.18867 52.83586 29.41546 71.18867 53.87857 29.38734 71.18867 52.87844 25.03273 71.18867 55.11194 29.38734 71.18867 55.93225 29.39453 71.18867 55.15453 25.00462 71.18867 57.16563 29.39453 71.18867 57.8011 29.40107 71.18867 57.20821 25.0118 71.18867 59.03447 29.40107 71.18867 60.03814 29.39948 71.18867 59.07706 25.01834 71.18867 61.76431 29.40048 71.18867 44.78571 25.05219 71.18867 45.97649 25.63991 71.18867 44.8823 20.77606 71.18867 46.01908 21.25719 71.18867 47.08011 25.03327 71.18867 48.2709 25.621 71.18867 47.1767 20.75715 71.18867 48.31349 21.23827 71.18867 49.43483 25.09731 71.18867 50.62562 25.68503 71.18867 49.53142 20.82118 71.18867 50.66821 21.30231 71.18867 51.64507 25.03273 71.18867 52.83586 25.62046 71.18867 51.74166 20.75661 71.18867 52.87844 21.23773 71.18867 53.92115 25.00462 71.18867 55.11194 25.59234 71.18867 54.01774 20.72849 71.18867 55.15453 21.20962 71.18867 55.97484 25.0118 71.18867 57.16563 25.59953 71.18867 56.07143 20.73568 71.18867 57.20821 21.2168 71.18867 57.84368 25.01834 71.18867 59.03447 25.60607 71.18867 57.94028 20.74222 71.18867 59.07706 21.22334 71.18867 59.07706 25.01834 71.18867 59.17365 20.74222 71.18867 59.07706 21.22334 71.18867 57.94028 20.74222 71.18867 57.94028 16.94722 71.18867 57.84368 21.22334 71.18867 59.03447 29.40107 71.18867 59.03447 25.60607 71.18867 57.84368 25.01834 71.18867 57.8011 25.60607 71.18867 57.20821 25.0118 71.18867 57.30481 20.73568 71.18867 57.20821 21.2168 71.18867 56.07143 20.73568 71.18867 56.07143 16.94068 71.18867 55.97484 21.2168 71.18867 57.16563 29.39453 71.18867 57.16563 25.59953 71.18867 55.97484 25.0118 71.18867 55.93225 25.59953 71.18867 55.15453 25.00462 71.18867 55.25112 20.72849 71.18867 55.15453 21.20962 71.18867 54.01774 20.72849 71.18867 54.01774 16.93349 71.18867 53.92115 21.20962 71.18867 55.11194 29.38734 71.18867 55.11194 25.59234 71.18867 53.92115 25.00462 71.18867 53.87857 25.59234 71.18867 52.87844 25.03273 71.18867 52.97503 20.75661 71.18867 52.87844 21.23773 71.18867 51.74166 20.75661 71.18867 51.74166 16.96161 71.18867 51.64507 21.23773 71.18867 52.83586 29.41546 71.18867 52.83586 25.62046 71.18867 51.64507 25.03273 71.18867 51.60248 25.62046 71.18867 50.66821 25.09731 71.18867 50.7648 20.82118 71.18867 50.66821 21.30231 71.18867 49.53142 20.82118 71.18867 49.53142 17.02618 71.18867 49.43483 21.30231 71.18867 50.62562 29.48003 71.18867 50.62562 25.68503 71.18867 49.43483 25.09731 71.18867 49.39224 25.68503 71.18867 48.31349 25.03327 71.18867 48.41008 20.75715 71.18867 48.31349 21.23827 71.18867 47.1767 20.75715 71.18867 47.1767 16.96215 71.18867 47.08011 21.23827 71.18867 48.2709 29.416 71.18867 48.2709 25.621 71.18867 47.08011 25.03327 71.18867 47.03753 25.621 71.18867 46.01908 25.05219 71.18867 46.11567 20.77606 71.18867 46.01908 21.25719 71.18867 44.8823 20.77606 71.18867 44.8823 16.98106 71.18867 44.78571 21.25719 71.18867 45.97649 29.43491 71.18867 45.97649 25.63991 71.18867 44.78571 25.05219 71.18867 44.74312 25.63991 71.18867 63.3252 16.32867 71.18867 63.13687 20.74163 71.18867 63.3252 30.46505 71.18867 63.04027 25.01775 71.18867 62.99769 29.40048 71.18867 61.76431 29.40048 71.18867 61.76431 25.60548 71.18867 61.31582 20.74063 71.18867 61.21923 25.01675 71.18867 61.17664 29.39948 71.18867 60.03814 29.39948 71.18867 60.03814 25.60448 71.18867 57.8011 29.40107 71.18867 55.93225 29.39453 71.18867 53.87857 29.38734 71.18867 51.60248 29.41546 71.18867 49.39224 29.48003 71.18867 47.03753 29.416 71.18867 44.74312 29.43491 71.18867 44.44507 30.46505 71.18867 63.13687 16.94663 71.18867 61.90349 16.94663 71.18867 61.8069 21.22275 71.18867 61.31582 16.94563 71.18867 60.17732 16.94563 71.18867 60.08073 21.22175 71.18867 59.17365 16.94722 71.18867 57.30481 16.94068 71.18867 55.25112 16.93349 71.18867 52.97503 16.96161 71.18867 50.7648 17.02618 71.18867 48.41008 16.96215 71.18867 46.11567 16.98106 71.18867 44.44507 16.32867 71.18867 63.04027 21.22275 71.18867 61.90349 20.74163 71.18867 62.99769 25.60548 71.18867 61.8069 25.01775 71.18867 61.21923 21.22175 71.18867 60.17732 20.74063 71.18867 61.17664 25.60448 71.18867 60.08073 25.01675 50.88542 44.70972 20.96835 50.88542 44.80632 21.44947 50.88542 45.9431 20.96835 50.88542 44.80632 25.24447 50.88542 46.03969 21.44947 50.88542 45.9431 17.17335 50.88542 44.8489 25.8322 50.88542 46.03969 25.24447 50.88542 44.8489 29.6272 50.88542 46.08228 25.8322 50.88542 61.73092 21.00279 50.88542 61.82751 21.48391 50.88542 62.96429 21.00279 50.88542 61.82751 25.27891 50.88542 63.06088 21.48391 50.88542 62.96429 17.20779 50.88542 61.8701 25.86664 50.88542 63.06088 25.27891 50.88542 61.8701 29.66164 50.88542 63.10347 25.86664 50.88542 44.44507 30.46505 50.88542 44.44507 16.32867 50.88542 63.3252 30.46505 50.88542 46.08228 29.6272 50.88542 46.66994 29.6262 50.88542 46.53077 20.96735 50.88542 46.62736 25.24348 50.88542 47.80844 29.6262 50.88542 48.81212 29.62779 50.88542 47.80844 25.8312 50.88542 48.67294 20.96895 50.88542 48.76953 25.24507 50.88542 50.04549 29.62779 50.88542 50.68096 29.62125 50.88542 50.04549 25.83279 50.88542 50.54178 20.9624 50.88542 50.63838 25.23853 50.88542 51.91434 29.62125 50.88542 52.73465 29.61407 50.88542 51.91434 25.82625 50.88542 52.59547 20.95522 50.88542 52.69206 25.23134 50.88542 53.96802 29.61407 50.88542 55.01073 29.64218 50.88542 53.96802 25.81907 50.88542 54.87156 20.98333 50.88542 54.96815 25.25945 50.88542 56.24411 29.64218 50.88542 57.22097 29.70676 50.88542 56.24411 25.84718 50.88542 57.08179 21.04791 50.88542 57.17838 25.32403 50.88542 58.45434 29.70676 50.88542 59.57569 29.64272 50.88542 58.45434 25.91176 50.88542 59.43651 20.98387 50.88542 59.5331 25.26 50.88542 60.80906 29.64272 50.88542 60.80906 25.84772 50.88542 63.10347 29.66164 50.88542 44.70972 17.17335 50.88542 63.3252 16.32867 50.88542 46.53077 17.17235 50.88542 47.66927 17.17235 50.88542 48.67294 17.17395 50.88542 47.76586 21.44848 50.88542 49.90631 17.17395 50.88542 50.54178 17.1674 50.88542 50.0029 21.45007 50.88542 51.77516 17.1674 50.88542 52.59547 17.16022 50.88542 51.87175 21.44353 50.88542 53.82884 17.16022 50.88542 54.87156 17.18833 50.88542 53.92544 21.43634 50.88542 56.10493 17.18833 50.88542 57.08179 17.25291 50.88542 56.20152 21.46445 50.88542 58.31517 17.25291 50.88542 59.43651 17.18887 50.88542 58.41176 21.52903 50.88542 60.66989 17.18887 50.88542 61.73092 17.20779 50.88542 60.76648 21.465 50.88542 59.5331 21.465 50.88542 60.66989 20.98387 50.88542 59.57569 25.84772 50.88542 60.76648 25.26 50.88542 57.17838 21.52903 50.88542 58.31517 21.04791 50.88542 57.22097 25.91176 50.88542 58.41176 25.32403 50.88542 54.96815 21.46445 50.88542 56.10493 20.98333 50.88542 55.01073 25.84718 50.88542 56.20152 25.25945 50.88542 52.69206 21.43634 50.88542 53.82884 20.95522 50.88542 52.73465 25.81907 50.88542 53.92544 25.23134 50.88542 50.63838 21.44353 50.88542 51.77516 20.9624 50.88542 50.68096 25.82625 50.88542 51.87175 25.23853 50.88542 48.76953 21.45007 50.88542 49.90631 20.96895 50.88542 48.81212 25.83279 50.88542 50.0029 25.24507 50.88542 46.62736 21.44848 50.88542 47.66927 20.96735 50.88542 46.66994 25.8312 50.88542 47.76586 25.24348 50.88542 47.76586 21.44848 50.88542 47.80844 25.8312 50.88542 47.76586 25.24348 50.88542 46.66994 25.8312 50.88542 46.66994 29.6262 50.88542 46.62736 25.24348 50.88542 47.66927 17.17235 50.88542 47.66927 20.96735 50.88542 46.62736 21.44848 50.88542 46.53077 20.96735 50.88542 50.0029 21.45007 50.88542 50.04549 25.83279 50.88542 50.0029 25.24507 50.88542 48.81212 25.83279 50.88542 48.81212 29.62779 50.88542 48.76953 25.24507 50.88542 49.90631 17.17395 50.88542 49.90631 20.96895 50.88542 48.76953 21.45007 50.88542 48.67294 20.96895 50.88542 51.87175 21.44353 50.88542 51.91434 25.82625 50.88542 51.87175 25.23853 50.88542 50.68096 25.82625 50.88542 50.68096 29.62125 50.88542 50.63838 25.23853 50.88542 51.77516 17.1674 50.88542 51.77516 20.9624 50.88542 50.63838 21.44353 50.88542 50.54178 20.9624 50.88542 53.92544 21.43634 50.88542 53.96802 25.81907 50.88542 53.92544 25.23134 50.88542 52.73465 25.81907 50.88542 52.73465 29.61407 50.88542 52.69206 25.23134 50.88542 53.82884 17.16022 50.88542 53.82884 20.95522 50.88542 52.69206 21.43634 50.88542 52.59547 20.95522 50.88542 56.20152 21.46445 50.88542 56.24411 25.84718 50.88542 56.20152 25.25945 50.88542 55.01073 25.84718 50.88542 55.01073 29.64218 50.88542 54.96815 25.25945 50.88542 56.10493 17.18833 50.88542 56.10493 20.98333 50.88542 54.96815 21.46445 50.88542 54.87156 20.98333 50.88542 58.41176 21.52903 50.88542 58.45434 25.91176 50.88542 58.41176 25.32403 50.88542 57.22097 25.91176 50.88542 57.22097 29.70676 50.88542 57.17838 25.32403 50.88542 58.31517 17.25291 50.88542 58.31517 21.04791 50.88542 57.17838 21.52903 50.88542 57.08179 21.04791 50.88542 60.76648 21.465 50.88542 60.80906 25.84772 50.88542 60.76648 25.26 50.88542 59.57569 25.84772 50.88542 59.57569 29.64272 50.88542 59.5331 25.26 50.88542 60.66989 17.18887 50.88542 60.66989 20.98387 50.88542 59.5331 21.465 50.88542 59.43651 20.98387 50.88542 63.3252 30.46505 50.88542 63.10347 25.86664 50.88542 63.3252 16.32867 50.88542 63.06088 21.48391 50.88542 62.96429 17.20779 50.88542 61.73092 17.20779 50.88542 61.73092 21.00279 50.88542 59.43651 17.18887 50.88542 57.08179 17.25291 50.88542 54.87156 17.18833 50.88542 52.59547 17.16022 50.88542 50.54178 17.1674 50.88542 48.67294 17.17395 50.88542 46.53077 17.17235 50.88542 46.08228 25.8322 50.88542 46.03969 21.44947 50.88542 45.9431 17.17335 50.88542 44.70972 17.17335 50.88542 44.70972 20.96835 50.88542 44.44507 16.32867 50.88542 63.10347 29.66164 50.88542 61.8701 29.66164 50.88542 61.82751 25.27891 50.88542 60.80906 29.64272 50.88542 58.45434 29.70676 50.88542 56.24411 29.64218 50.88542 53.96802 29.61407 50.88542 51.91434 29.62125 50.88542 50.04549 29.62779 50.88542 47.80844 29.6262 50.88542 46.08228 29.6272 50.88542 44.8489 29.6272 50.88542 44.80632 25.24447 50.88542 44.44507 30.46505 50.88542 63.06088 25.27891 50.88542 61.8701 25.86664 50.88542 62.96429 21.00279 50.88542 61.82751 21.48391 50.88542 46.03969 25.24447 50.88542 44.8489 25.8322 50.88542 45.9431 20.96835 50.88542 44.80632 21.44947 59.86023 63.3252 25.66123 59.03992 63.3252 25.66842 59.86023 63.3252 29.45623 57.80654 63.3252 25.66842 59.03992 63.3252 29.46342 61.0936 63.3252 29.45623 57.17107 63.3252 25.67496 57.80654 63.3252 29.46342 54.93402 63.3252 25.67336 53.79552 63.3252 25.67336 55.9377 63.3252 25.67496 57.17107 63.3252 29.46996 53.20786 63.3252 25.67436 53.79552 63.3252 29.46836 51.97448 63.3252 25.67436 53.20786 63.3252 29.46936 54.93402 63.3252 29.46836 66.70127 63.3252 25.68988 65.57992 63.3252 25.75392 66.70127 63.3252 29.48488 64.34655 63.3252 25.75392 65.57992 63.3252 29.54892 67.93464 63.3252 29.48488 68.99568 63.3252 29.5038 70.22905 63.3252 29.5038 50.88542 63.3252 16.32867 51.8353 63.3252 17.01551 71.18867 63.3252 16.32867 50.88542 63.3252 30.46505 59.72105 63.3252 17.00238 57.66736 63.3252 17.00957 53.65635 63.3252 17.01452 51.8353 63.3252 20.81051 51.9319 63.3252 21.29164 53.06868 63.3252 20.81051 55.79852 63.3252 20.81111 57.03189 63.3252 20.81111 61.99714 63.3252 20.82549 63.23051 63.3252 20.82549 64.20737 63.3252 20.89007 65.44075 63.3252 20.89007 59.81764 63.3252 21.2785 57.76395 63.3252 21.28569 53.75294 63.3252 21.29064 51.9319 63.3252 25.08664 53.16527 63.3252 25.08664 55.89511 63.3252 25.08723 57.12848 63.3252 25.08723 62.09373 63.3252 25.10161 63.3271 63.3252 25.10161 64.30396 63.3252 25.16619 65.53734 63.3252 25.16619 51.97448 63.3252 29.46936 55.9377 63.3252 29.46996 62.13631 63.3252 29.48434 63.36969 63.3252 29.48434 64.34655 63.3252 29.54892 70.08987 63.3252 17.04995 71.18867 63.3252 30.46505 67.79546 63.3252 17.03103 60.95442 63.3252 17.00238 63.23051 63.3252 17.03049 61.99714 63.3252 17.03049 66.56209 63.3252 17.03103 68.8565 63.3252 17.04995 70.18646 63.3252 21.32607 70.08987 63.3252 20.84495 67.89206 63.3252 21.30716 61.05102 63.3252 21.2785 63.3271 63.3252 21.30661 62.09373 63.3252 21.30661 66.65868 63.3252 21.30716 68.95309 63.3252 21.32607 70.18646 63.3252 25.12107 70.22905 63.3252 25.7088 67.93464 63.3252 25.68988 61.0936 63.3252 25.66123 63.36969 63.3252 25.68934 62.13631 63.3252 25.68934 68.99568 63.3252 25.7088 58.99733 63.3252 21.28569 59.81764 63.3252 25.0735 58.99733 63.3252 25.08069 61.05102 63.3252 25.0735 57.12848 63.3252 21.29223 57.76395 63.3252 25.08069 54.89144 63.3252 21.29064 55.89511 63.3252 21.29223 53.16527 63.3252 21.29164 53.75294 63.3252 25.08564 54.89144 63.3252 25.08564 65.53734 63.3252 21.37119 66.65868 63.3252 25.10216 64.30396 63.3252 21.37119 67.89206 63.3252 25.10216 68.95309 63.3252 25.12107 58.90074 63.3252 17.00957 59.72105 63.3252 20.79738 58.90074 63.3252 20.80457 60.95442 63.3252 20.79738 57.03189 63.3252 17.01611 57.66736 63.3252 20.80457 54.79485 63.3252 17.01452 55.79852 63.3252 17.01611 53.06868 63.3252 17.01551 53.65635 63.3252 20.80952 54.79485 63.3252 20.80952 65.44075 63.3252 17.09507 66.56209 63.3252 20.82603 64.20737 63.3252 17.09507 67.79546 63.3252 20.82603 68.8565 63.3252 20.84495 53.06868 63.3252 20.81051 54.79485 63.3252 20.80952 55.79852 63.3252 20.81111 55.79852 63.3252 17.01611 54.79485 63.3252 17.01452 57.03189 63.3252 20.81111 58.90074 63.3252 20.80457 61.99714 63.3252 20.82549 60.95442 63.3252 20.79738 61.99714 63.3252 17.03049 60.95442 63.3252 17.00238 64.20737 63.3252 20.89007 63.23051 63.3252 20.82549 64.20737 63.3252 17.09507 63.23051 63.3252 17.03049 66.56209 63.3252 17.03103 68.8565 63.3252 20.84495 67.79546 63.3252 20.82603 68.8565 63.3252 17.04995 67.79546 63.3252 17.03103 70.08987 63.3252 20.84495 65.44075 63.3252 20.89007 66.56209 63.3252 20.82603 65.44075 63.3252 17.09507 53.65635 63.3252 20.80952 53.06868 63.3252 17.01551 51.8353 63.3252 17.01551 53.65635 63.3252 17.01452 57.66736 63.3252 20.80457 57.03189 63.3252 17.01611 57.66736 63.3252 17.00957 59.72105 63.3252 20.79738 58.90074 63.3252 17.00957 59.72105 63.3252 17.00238 53.16527 63.3252 25.08664 54.89144 63.3252 25.08564 55.89511 63.3252 25.08723 55.89511 63.3252 21.29223 54.89144 63.3252 21.29064 57.12848 63.3252 25.08723 58.99733 63.3252 25.08069 62.09373 63.3252 25.10161 61.05102 63.3252 25.0735 62.09373 63.3252 21.30661 61.05102 63.3252 21.2785 64.30396 63.3252 25.16619 63.3271 63.3252 25.10161 64.30396 63.3252 21.37119 63.3271 63.3252 21.30661 66.65868 63.3252 21.30716 68.95309 63.3252 25.12107 67.89206 63.3252 25.10216 68.95309 63.3252 21.32607 67.89206 63.3252 21.30716 70.18646 63.3252 25.12107 65.53734 63.3252 25.16619 66.65868 63.3252 25.10216 65.53734 63.3252 21.37119 53.75294 63.3252 25.08564 53.16527 63.3252 21.29164 51.9319 63.3252 21.29164 53.75294 63.3252 21.29064 57.76395 63.3252 25.08069 57.12848 63.3252 21.29223 57.76395 63.3252 21.28569 59.81764 63.3252 25.0735 58.99733 63.3252 21.28569 59.81764 63.3252 21.2785 53.20786 63.3252 29.46936 54.93402 63.3252 29.46836 55.9377 63.3252 29.46996 55.9377 63.3252 25.67496 54.93402 63.3252 25.67336 57.17107 63.3252 29.46996 59.03992 63.3252 29.46342 62.13631 63.3252 29.48434 61.0936 63.3252 29.45623 62.13631 63.3252 25.68934 61.0936 63.3252 25.66123 64.34655 63.3252 29.54892 63.36969 63.3252 29.48434 64.34655 63.3252 25.75392 63.36969 63.3252 25.68934 66.70127 63.3252 25.68988 68.99568 63.3252 29.5038 67.93464 63.3252 29.48488 68.99568 63.3252 25.7088 67.93464 63.3252 25.68988 50.88542 63.3252 30.46505 65.57992 63.3252 29.54892 71.18867 63.3252 30.46505 70.22905 63.3252 29.5038 70.22905 63.3252 25.7088 59.86023 63.3252 25.66123 70.18646 63.3252 21.32607 70.08987 63.3252 17.04995 71.18867 63.3252 16.32867 51.97448 63.3252 29.46936 51.97448 63.3252 25.67436 53.79552 63.3252 25.67336 57.80654 63.3252 25.66842 51.9319 63.3252 25.08664 51.8353 63.3252 20.81051 50.88542 63.3252 16.32867 66.70127 63.3252 29.48488 65.57992 63.3252 25.75392 53.79552 63.3252 29.46836 53.20786 63.3252 25.67436 57.80654 63.3252 29.46342 57.17107 63.3252 25.67496 59.86023 63.3252 29.45623 59.03992 63.3252 25.66842 + + + + + + + + + + 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -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 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 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 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 70.62073 44.95786 20.50317 70.62073 44.95786 30.46505 63.64954 48.05032 37.12085 63.64954 60.98956 37.12085 71.18867 63.3252 30.46505 + + + + + + + + + + + + + +

1 0 2 1 4 3

+
+ + +

3 2

+
+
+
+ + + + 50.88542 44.44507 30.46505 51.26623 44.95786 30.46505 51.26623 44.95786 20.50317 58.97882 46.66503 37.22875 58.97882 61.26384 37.22875 58.97882 61.45073 37.28572 50.88542 63.3252 30.46505 + + + + + + + + + + + + + +

1 0 1 2 1 3 5 4 6 5

+
+ + +

3 4

+
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0.7215686 0.5254902 0.04313725 1 + + + + + + + + + + + 0.3764706 0.3764706 0.3764706 1 + + + + + + + + + + + 0.827451 0.7411765 0.5647059 1 + + + + + + + + + + + 0.4666667 0.345098 0.2117647 1 + + + + + + + + + + + 0.1372549 0.1372549 0.1372549 1 + + + + + + + + + + + 0 0 0 1 + + + + + + + + + + + 0.654902 0.3960784 0.3215686 1 + + + + + + + + + + + 0.1411765 0.1843137 0.2588235 1 + + + + + + + + + + + 0 0 0 1 + + + 1 + + + + + + + + + + + 1 0.6 0.6 1 + + + + + + + + + + + 0.8 0.6392157 0.6392157 1 + + + + + + + + + + + 0.8 0 0 1 + + + + + + + + + + + 0.8 0.6 1 1 + + + 1 + + + + + + + + + +
diff --git a/cram_pr2/cram_pr2_shopping_demo/dae_files/Denkmit.dae b/cram_demos/cram_pr2_shopping_demo/resource/dae_files/Denkmit.dae similarity index 100% rename from cram_pr2/cram_pr2_shopping_demo/dae_files/Denkmit.dae rename to cram_demos/cram_pr2_shopping_demo/resource/dae_files/Denkmit.dae diff --git a/cram_pr2/cram_pr2_shopping_demo/dae_files/Dove.dae b/cram_demos/cram_pr2_shopping_demo/resource/dae_files/Dove.dae similarity index 100% rename from cram_pr2/cram_pr2_shopping_demo/dae_files/Dove.dae rename to cram_demos/cram_pr2_shopping_demo/resource/dae_files/Dove.dae diff --git a/cram_pr2/cram_pr2_shopping_demo/dae_files/Heitmann.dae b/cram_demos/cram_pr2_shopping_demo/resource/dae_files/Heitmann.dae similarity index 100% rename from cram_pr2/cram_pr2_shopping_demo/dae_files/Heitmann.dae rename to cram_demos/cram_pr2_shopping_demo/resource/dae_files/Heitmann.dae diff --git a/cram_pr2/cram_pr2_shopping_demo/dae_files/Somat.dae b/cram_demos/cram_pr2_shopping_demo/resource/dae_files/Somat.dae similarity index 100% rename from cram_pr2/cram_pr2_shopping_demo/dae_files/Somat.dae rename to cram_demos/cram_pr2_shopping_demo/resource/dae_files/Somat.dae diff --git a/cram_pr2/cram_pr2_shopping_demo/dae_files/untitled.dae b/cram_demos/cram_pr2_shopping_demo/resource/dae_files/untitled.dae similarity index 100% rename from cram_pr2/cram_pr2_shopping_demo/dae_files/untitled.dae rename to cram_demos/cram_pr2_shopping_demo/resource/dae_files/untitled.dae diff --git a/cram_demos/cram_pr2_shopping_demo/resource/decimate/denkmit.stl b/cram_demos/cram_pr2_shopping_demo/resource/decimate/denkmit.stl new file mode 100644 index 0000000000..c2401be23f Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/decimate/denkmit.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/decimate/dove.stl b/cram_demos/cram_pr2_shopping_demo/resource/decimate/dove.stl new file mode 100644 index 0000000000..7758ff0153 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/decimate/dove.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/decimate/heitmann.stl b/cram_demos/cram_pr2_shopping_demo/resource/decimate/heitmann.stl new file mode 100644 index 0000000000..eff81be451 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/decimate/heitmann.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/decimate/somat.stl b/cram_demos/cram_pr2_shopping_demo/resource/decimate/somat.stl new file mode 100644 index 0000000000..dcc9c41105 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/decimate/somat.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/denkmit.stl b/cram_demos/cram_pr2_shopping_demo/resource/denkmit.stl new file mode 100644 index 0000000000..c2401be23f Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/denkmit.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/denkmit_allzweckreiniger.stl b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_allzweckreiniger.stl new file mode 100644 index 0000000000..93d5d1d3ab Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_allzweckreiniger.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/denkmit_allzweckreiniger_frueling.stl b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_allzweckreiniger_frueling.stl new file mode 100644 index 0000000000..c76c10052c Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_allzweckreiniger_frueling.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/denkmit_allzweckreiniger_limette.stl b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_allzweckreiniger_limette.stl new file mode 100644 index 0000000000..b8f7f2cf4a Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_allzweckreiniger_limette.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/denkmit_edelstahl_reiniger.stl b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_edelstahl_reiniger.stl new file mode 100644 index 0000000000..38c271748e Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_edelstahl_reiniger.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/denkmit_edelstahl_reiniger_spray.stl b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_edelstahl_reiniger_spray.stl new file mode 100644 index 0000000000..6914b7a1c4 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_edelstahl_reiniger_spray.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/denkmit_entkalker.stl b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_entkalker.stl new file mode 100644 index 0000000000..09f0937691 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_entkalker.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/denkmit_glaskeramik_reiniger.stl b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_glaskeramik_reiniger.stl new file mode 100644 index 0000000000..165b670991 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_glaskeramik_reiniger.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/denkmit_maschienen_entkalker.stl b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_maschienen_entkalker.stl new file mode 100644 index 0000000000..916f449ea3 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_maschienen_entkalker.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/denkmit_maschienenpfleger.stl b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_maschienenpfleger.stl new file mode 100644 index 0000000000..34d985db24 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_maschienenpfleger.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/denkmit_spezialsalz.stl b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_spezialsalz.stl new file mode 100644 index 0000000000..60133a64fd Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_spezialsalz.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/denkmit_spuelmaschienen_tabs_allinone.stl b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_spuelmaschienen_tabs_allinone.stl new file mode 100644 index 0000000000..677974168c Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_spuelmaschienen_tabs_allinone.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/denkmit_spuelmaschienen_tabs_classic.stl b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_spuelmaschienen_tabs_classic.stl new file mode 100644 index 0000000000..e9119ddb85 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_spuelmaschienen_tabs_classic.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/denkmit_spuelmaschienen_tabs_nature.stl b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_spuelmaschienen_tabs_nature.stl new file mode 100644 index 0000000000..ed70d2aa73 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_spuelmaschienen_tabs_nature.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/denkmit_spuelmaschienen_tabs_power.stl b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_spuelmaschienen_tabs_power.stl new file mode 100644 index 0000000000..d08f49ef6f Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_spuelmaschienen_tabs_power.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/denkmit_spuelmaschienen_tabs_revolution.stl b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_spuelmaschienen_tabs_revolution.stl new file mode 100644 index 0000000000..25ffa2a0b4 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/denkmit_spuelmaschienen_tabs_revolution.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/der_general_allzweckreiniger.stl b/cram_demos/cram_pr2_shopping_demo/resource/der_general_allzweckreiniger.stl new file mode 100644 index 0000000000..cc56cac23b Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/der_general_allzweckreiniger.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/dm_shelves.urdf b/cram_demos/cram_pr2_shopping_demo/resource/dm_shelves.urdf new file mode 100644 index 0000000000..6ef791c655 --- /dev/null +++ b/cram_demos/cram_pr2_shopping_demo/resource/dm_shelves.urdf @@ -0,0 +1,1460 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/cram_demos/cram_pr2_shopping_demo/resource/domestos_allzweckreiniger.stl b/cram_demos/cram_pr2_shopping_demo/resource/domestos_allzweckreiniger.stl new file mode 100644 index 0000000000..8467349aba Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/domestos_allzweckreiniger.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/dove.stl b/cram_demos/cram_pr2_shopping_demo/resource/dove.stl new file mode 100644 index 0000000000..7758ff0153 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/dove.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/finish_deo.stl b/cram_demos/cram_pr2_shopping_demo/resource/finish_deo.stl new file mode 100644 index 0000000000..981e216138 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/finish_deo.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/finish_klarspueler.stl b/cram_demos/cram_pr2_shopping_demo/resource/finish_klarspueler.stl new file mode 100644 index 0000000000..1e182a6003 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/finish_klarspueler.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/finish_maschienenpfleger.stl b/cram_demos/cram_pr2_shopping_demo/resource/finish_maschienenpfleger.stl new file mode 100644 index 0000000000..6a59a0a72b Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/finish_maschienenpfleger.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/finish_spezialsalz.stl b/cram_demos/cram_pr2_shopping_demo/resource/finish_spezialsalz.stl new file mode 100644 index 0000000000..1fd96351db Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/finish_spezialsalz.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/finish_spuelmaschienen_protector.stl b/cram_demos/cram_pr2_shopping_demo/resource/finish_spuelmaschienen_protector.stl new file mode 100644 index 0000000000..ed061e2bcd Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/finish_spuelmaschienen_protector.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/finish_spuelmaschienen_pulver.stl b/cram_demos/cram_pr2_shopping_demo/resource/finish_spuelmaschienen_pulver.stl new file mode 100644 index 0000000000..a508b22870 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/finish_spuelmaschienen_pulver.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/finish_spuelmaschienen_tabs_classic.stl b/cram_demos/cram_pr2_shopping_demo/resource/finish_spuelmaschienen_tabs_classic.stl new file mode 100644 index 0000000000..145d6e8079 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/finish_spuelmaschienen_tabs_classic.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/finish_spuelmaschienen_tabs_classic_vorratspack.stl b/cram_demos/cram_pr2_shopping_demo/resource/finish_spuelmaschienen_tabs_classic_vorratspack.stl new file mode 100644 index 0000000000..6783c39ea8 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/finish_spuelmaschienen_tabs_classic_vorratspack.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/finish_spuelmaschienen_tabs_quantum.stl b/cram_demos/cram_pr2_shopping_demo/resource/finish_spuelmaschienen_tabs_quantum.stl new file mode 100644 index 0000000000..8790f16e41 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/finish_spuelmaschienen_tabs_quantum.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/heitmann.stl b/cram_demos/cram_pr2_shopping_demo/resource/heitmann.stl new file mode 100644 index 0000000000..784fb2200c Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/heitmann.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/heitmann_citronensaeure.stl b/cram_demos/cram_pr2_shopping_demo/resource/heitmann_citronensaeure.stl new file mode 100644 index 0000000000..cbd1c58844 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/heitmann_citronensaeure.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/heitmann_citronensaeure_box.stl b/cram_demos/cram_pr2_shopping_demo/resource/heitmann_citronensaeure_box.stl new file mode 100644 index 0000000000..78416c19b4 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/heitmann_citronensaeure_box.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/heitmann_old.stl b/cram_demos/cram_pr2_shopping_demo/resource/heitmann_old.stl new file mode 100644 index 0000000000..eff81be451 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/heitmann_old.stl differ diff --git a/cram_pr2/cram_pr2_shopping_demo/resource/denkmit.stl b/cram_demos/cram_pr2_shopping_demo/resource/high_res/denkmit.stl similarity index 100% rename from cram_pr2/cram_pr2_shopping_demo/resource/denkmit.stl rename to cram_demos/cram_pr2_shopping_demo/resource/high_res/denkmit.stl diff --git a/cram_pr2/cram_pr2_shopping_demo/resource/dove.stl b/cram_demos/cram_pr2_shopping_demo/resource/high_res/dove.stl similarity index 100% rename from cram_pr2/cram_pr2_shopping_demo/resource/dove.stl rename to cram_demos/cram_pr2_shopping_demo/resource/high_res/dove.stl diff --git a/cram_pr2/cram_pr2_shopping_demo/resource/heitmann.stl b/cram_demos/cram_pr2_shopping_demo/resource/high_res/heitmann.stl similarity index 100% rename from cram_pr2/cram_pr2_shopping_demo/resource/heitmann.stl rename to cram_demos/cram_pr2_shopping_demo/resource/high_res/heitmann.stl diff --git a/cram_pr2/cram_pr2_shopping_demo/resource/somat.stl b/cram_demos/cram_pr2_shopping_demo/resource/high_res/somat.stl similarity index 100% rename from cram_pr2/cram_pr2_shopping_demo/resource/somat.stl rename to cram_demos/cram_pr2_shopping_demo/resource/high_res/somat.stl diff --git a/cram_demos/cram_pr2_shopping_demo/resource/kuehne_essig_essenz.stl b/cram_demos/cram_pr2_shopping_demo/resource/kuehne_essig_essenz.stl new file mode 100644 index 0000000000..ee370823ed Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/kuehne_essig_essenz.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/meister_proper_allzweckreiniger.stl b/cram_demos/cram_pr2_shopping_demo/resource/meister_proper_allzweckreiniger.stl new file mode 100644 index 0000000000..d01140da42 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/meister_proper_allzweckreiniger.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/sagrotan_allzweckreiniger.stl b/cram_demos/cram_pr2_shopping_demo/resource/sagrotan_allzweckreiniger.stl new file mode 100644 index 0000000000..f25c73a29b Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/sagrotan_allzweckreiniger.stl differ diff --git a/cram_pr2/cram_pr2_shopping_demo/resource/shelf.urdf b/cram_demos/cram_pr2_shopping_demo/resource/shelf.urdf similarity index 86% rename from cram_pr2/cram_pr2_shopping_demo/resource/shelf.urdf rename to cram_demos/cram_pr2_shopping_demo/resource/shelf.urdf index 2df2bf55bd..742ea91195 100644 --- a/cram_pr2/cram_pr2_shopping_demo/resource/shelf.urdf +++ b/cram_demos/cram_pr2_shopping_demo/resource/shelf.urdf @@ -43,15 +43,15 @@ - + - + - + - + @@ -61,13 +61,13 @@ - + - + @@ -75,15 +75,15 @@ - + - + - + - + @@ -93,13 +93,13 @@ - + - + @@ -107,15 +107,15 @@ - + - + - + - + @@ -125,13 +125,13 @@ - + - + @@ -139,15 +139,15 @@ - + - + - + - + @@ -157,13 +157,13 @@ - + - + @@ -172,25 +172,25 @@ - + - + - + - + @@ -222,7 +222,7 @@ - + diff --git a/cram_demos/cram_pr2_shopping_demo/resource/somat.stl b/cram_demos/cram_pr2_shopping_demo/resource/somat.stl new file mode 100644 index 0000000000..dcc9c41105 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/somat.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/somat_spuelmaschienen_pulver.stl b/cram_demos/cram_pr2_shopping_demo/resource/somat_spuelmaschienen_pulver.stl new file mode 100644 index 0000000000..2e8af99be1 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/somat_spuelmaschienen_pulver.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/somat_spuelmaschienen_tabs_classic.stl b/cram_demos/cram_pr2_shopping_demo/resource/somat_spuelmaschienen_tabs_classic.stl new file mode 100644 index 0000000000..06bfa6a196 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/somat_spuelmaschienen_tabs_classic.stl differ diff --git a/cram_demos/cram_pr2_shopping_demo/resource/somat_spuelmaschienen_tabs_extra.stl b/cram_demos/cram_pr2_shopping_demo/resource/somat_spuelmaschienen_tabs_extra.stl new file mode 100644 index 0000000000..494fa187d4 Binary files /dev/null and b/cram_demos/cram_pr2_shopping_demo/resource/somat_spuelmaschienen_tabs_extra.stl differ diff --git a/cram_pr2/cram_pr2_shopping_demo/resource/table.urdf b/cram_demos/cram_pr2_shopping_demo/resource/table.urdf similarity index 100% rename from cram_pr2/cram_pr2_shopping_demo/resource/table.urdf rename to cram_demos/cram_pr2_shopping_demo/resource/table.urdf diff --git a/cram_pr2/cram_pr2_shopping_demo/src/package.lisp b/cram_demos/cram_pr2_shopping_demo/src/package.lisp similarity index 97% rename from cram_pr2/cram_pr2_shopping_demo/src/package.lisp rename to cram_demos/cram_pr2_shopping_demo/src/package.lisp index 5be3589ea2..b84017f170 100644 --- a/cram_pr2/cram_pr2_shopping_demo/src/package.lisp +++ b/cram_demos/cram_pr2_shopping_demo/src/package.lisp @@ -30,6 +30,7 @@ (in-package :cl-user) (defpackage cram-pr2-shopping-demo + (:nicknames #:pr2-shop-demo #:demo) (:use #:common-lisp #:cram-prolog) (:export)) diff --git a/cram_demos/cram_pr2_shopping_demo/src/plans.lisp b/cram_demos/cram_pr2_shopping_demo/src/plans.lisp new file mode 100644 index 0000000000..e433b77cf9 --- /dev/null +++ b/cram_demos/cram_pr2_shopping_demo/src/plans.lisp @@ -0,0 +1,106 @@ +;;; +;;; Copyright (c) 2019, Jonas Dech transform + (btr:pose + (btr:rigid-body + (btr:get-environment-object) + (nth i levels)))))) + ;; Loop for the objects + (loop for j from 0 to (- (length level-poses) 1) + do (let* ((shelf-T-object + (cram-tf:list->transform `(,(nth j level-poses) (0 0 1 0)))) + (world-T-object + (cl-transforms:transform* world-T-shelf shelf-T-object))) + (push (cl-transforms:transform->pose world-T-object) tmp))) + (push (reverse tmp) res) + (setf tmp '()))) + (reverse res))) + + +(defun spawn-objects-new () + (let ((poses (convert-shelf-poses "shelf-1" *shelf-1-poses*)) + (object-types '((:denkmit-edelstahl-reiniger-spray + :denkmit-edelstahl-reiniger + :denkmit-glaskeramik-reiniger + :denkmit-maschienen-entkalker + :denkmit-entkalker + :kuehne-essig-essenz + :heitmann-citronensaeure) + (:finish-deo + :finish-spuelmaschienen-tabs-quantum + :finish-spuelmaschienen-tabs-classic + :finish-spuelmaschienen-tabs-classic-vorratspack) + (:finish-spuelmaschienen-pulver + :finish-spuelmaschienen-protector + :somat-spuelmaschienen-tabs-extra + :somat-spuelmaschienen-tabs-classic + :somat-spuelmaschienen-pulver) + (:denkmit-spezialsalz + :denkmit-spuelmaschienen-tabs-power + :denkmit-spuelmaschienen-tabs-revolution + :denkmit-spuelmaschienen-tabs-classic + :denkmit-spuelmaschienen-tabs-nature) + (:denkmit-maschienenpfleger + :denkmit-maschienenpfleger + :finish-maschienenpfleger + :finish-spezialsalz + :finish-klarspueler + :denkmit-spuelmaschienen-tabs-allinone) + (:domestos-allzweckreiniger + :sagrotan-allzweckreiniger + :denkmit-allzweckreiniger + :denkmit-allzweckreiniger-frueling + :meister-proper-allzweckreiniger + :denkmit-allzweckreiniger-limette + :der-general-allzweckreiniger)))) + ;; Loop for shelf level + (loop for i from 0 to (- (length poses) 1) + ;; loop for objects in the level + do (loop for j from 0 to (- (length (nth i poses)) 1) + do (spawn-object-n-times (nth j (nth i object-types)) + (cram-tf:pose->list (nth j(nth i poses))) + (+ (random 3) 1) + `(,(float (/ (random 10) 10)) + ,(float (/ (random 10) 10)) + ,(float (/ (random 10) 10)))))))) + +(defun spawn-object-n-times (type pose times color) + (loop for i from 0 to times + do (let ((name (intern (string-upcase (format nil "~a-~a" type i)) :keyword))) + (setf (second (first pose)) (+ (second (first pose)) 0.13)) + (when (btr:object btr:*current-bullet-world* name) + (setf i (+ i times) + name (intern (string-upcase (format nil "~a-~a" type i)) :keyword))) + (btr-utils:spawn-object name type :pose pose :color color)))) + +(defun spawn-shelf () + (let ((shelve-urdf + (cl-urdf:parse-urdf + (roslisp:get-param "shelf_description")))) + (prolog:prolog + `(and (btr:bullet-world ?world) + (rob-int:environment-name ?environment-name) + (assert (btr:object ?world :urdf ?environment-name ((0 0 0) (0 0 0 1)) + :urdf ,shelve-urdf + :collision-group :static-filter + :collision-mask (:default-filter + :character-filter))))))) + +(defun spawn-robot () + (setf rob-int:*robot-urdf* + (cl-urdf:parse-urdf + (roslisp:get-param rob-int:*robot-description-parameter*))) + (prolog:prolog + `(and (btr:bullet-world ?world) + (rob-int:robot ?robot) + (assert (btr:object ?world :urdf ?robot ((0 0 0) (0 0 0 1)) + :urdf ,rob-int:*robot-urdf*)) + (assert (btr:joint-state ?world ?robot (("torso_lift_joint" 0.15d0))))))) + +(defun spawn-basket () + (let* ((map-T-wrist (btr:link-pose (btr:get-robot-object) "l_wrist_roll_link")) + (wrist-T-basket (cl-transforms:make-transform + (cl-transforms:make-3d-vector 0.36 0 -0.15) + (cl-transforms:make-quaternion 0.0d0 -0.7071067811865475d0 + 0.0d0 0.7071067811865475d0))) + (map-T-basket (cl-transforms:transform* + (cl-transforms:pose->transform map-T-wrist) + wrist-T-basket)) + (basket-pose (cl-transforms:transform->pose map-T-basket))) + (btr:add-object btr:*current-bullet-world* :basket + :b + basket-pose + :mass 1 + :length 0.5 :width 0.3 :height 0.18 :handle-height 0.09) + (let ((basket-desig (desig:an object (type basket) (name b)))) + (coe:on-event + (make-instance 'cpoe:object-attached-robot + :link "l_wrist_roll_link" + :not-loose t + :grasp :top + :arm :left + :object-name :b + :object-designator basket-desig))))) + +(defun spawn-objects () + (let ((i 1)) + ;;Spawn objects in shelf 1 + (loop for j from -1.3 to -0.6 by 0.16 + do (let ((denkmit + (concatenate 'string + "denkmit" "-" (write-to-string j) "-" (write-to-string i))) + (heitmamn + (concatenate 'string + "heitmann" "-" (write-to-string j) "-" (write-to-string i))) + (dove + (concatenate 'string + "dove" "-" (write-to-string j) "-" (write-to-string i)))) + (btr-utils:spawn-object + (intern denkmit) :denkmit :pose `((,j 0.9 0.5) (0 0 1 0))) + (btr-utils:spawn-object + (intern heitmamn) :heitmann :pose `((,j 0.9 0.96) (0 0 1 0))) + (btr-utils:spawn-object + (intern dove) :dove :pose `((,j 0.9 0.73) (0 0 1 0))))) + (incf i) + ;; Spawn objects in shelf 2 + (loop for k from 0.6 to 1.4 by 0.12 + do (let ((denkmit + (concatenate 'string + "denkmit" "-" (write-to-string k) "-" (write-to-string i))) + (heitmamn + (concatenate 'string + "heitmann" "-" (write-to-string k) "-" (write-to-string i))) + (dove + (concatenate 'string + "dove" "-" (write-to-string k) "-" (write-to-string i)))) + ;; (btr-utils:spawn-object + ;; (intern denkmit) :denkmit :pose `((,k 0.7 0.68) (0 0 1 0)) :color '(1 0 0 1)) + (btr-utils:spawn-object + (intern heitmamn) :heitmann :pose `((,k 0.75 1.05) (0 0 1 0))) + (btr-utils:spawn-object + (intern dove) :dove :pose `((,k 0.75 1.39) (0 0 1 0))))) + (incf i) + ;; Spawn objects on the table + (loop for k from -3.7 to -3.3 by 0.12 + do (let ((denkmit + (concatenate 'string + "denkmit" "-" (write-to-string k) "-" (write-to-string i))) + (heitmamn + (concatenate 'string + "heitmann" "-" (write-to-string k) "-" (write-to-string i))) + (dove + (concatenate 'string + "dove" "-" (write-to-string k) "-" (write-to-string i)))) + (btr-utils:spawn-object + (intern denkmit) :denkmit :pose `((,k 0.1 0.7) (0 0 1 0)) :color '(1 0 0 1)))))) + + +(defun init () + ;; (roslisp:start-ros-node "shopping_demo") + + (cram-bullet-reasoning-belief-state::ros-time-init) + (cram-location-costmap::location-costmap-vis-init) + (cram-tf::init-tf) + + (prolog:prolog '(and + (btr:bullet-world ?world) + (btr:debug-window ?world))) + + (prolog:prolog '(and + (btr:bullet-world ?world) + (assert (btr:object ?world :static-plane + :floor + ((0 0 0) (0 0 0 1)) + :normal (0 0 1) :constant 0 + :collision-mask (:default-filter))))) + (btr:add-objects-to-mesh-list "cram_pr2_shopping_demo")) + + +(roslisp-utilities:register-ros-init-function init) +(roslisp-utilities:register-ros-init-function spawn-robot) +(roslisp-utilities:register-ros-init-function spawn-shelf) +(roslisp-utilities:register-ros-init-function spawn-objects) +;; (roslisp-utilities:register-ros-init-function spawn-objects-new) +(roslisp-utilities:register-ros-init-function spawn-basket) + diff --git a/cram_pr2/cram_pr2_shopping_demo/src/utils.lisp b/cram_demos/cram_pr2_shopping_demo/src/utils.lisp similarity index 82% rename from cram_pr2/cram_pr2_shopping_demo/src/utils.lisp rename to cram_demos/cram_pr2_shopping_demo/src/utils.lisp index 1fc19850dd..f04659a3e5 100644 --- a/cram_pr2/cram_pr2_shopping_demo/src/utils.lisp +++ b/cram_demos/cram_pr2_shopping_demo/src/utils.lisp @@ -35,23 +35,25 @@ (roslisp:get-param "shelf_description")))) (prolog:prolog `(and (btr:bullet-world ?world) - (assert (btr:object ?world :urdf :kitchen ((0 0 0) (0 0 0 1)) + (rob-int:environment-name ?environment-name) + (assert (btr:object ?world :urdf ?environment-name ((0 0 0) (0 0 0 1)) :urdf ,shelve-urdf)))))) (defun spawn-kitchen () - (let ((kitchen-urdf - (cl-urdf:parse-urdf - (roslisp:get-param "kitchen_description")))) - (prolog:prolog - `(and (btr:bullet-world ?world) - (assert (btr:object ?world :urdf :kitchen ((0 0 0) (0 0 0 1)) - :urdf ,kitchen-urdf)))))) + (setf rob-int:*environment-urdf* + (cl-urdf:parse-urdf + (roslisp:get-param rob-int:*environment-description-parameter*))) + (prolog:prolog + `(and (btr:bullet-world ?world) + (rob-int:environment-name ?environment-name) + (assert (btr:object ?world :urdf ?environment-name ((0 0 0) (0 0 0 1)) + :urdf ,rob-int:*environment-urdf*))))) (defun spawn-robot () (setf cram-robot-interfaces:*robot-urdf* (cl-urdf:parse-urdf - (roslisp:get-param "robot_description"))) + (roslisp:get-param rob-int:*robot-description-parameter*))) (prolog:prolog `(and (btr:bullet-world ?world) (cram-robot-interfaces:robot ?robot) @@ -125,14 +127,3 @@ :normal (0 0 1) :constant 0)))) (btr:add-objects-to-mesh-list "cram_pr2_shopping_demo")) -(def-fact-group costmap-metadata (costmap:costmap-size - costmap:costmap-origin - costmap:costmap-resolution - costmap:orientation-samples - costmap:orientation-sample-step) - (<- (location-costmap:costmap-size 12 12)) - (<- (location-costmap:costmap-origin -6 -6)) - (<- (location-costmap:costmap-resolution 0.04)) - (<- (location-costmap:orientation-samples 2)) - (<- (location-costmap:orientation-sample-step 0.1))) - diff --git a/cram_boxy/cram_boxy_designators/CMakeLists.txt b/cram_demos/cram_projection_demos/CMakeLists.txt similarity index 73% rename from cram_boxy/cram_boxy_designators/CMakeLists.txt rename to cram_demos/cram_projection_demos/CMakeLists.txt index da7e19ca43..c94add5961 100644 --- a/cram_boxy/cram_boxy_designators/CMakeLists.txt +++ b/cram_demos/cram_projection_demos/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 2.8.3) -project(cram_boxy_designators) +project(cram_projection_demos) find_package(catkin REQUIRED) catkin_package() diff --git a/cram_demos/cram_projection_demos/cram-projection-demos.asd b/cram_demos/cram_projection_demos/cram-projection-demos.asd new file mode 100644 index 0000000000..3878ff9571 --- /dev/null +++ b/cram_demos/cram_projection_demos/cram-projection-demos.asd @@ -0,0 +1,86 @@ +;;; +;;; Copyright (c) 2020, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(defsystem cram-projection-demos + :author "Gayane Kazhoyan" + :maintainer "Gayane Kazhoyan" + :license "BSD" + + :depends-on (roslisp-utilities ; for ros-init-function + + cl-transforms + ;; cl-transforms-stamped + ;; cl-tf + + ;; cram_core + cram-prolog ; for restricted ground costmap and to set break on errors + cram-occasions-events ; for CLEAR-BELIEF + cram-designators ; for the plan, costmap + cram-executive ; for the plan + ;; cram-language + ;; cram-projection + ;; cram-utilities + + ;; cram_common + cram-tf ; to set the default timeout to a small number, tf utils + cram-location-costmap ; for the restricted ground costmap + cram-robot-interfaces ; for ENV-NAME, VIS/REACH-DESIG + cram-manipulation-interfaces ; for costmap, standard rotations + cram-object-knowledge ; for manipulation knowledge + cram-mobile-pick-place-plans ; for action desig implementations + ;; cram-common-failures + + ;; cram_3d_world + cram-bullet-reasoning + cram-bullet-reasoning-belief-state ; for handling events + cram-urdf-projection ; for with-simulated-robot + cram-fetch-deliver-plans ; for action desig implementations + cram-urdf-environment-manipulation ; for action desig implementations + + ;; costmaps + cram-btr-visibility-costmap + cram-btr-spatial-relations-costmap + cram-robot-pose-gaussian-costmap + ;; cram-occupancy-grid-costmap + + ;; robot descriptions + cram-pr2-description + cram-boxy-description + cram-donbot-description + ;; cram-hsrb-description + ) + :components + ((:module "src" + :components + ((:file "package") + (:file "costmaps" :depends-on ("package")) + (:file "setup" :depends-on ("package")) + (:file "assembly-demo" :depends-on ("package" "setup")) + (:file "household-demo" :depends-on ("package" "setup")) + (:file "retail-demo" :depends-on ("package" "setup")))))) diff --git a/cram_demos/cram_projection_demos/launch/everything.launch b/cram_demos/cram_projection_demos/launch/everything.launch new file mode 100644 index 0000000000..d6a2f92e9e --- /dev/null +++ b/cram_demos/cram_projection_demos/launch/everything.launch @@ -0,0 +1,110 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - /kitchen/cram_joint_states + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/cram_demos/cram_projection_demos/launch/household_boxy.launch b/cram_demos/cram_projection_demos/launch/household_boxy.launch new file mode 100644 index 0000000000..18b4de22c8 --- /dev/null +++ b/cram_demos/cram_projection_demos/launch/household_boxy.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/cram_demos/cram_projection_demos/launch/household_donbot.launch b/cram_demos/cram_projection_demos/launch/household_donbot.launch new file mode 100644 index 0000000000..53877c0ebe --- /dev/null +++ b/cram_demos/cram_projection_demos/launch/household_donbot.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/cram_demos/cram_projection_demos/launch/household_pr2.launch b/cram_demos/cram_projection_demos/launch/household_pr2.launch new file mode 100644 index 0000000000..a69be36436 --- /dev/null +++ b/cram_demos/cram_projection_demos/launch/household_pr2.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/cram_demos/cram_projection_demos/launch/household_pr2_with_giskard.launch b/cram_demos/cram_projection_demos/launch/household_pr2_with_giskard.launch new file mode 100644 index 0000000000..850d935fea --- /dev/null +++ b/cram_demos/cram_projection_demos/launch/household_pr2_with_giskard.launch @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/cram_demos/cram_projection_demos/launch/retail_boxy.launch b/cram_demos/cram_projection_demos/launch/retail_boxy.launch new file mode 100644 index 0000000000..9eab8882f7 --- /dev/null +++ b/cram_demos/cram_projection_demos/launch/retail_boxy.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/cram_demos/cram_projection_demos/launch/retail_donbot.launch b/cram_demos/cram_projection_demos/launch/retail_donbot.launch new file mode 100644 index 0000000000..d62011aa52 --- /dev/null +++ b/cram_demos/cram_projection_demos/launch/retail_donbot.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/cram_demos/cram_projection_demos/launch/retail_pr2.launch b/cram_demos/cram_projection_demos/launch/retail_pr2.launch new file mode 100644 index 0000000000..44e4afe24d --- /dev/null +++ b/cram_demos/cram_projection_demos/launch/retail_pr2.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/cram_demos/cram_projection_demos/package.xml b/cram_demos/cram_projection_demos/package.xml new file mode 100644 index 0000000000..8f3b74191c --- /dev/null +++ b/cram_demos/cram_projection_demos/package.xml @@ -0,0 +1,71 @@ + + cram_projection_demos + 0.7.0 + + A bunch of demos that work on a bunch of robots in a bunch of environments + + Gayane Kazhoyan + Gayane Kazhoyan + BSD + + catkin + + roslisp_utilities + + cl_transforms + + + + cram_prolog + cram_occasions_events + cram_designators + cram_executive + + + + + cram_tf + cram_location_costmap + cram_robot_interfaces + cram_manipulation_interfaces + cram_object_knowledge + cram_mobile_pick_place_plans + + + cram_bullet_reasoning + cram_bullet_reasoning_belief_state + cram_urdf_projection + cram_fetch_deliver_plans + cram_urdf_environment_manipulation + + cram_btr_visibility_costmap + cram_btr_spatial_relations_costmap + cram_robot_pose_gaussian_costmap + + + cram_pr2_description + cram_boxy_description + cram_donbot_description + + + + + xacro + joint_state_publisher + robot_state_publisher + map_server + tf2_ros + + pr2_description + pr2_arm_kinematics + + iai_boxy_description + iai_donbot_description + + ur_description + + iai_kitchen + iai_refills_lab + iai_maps + diff --git a/cram_boxy/cram_boxy_projection/CATKIN_IGNORE b/cram_demos/cram_projection_demos/resource/assembly/see_github.com_code-iai_assembly_models.git similarity index 100% rename from cram_boxy/cram_boxy_projection/CATKIN_IGNORE rename to cram_demos/cram_projection_demos/resource/assembly/see_github.com_code-iai_assembly_models.git diff --git a/cram_pr2/cram_pr2_pick_place_demo/resource/blue_metal_plate.stl b/cram_demos/cram_projection_demos/resource/household/blue_metal_plate.stl similarity index 100% rename from cram_pr2/cram_pr2_pick_place_demo/resource/blue_metal_plate.stl rename to cram_demos/cram_projection_demos/resource/household/blue_metal_plate.stl diff --git a/cram_pr2/cram_pr2_pick_place_demo/resource/bottle.dae b/cram_demos/cram_projection_demos/resource/household/bottle.dae similarity index 100% rename from cram_pr2/cram_pr2_pick_place_demo/resource/bottle.dae rename to cram_demos/cram_projection_demos/resource/household/bottle.dae diff --git a/cram_demos/cram_projection_demos/resource/household/bowl.obj b/cram_demos/cram_projection_demos/resource/household/bowl.obj new file mode 100644 index 0000000000..f14870ddce --- /dev/null +++ b/cram_demos/cram_projection_demos/resource/household/bowl.obj @@ -0,0 +1,6905 @@ +# Blender v2.83.4 OBJ File: '' +# www.blender.org +mtllib bowl_39.mtl +o Bowl_hull_1 +v 0.033177 -0.029301 -0.019176 +v -0.003464 0.040094 -0.026073 +v -0.003464 0.040094 -0.025642 +v -0.038369 -0.021546 -0.019609 +v -0.005614 -0.037064 -0.033400 +v 0.036191 0.009906 -0.033400 +v -0.034060 0.015950 -0.033400 +v 0.026701 0.035337 -0.018744 +v -0.033189 0.029301 -0.018744 +v 0.009896 0.036201 -0.033400 +v -0.018102 -0.040086 -0.019177 +v 0.028859 -0.024136 -0.033400 +v -0.030175 -0.022410 -0.033400 +v 0.040084 -0.018532 -0.018744 +v 0.019385 -0.039654 -0.018744 +v 0.039652 0.019388 -0.018744 +v -0.017694 0.033187 -0.033400 +v -0.019398 0.039646 -0.018744 +v -0.040104 0.018532 -0.018744 +v -0.037506 -0.002582 -0.032969 +v 0.028859 0.024136 -0.033400 +v 0.015932 -0.034042 -0.033400 +v 0.037046 -0.005597 -0.033400 +v 0.018522 0.040086 -0.018744 +v -0.022420 -0.030172 -0.033400 +v -0.028448 -0.033618 -0.019177 +v 0.003428 -0.040094 -0.026073 +v 0.040076 0.003862 -0.026073 +v -0.040096 0.003438 -0.026073 +v -0.008205 0.036632 -0.033400 +v 0.019817 0.031884 -0.033400 +v -0.039656 -0.018964 -0.019177 +v -0.024146 0.028877 -0.033400 +v -0.034923 -0.013791 -0.033400 +v -0.040104 0.004741 -0.018744 +v 0.026709 -0.035345 -0.019176 +v 0.033177 -0.017669 -0.033400 +v 0.033177 0.029301 -0.019176 +v 0.008177 -0.036632 -0.033400 +v -0.036642 0.008195 -0.033400 +v -0.025434 0.036201 -0.019176 +v -0.015960 -0.034050 -0.033400 +v 0.032745 0.018532 -0.033400 +v 0.007745 -0.039654 -0.018744 +v -0.030175 0.022410 -0.033400 +v 0.024119 -0.028869 -0.033400 +v 0.002988 0.037496 -0.032969 +v -0.033620 -0.028438 -0.019609 +v 0.010759 0.040086 -0.023918 +v -0.039656 -0.010345 -0.024779 +v 0.040084 -0.013367 -0.022622 +v -0.037930 0.022841 -0.019176 +v -0.011643 -0.040086 -0.023486 +v -0.023707 -0.037064 -0.019609 +v 0.037917 -0.022841 -0.019176 +v 0.024119 0.028877 -0.033400 +v 0.037917 0.022833 -0.019176 +v -0.018534 0.039646 -0.020038 +v 0.039652 0.018532 -0.020038 +v 0.018514 -0.039654 -0.020038 +v -0.040096 -0.003438 -0.026073 +v -0.040104 0.015510 -0.021331 +v 0.034896 -0.013783 -0.033400 +v 0.040076 -0.003870 -0.026073 +v 0.037486 0.002991 -0.032969 +v 0.018090 0.040086 -0.019609 +v -0.036642 -0.008171 -0.033400 +v -0.033189 0.029301 -0.019176 +v -0.024146 -0.028869 -0.033400 +v 0.022823 0.037927 -0.019176 +v 0.015932 0.034050 -0.033400 +v -0.009924 -0.036209 -0.033400 +v 0.002572 -0.040086 -0.019609 +v -0.003464 -0.040094 -0.026073 +v 0.002988 -0.037504 -0.032969 +v 0.022831 -0.037928 -0.019176 +v 0.040084 0.000424 -0.019609 +v -0.001282 0.040086 -0.019609 +v -0.029311 0.033187 -0.019176 +v -0.033197 -0.017669 -0.033400 +v 0.039652 0.010345 -0.024777 +v -0.018102 -0.040086 -0.019609 +v 0.026701 0.035337 -0.019176 +v -0.039656 -0.018964 -0.019609 +v 0.009472 -0.039654 -0.025212 +v 0.033177 -0.029301 -0.018744 +v 0.040084 -0.018100 -0.019609 +v 0.019817 -0.031884 -0.033400 +v -0.009484 0.039646 -0.025212 +v -0.013809 0.034913 -0.033400 +v -0.028448 -0.033618 -0.019609 +v 0.003420 0.040094 -0.026073 +v -0.005622 0.037072 -0.033400 +v 0.036191 -0.009906 -0.033400 +v -0.028887 0.024136 -0.033400 +v -0.028887 -0.024136 -0.033400 +v 0.034896 0.013791 -0.033400 +v -0.040104 0.009474 -0.024350 +v -0.037066 0.005596 -0.033400 +v -0.035339 -0.026287 -0.019609 +v -0.022836 0.037927 -0.019176 +v 0.029299 0.033187 -0.019176 +v -0.040104 0.018100 -0.019609 +v 0.029299 -0.033187 -0.019176 +v 0.035335 0.026287 -0.019609 +v -0.035347 0.026279 -0.019609 +v -0.017686 -0.033187 -0.033400 +v 0.037046 0.005596 -0.033400 +v -0.035339 -0.026287 -0.019177 +v 0.035335 -0.026287 -0.019609 +v 0.030155 -0.022402 -0.033400 +v -0.039656 -0.014655 -0.022624 +v -0.036211 0.009906 -0.033400 +v 0.005586 0.037064 -0.033400 +v -0.022420 0.030165 -0.033400 +v -0.033197 0.017669 -0.033400 +v 0.011191 -0.035769 -0.033400 +v 0.033177 0.029301 -0.018744 +v 0.014637 -0.039654 -0.022622 +v 0.040084 -0.008626 -0.024777 +v -0.014657 0.039646 -0.022622 +v -0.037082 -0.005597 -0.033400 +vt 0.037882 0.430207 +vt 0.043168 0.601899 +vt 0.037686 0.569793 +vt 0.951449 0.376468 +vt 0.430110 0.962216 +vt 0.075372 0.301096 +vt 0.623532 0.048551 +vt 0.860023 0.800998 +vt 0.123825 0.779464 +vt 0.833105 0.059319 +vt 0.086237 0.134593 +vt 1.000000 0.731108 +vt 0.741875 0.994518 +vt 0.994616 0.258222 +vt 0.279464 0.086139 +vt 0.456930 0.000000 +vt 0.456930 0.000000 +vt 0.258222 0.005579 +vt 0.000000 0.268892 +vt 0.860023 0.199002 +vt 0.698806 0.924530 +vt 0.962118 0.569793 +vt 0.731108 0.000098 +vt 0.220536 0.876272 +vt 0.397807 0.043168 +vt 0.747259 0.102388 +vt 0.199002 0.139879 +vt 0.064605 0.671985 +vt 0.000000 0.440877 +vt 0.913861 0.720341 +vt 0.602095 0.956832 +vt 0.043168 0.397807 +vt 0.182948 0.048551 +vt 0.301096 0.924628 +vt 0.908477 0.268892 +vt 0.274374 0.999902 +vt 0.596711 0.994518 +vt 0.145360 0.919244 +vt 0.123825 0.220536 +vt 0.800901 0.860024 +vt 0.027114 0.215153 +vt 0.204483 0.962216 +vt 0.800901 0.139879 +vt 0.268990 0.005579 +vt 0.999902 0.451840 +vt 0.994616 0.268892 +vt 0.972984 0.215251 +vt 0.542874 1.000000 +vt 0.731010 0.994518 +vt 0.000098 0.457126 +vt 0.032400 0.532204 +vt 0.000098 0.542874 +vt 0.005579 0.736492 +vt 0.000000 0.306578 +vt 0.935298 0.671887 +vt 0.999902 0.548258 +vt 0.967600 0.462706 +vt 0.634299 0.000098 +vt 0.725724 0.000098 +vt 0.086237 0.134593 +vt 0.199002 0.860024 +vt 0.784749 0.027016 +vt 0.698806 0.075372 +vt 0.376370 0.951547 +vt 0.354933 0.999902 +vt 0.532204 0.999902 +vt 0.456930 1.000000 +vt 0.537392 0.967698 +vt 0.833203 0.940779 +vt 0.784847 0.972984 +vt 1.000000 0.494714 +vt 1.000000 0.666699 +vt 0.484143 0.000098 +vt 0.134593 0.086139 +vt 0.021633 0.768696 +vt 0.086139 0.720341 +vt 0.994616 0.370987 +vt 0.274374 0.999902 +vt 0.833105 0.059319 +vt 0.005579 0.736492 +vt 0.618246 0.994518 +vt 0.913861 0.865407 +vt 0.913861 0.865407 +vt 0.972984 0.784847 +vt 1.000000 0.725724 +vt 0.747259 0.897612 +vt 0.327917 0.064605 +vt 0.080854 0.854640 +vt 0.145360 0.919244 +vt 0.542776 0.000000 +vt 0.537392 0.032400 +vt 0.430012 0.037686 +vt 0.381852 0.005579 +vt 0.951449 0.623532 +vt 0.139879 0.199002 +vt 0.139879 0.800998 +vt 0.935298 0.328015 +vt 0.000000 0.381852 +vt 0.059417 0.827819 +vt 0.215348 0.027016 +vt 0.913861 0.134593 +vt 0.865505 0.086139 +vt 0.000000 0.274276 +vt 0.865505 0.913861 +vt 0.940779 0.172181 +vt 0.059319 0.172279 +vt 0.279561 0.913861 +vt 0.962118 0.430207 +vt 0.059417 0.827819 +vt 0.940779 0.827819 +vt 0.876175 0.779366 +vt 0.005579 0.629013 +vt 0.005579 0.682753 +vt 0.048551 0.376468 +vt 0.569793 0.037784 +vt 0.220536 0.123825 +vt 0.086139 0.279659 +vt 0.639683 0.946065 +vt 0.913861 0.134593 +vt 0.682655 0.994518 +vt 1.000000 0.607576 +vt 0.317345 0.005579 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -0.0000 1.0000 +vn -0.0281 0.9996 0.0000 +vn -0.2679 0.3571 0.8948 +vn 0.0000 -0.7084 0.7058 +vn -0.0163 -0.0261 0.9995 +vn -0.0146 -0.0157 0.9998 +vn -0.5507 0.3536 0.7560 +vn -0.3851 -0.6160 0.6872 +vn -0.0405 0.9988 -0.0270 +vn 0.9989 0.0396 -0.0262 +vn 0.8735 0.4061 -0.2685 +vn 0.8100 0.4106 -0.4187 +vn 0.0398 -0.9988 -0.0268 +vn -0.9362 0.0000 -0.3516 +vn -0.9996 -0.0192 0.0204 +vn -1.0000 -0.0000 0.0000 +vn 0.9261 -0.0285 -0.3762 +vn 0.9362 0.0000 -0.3516 +vn 0.2274 0.8937 -0.3869 +vn -0.8062 0.5917 0.0000 +vn 0.4155 0.7156 0.5616 +vn 0.4215 0.8821 -0.2103 +vn 0.4082 0.8111 -0.4189 +vn 0.3044 0.8542 -0.4215 +vn 0.4401 0.7892 -0.4284 +vn -0.1797 -0.9052 -0.3852 +vn 0.0070 -0.9424 0.3345 +vn 0.0000 -1.0000 0.0012 +vn 0.0254 -0.9997 0.0046 +vn 0.0000 -1.0000 0.0011 +vn -0.1120 -0.9295 -0.3515 +vn 0.0162 -0.5190 -0.8546 +vn -0.0286 -0.9267 -0.3748 +vn 0.0000 -0.9362 -0.3516 +vn 0.3738 -0.5613 0.7384 +vn 0.4037 -0.8736 -0.2718 +vn 0.4081 -0.8109 -0.4195 +vn 0.9702 0.0110 0.2420 +vn 0.9997 0.0223 0.0106 +vn 1.0000 0.0000 0.0000 +vn -0.0238 0.9997 0.0099 +vn -0.0001 1.0000 0.0013 +vn -0.0112 0.9665 0.2565 +vn -0.3263 0.4198 0.8469 +vn -0.5571 0.7167 -0.4194 +vn -0.7078 0.7064 0.0000 +vn -0.7639 -0.4869 -0.4234 +vn 0.9022 0.2160 -0.3732 +vn 0.9807 0.0979 -0.1692 +vn -0.4746 -0.8802 0.0000 +vn -0.3054 -0.8540 -0.4212 +vn -0.2335 -0.8912 -0.3890 +vn -0.0005 -1.0000 0.0000 +vn -0.0020 -1.0000 -0.0034 +vn 0.5172 0.7400 -0.4300 +vn 0.5555 0.8315 0.0000 +vn 0.5026 0.7523 -0.4259 +vn -0.8950 -0.4461 0.0000 +vn -0.9996 -0.0283 0.0000 +vn -0.8127 -0.4051 -0.4187 +vn -0.8280 -0.3687 -0.4225 +vn 0.1253 -0.9242 -0.3609 +vn 0.1181 -0.9271 -0.3557 +vn 0.2483 -0.3308 0.9104 +vn 0.8062 -0.5917 0.0000 +vn 0.5483 -0.3517 0.7587 +vn 0.8817 -0.4222 -0.2107 +vn 0.8108 -0.4088 -0.4189 +vn 0.8274 -0.3661 -0.4259 +vn 0.5179 -0.7391 -0.4308 +vn 0.5014 -0.7529 -0.4262 +vn 0.4388 -0.7898 -0.4286 +vn -0.3679 0.8279 -0.4234 +vn -0.7076 -0.7066 0.0000 +vn -0.5343 -0.7351 -0.4172 +vn -0.5879 -0.8089 0.0000 +vn -0.5466 -0.7244 -0.4200 +vn 0.0000 1.0000 0.0000 +vn 0.0001 1.0000 0.0009 +vn 0.0000 0.9358 -0.3525 +vn 0.0007 1.0000 -0.0003 +vn 0.0021 1.0000 -0.0036 +vn -0.0269 0.9269 -0.3744 +vn -0.1189 0.9298 -0.3484 +vn -0.1564 0.9187 -0.3626 +vn 0.9053 -0.1798 -0.3848 +vn 0.8805 -0.2545 -0.3998 +vn 0.8630 -0.2882 -0.4149 +vn -0.6397 0.6397 -0.4261 +vn -0.6405 0.6392 -0.4258 +vn -0.6421 -0.6411 -0.4203 +vn -0.6409 -0.6419 -0.4209 +vn 0.8651 0.2884 -0.4103 +vn 0.8239 0.3738 -0.4259 +vn -1.0000 0.0000 -0.0046 +vn -1.0000 -0.0005 -0.0005 +vn -0.9084 0.1870 -0.3739 +vn -0.9268 0.0301 -0.3744 +vn -0.9295 0.1001 -0.3549 +vn -0.9163 0.1495 -0.3716 +vn -0.7635 -0.4879 -0.4231 +vn -0.7261 -0.5413 -0.4241 +vn -0.7089 -0.5666 -0.4200 +vn -0.3739 0.5625 0.7374 +vn -0.4034 0.8745 -0.2692 +vn -0.4081 0.8116 -0.4180 +vn 0.6403 0.6390 -0.4263 +vn 0.6395 0.6395 -0.4267 +vn 0.6377 0.7703 0.0000 +vn 0.5781 0.6983 -0.4221 +vn -0.8810 0.4233 -0.2112 +vn 0.6403 -0.6390 -0.4263 +vn 0.6389 -0.6400 -0.4269 +vn 0.5802 -0.6962 -0.4226 +vn 0.7078 -0.7064 0.0000 +vn 0.4173 -0.5007 0.7584 +vn 0.7078 0.5674 -0.4208 +vn 0.7424 0.5147 -0.4289 +vn 0.8029 0.5886 -0.0942 +vn 0.7494 0.5070 -0.4258 +vn -0.7490 0.5092 -0.4238 +vn -0.8013 0.5881 -0.1096 +vn -0.7260 0.5412 -0.4242 +vn -0.7089 0.5666 -0.4201 +vn -0.4858 -0.7629 -0.4266 +vn -0.4321 -0.8013 -0.4139 +vn -0.4061 -0.8123 -0.4186 +vn 0.6996 0.0000 -0.7145 +vn 0.9277 0.0969 -0.3606 +vn 0.9095 0.1806 -0.3743 +vn 0.9267 0.1310 -0.3522 +vn -0.7800 -0.4598 0.4245 +vn -0.0178 -0.0167 0.9997 +vn -0.0320 -0.0189 0.9993 +vn -0.6489 -0.6100 0.4549 +vn -0.8426 -0.5385 0.0000 +vn -0.7811 -0.6243 0.0000 +vn 0.7078 -0.5674 -0.4208 +vn 0.8022 -0.5887 -0.0991 +vn 0.7493 -0.5082 -0.4246 +vn 0.7609 -0.4858 -0.4303 +vn 0.7253 -0.5415 -0.4250 +vn -0.9751 -0.0992 -0.1984 +vn -0.8742 -0.2674 -0.4054 +vn -0.9128 -0.1826 -0.3652 +vn -0.9926 -0.0694 -0.0992 +vn -0.8696 -0.2830 -0.4046 +vn -0.8919 0.2250 -0.3922 +vn -0.8542 0.3040 -0.4218 +vn -0.8724 0.2706 -0.4071 +vn 0.1812 0.9041 -0.3870 +vn 0.0955 0.9295 -0.3561 +vn 0.1048 0.9296 -0.3534 +vn 0.0005 0.7075 -0.7067 +vn -0.5416 0.7265 -0.4230 +vn -0.5008 0.7535 -0.4259 +vn -0.4866 0.7608 -0.4295 +vn -0.7614 0.4853 -0.4298 +vn -0.8113 0.4075 -0.4191 +vn -0.8103 0.4099 -0.4187 +vn 0.3108 -0.8534 -0.4185 +vn 0.5918 0.3866 0.7073 +vn 0.8065 0.5912 0.0000 +vn 0.6197 0.6648 0.4172 +vn 0.7078 0.7064 0.0000 +vn 0.0723 -0.9915 -0.1084 +vn 0.0991 -0.9753 -0.1976 +vn 0.1834 -0.9125 -0.3658 +vn 0.2526 -0.8817 -0.3986 +vn 0.2674 -0.8760 -0.4013 +vn 0.9083 -0.1731 -0.3808 +vn 0.9276 -0.0967 -0.3608 +vn 1.0000 0.0000 -0.0061 +vn 1.0000 0.0005 -0.0009 +vn -0.0737 0.9911 -0.1106 +vn -0.1013 0.9740 -0.2024 +vn -0.1826 0.9131 -0.3646 +vn -0.2681 0.8741 -0.4050 +vn -0.2698 0.8736 -0.4049 +vn -0.9299 -0.0795 -0.3591 +vn -0.9300 -0.1240 -0.3460 +vn -0.9193 -0.1569 -0.3610 +vn -0.7090 0.0010 -0.7052 +usemtl None +s off +f 99/1/1 67/2/1 122/3/1 +f 6/4/1 5/5/1 7/6/1 +f 6/4/1 7/6/1 10/7/1 +f 5/5/1 6/4/1 12/8/1 +f 7/6/1 5/5/1 13/9/1 +f 8/10/2 9/11/2 14/12/2 +f 14/12/2 9/11/2 15/13/2 +f 8/10/2 14/12/2 16/14/2 +f 10/7/1 7/6/1 17/15/1 +f 3/16/3 2/17/3 18/18/3 +f 9/11/2 8/10/2 18/18/2 +f 15/13/2 9/11/2 19/19/2 +f 6/4/1 10/7/1 21/20/1 +f 5/5/1 12/8/1 22/21/1 +f 12/8/1 6/4/1 23/22/1 +f 18/18/2 8/10/2 24/23/2 +f 13/9/1 5/5/1 25/24/1 +f 10/7/1 17/15/1 30/25/1 +f 21/20/1 10/7/1 31/26/1 +f 17/15/1 7/6/1 33/27/1 +f 7/6/1 13/9/1 34/28/1 +f 15/13/2 19/19/2 35/29/2 +f 12/8/1 23/22/1 37/30/1 +f 5/5/1 22/21/1 39/31/1 +f 7/6/1 34/28/1 40/32/1 +f 9/11/4 18/18/4 41/33/4 +f 25/24/1 5/5/1 42/34/1 +f 6/4/1 21/20/1 43/35/1 +f 11/36/5 15/13/5 44/37/5 +f 26/38/6 11/36/6 44/37/6 +f 15/13/2 35/29/2 44/37/2 +f 35/29/7 26/38/7 44/37/7 +f 33/27/1 7/6/1 45/39/1 +f 22/21/1 12/8/1 46/40/1 +f 19/19/8 9/11/8 52/41/8 +f 11/36/9 26/38/9 54/42/9 +f 21/20/1 31/26/1 56/43/1 +f 18/18/10 2/17/10 58/44/10 +f 16/14/11 28/45/11 59/46/11 +f 57/47/12 16/14/12 59/46/12 +f 43/35/13 57/47/13 59/46/13 +f 15/13/14 27/48/14 60/49/14 +f 29/50/15 20/51/15 61/52/15 +f 32/53/16 35/29/16 61/52/16 +f 35/29/17 19/19/17 62/54/17 +f 37/30/1 23/22/1 63/55/1 +f 64/56/18 23/22/18 65/57/18 +f 28/45/19 64/56/19 65/57/19 +f 10/7/20 49/58/20 66/59/20 +f 40/32/1 34/28/1 67/2/1 +f 52/41/21 9/11/21 68/60/21 +f 13/9/1 25/24/1 69/61/1 +f 24/23/22 8/10/22 70/62/22 +f 66/59/23 24/23/23 70/62/23 +f 66/59/24 70/62/24 71/63/24 +f 31/26/1 10/7/1 71/63/1 +f 10/7/25 66/59/25 71/63/25 +f 70/62/26 31/26/26 71/63/26 +f 42/34/1 5/5/1 72/64/1 +f 5/5/27 53/65/27 72/64/27 +f 15/13/28 11/36/28 73/66/28 +f 11/36/29 27/48/29 73/66/29 +f 27/48/30 15/13/30 73/66/30 +f 27/48/31 11/36/31 74/67/31 +f 53/65/32 5/5/32 74/67/32 +f 5/5/33 39/31/33 75/68/33 +f 74/67/34 5/5/34 75/68/34 +f 27/48/35 74/67/35 75/68/35 +f 36/69/36 15/13/36 76/70/36 +f 15/13/37 60/49/37 76/70/37 +f 60/49/38 22/21/38 76/70/38 +f 16/14/39 14/12/39 77/71/39 +f 28/45/40 16/14/40 77/71/40 +f 14/12/41 51/72/41 77/71/41 +f 3/16/42 18/18/42 78/73/42 +f 24/23/43 3/16/43 78/73/43 +f 18/18/44 24/23/44 78/73/44 +f 9/11/45 41/33/45 79/74/45 +f 41/33/46 33/27/46 79/74/46 +f 68/60/47 9/11/47 79/74/47 +f 13/9/48 4/75/48 80/76/48 +f 34/28/1 13/9/1 80/76/1 +f 6/4/49 59/46/49 81/77/49 +f 59/46/50 28/45/50 81/77/50 +f 11/36/51 54/42/51 82/78/51 +f 42/34/52 72/64/52 82/78/52 +f 72/64/53 53/65/53 82/78/53 +f 74/67/54 11/36/54 82/78/54 +f 53/65/55 74/67/55 82/78/55 +f 56/43/56 31/26/56 83/79/56 +f 70/62/57 8/10/57 83/79/57 +f 31/26/58 70/62/58 83/79/58 +f 4/75/59 32/53/59 84/80/59 +f 32/53/60 61/52/60 84/80/60 +f 80/76/61 4/75/61 84/80/61 +f 34/28/62 80/76/62 84/80/62 +f 75/68/63 39/31/63 85/81/63 +f 27/48/64 75/68/64 85/81/64 +f 14/12/2 15/13/2 86/82/2 +f 15/13/65 36/69/65 86/82/65 +f 1/83/66 55/84/66 86/82/66 +f 55/84/67 14/12/67 86/82/67 +f 51/72/41 14/12/41 87/85/41 +f 14/12/68 55/84/68 87/85/68 +f 55/84/69 37/30/69 87/85/69 +f 37/30/70 63/55/70 87/85/70 +f 22/21/1 46/40/1 88/86/1 +f 46/40/71 36/69/71 88/86/71 +f 36/69/72 76/70/72 88/86/72 +f 76/70/73 22/21/73 88/86/73 +f 30/25/1 17/15/1 90/87/1 +f 17/15/74 58/44/74 90/87/74 +f 26/38/75 48/88/75 91/89/75 +f 25/24/76 54/42/76 91/89/76 +f 54/42/77 26/38/77 91/89/77 +f 69/61/78 25/24/78 91/89/78 +f 2/17/79 3/16/79 92/90/79 +f 3/16/80 24/23/80 92/90/80 +f 47/91/81 2/17/81 92/90/81 +f 24/23/82 66/59/82 92/90/82 +f 66/59/83 49/58/83 92/90/83 +f 10/7/1 30/25/1 93/92/1 +f 2/17/84 47/91/84 93/92/84 +f 89/93/85 2/17/85 93/92/85 +f 30/25/86 89/93/86 93/92/86 +f 23/22/87 51/72/87 94/94/87 +f 63/55/1 23/22/1 94/94/1 +f 51/72/88 87/85/88 94/94/88 +f 87/85/89 63/55/89 94/94/89 +f 33/27/1 45/39/1 95/95/1 +f 79/74/90 33/27/90 95/95/90 +f 68/60/91 79/74/91 95/95/91 +f 13/9/1 69/61/1 96/96/1 +f 91/89/92 48/88/92 96/96/92 +f 69/61/93 91/89/93 96/96/93 +f 6/4/1 43/35/1 97/97/1 +f 59/46/94 6/4/94 97/97/94 +f 43/35/95 59/46/95 97/97/95 +f 29/50/96 61/52/96 98/98/96 +f 61/52/97 35/29/97 98/98/97 +f 35/29/17 62/54/17 98/98/17 +f 62/54/98 40/32/98 98/98/98 +f 20/51/99 29/50/99 99/1/99 +f 40/32/1 67/2/1 99/1/1 +f 29/50/100 98/98/100 99/1/100 +f 98/98/101 40/32/101 99/1/101 +f 4/75/102 13/9/102 100/99/102 +f 13/9/103 96/96/103 100/99/103 +f 96/96/104 48/88/104 100/99/104 +f 41/33/105 18/18/105 101/100/105 +f 18/18/106 58/44/106 101/100/106 +f 58/44/107 17/15/107 101/100/107 +f 38/101/108 21/20/108 102/102/108 +f 21/20/109 56/43/109 102/102/109 +f 83/79/110 8/10/110 102/102/110 +f 56/43/111 83/79/111 102/102/111 +f 19/19/112 52/41/112 103/103/112 +f 62/54/17 19/19/17 103/103/17 +f 12/8/113 1/83/113 104/104/113 +f 46/40/114 12/8/114 104/104/114 +f 36/69/115 46/40/115 104/104/115 +f 1/83/116 86/82/116 104/104/116 +f 86/82/117 36/69/117 104/104/117 +f 21/20/118 38/101/118 105/105/118 +f 43/35/119 21/20/119 105/105/119 +f 38/101/120 57/47/120 105/105/120 +f 57/47/121 43/35/121 105/105/121 +f 45/39/122 52/41/122 106/106/122 +f 52/41/123 68/60/123 106/106/123 +f 95/95/124 45/39/124 106/106/124 +f 68/60/125 95/95/125 106/106/125 +f 25/24/1 42/34/1 107/107/1 +f 54/42/126 25/24/126 107/107/126 +f 82/78/127 54/42/127 107/107/127 +f 42/34/128 82/78/128 107/107/128 +f 23/22/1 6/4/1 108/108/1 +f 65/57/129 23/22/129 108/108/129 +f 28/45/130 65/57/130 108/108/130 +f 6/4/131 81/77/131 108/108/131 +f 81/77/132 28/45/132 108/108/132 +f 32/53/133 4/75/133 109/109/133 +f 26/38/134 35/29/134 109/109/134 +f 35/29/135 32/53/135 109/109/135 +f 48/88/136 26/38/136 109/109/136 +f 4/75/137 100/99/137 109/109/137 +f 100/99/138 48/88/138 109/109/138 +f 1/83/139 12/8/139 110/110/139 +f 55/84/140 1/83/140 110/110/140 +f 55/84/141 110/110/141 111/111/141 +f 12/8/1 37/30/1 111/111/1 +f 37/30/142 55/84/142 111/111/142 +f 110/110/143 12/8/143 111/111/143 +f 61/52/144 50/112/144 112/113/144 +f 67/2/145 34/28/145 112/113/145 +f 50/112/146 67/2/146 112/113/146 +f 84/80/147 61/52/147 112/113/147 +f 34/28/148 84/80/148 112/113/148 +f 7/6/1 40/32/1 113/114/1 +f 40/32/149 62/54/149 113/114/149 +f 103/103/150 7/6/150 113/114/150 +f 62/54/151 103/103/151 113/114/151 +f 49/58/152 10/7/152 114/115/152 +f 47/91/153 92/90/153 114/115/153 +f 92/90/154 49/58/154 114/115/154 +f 10/7/1 93/92/1 114/115/1 +f 93/92/155 47/91/155 114/115/155 +f 17/15/1 33/27/1 115/116/1 +f 33/27/156 41/33/156 115/116/156 +f 41/33/157 101/100/157 115/116/157 +f 101/100/158 17/15/158 115/116/158 +f 45/39/1 7/6/1 116/117/1 +f 52/41/159 45/39/159 116/117/159 +f 7/6/160 103/103/160 116/117/160 +f 103/103/161 52/41/161 116/117/161 +f 39/31/1 22/21/1 117/118/1 +f 22/21/162 60/49/162 117/118/162 +f 8/10/2 16/14/2 118/119/2 +f 16/14/163 57/47/163 118/119/163 +f 57/47/164 38/101/164 118/119/164 +f 102/102/165 8/10/165 118/119/165 +f 38/101/166 102/102/166 118/119/166 +f 60/49/167 27/48/167 119/120/167 +f 27/48/168 85/81/168 119/120/168 +f 85/81/169 39/31/169 119/120/169 +f 39/31/170 117/118/170 119/120/170 +f 117/118/171 60/49/171 119/120/171 +f 51/72/172 23/22/172 120/121/172 +f 23/22/173 64/56/173 120/121/173 +f 64/56/174 28/45/174 120/121/174 +f 28/45/175 77/71/175 120/121/175 +f 77/71/41 51/72/41 120/121/41 +f 58/44/176 2/17/176 121/122/176 +f 2/17/177 89/93/177 121/122/177 +f 89/93/178 30/25/178 121/122/178 +f 30/25/179 90/87/179 121/122/179 +f 90/87/180 58/44/180 121/122/180 +f 61/52/181 20/51/181 122/3/181 +f 50/112/182 61/52/182 122/3/182 +f 67/2/183 50/112/183 122/3/183 +f 20/51/184 99/1/184 122/3/184 +o Bowl_hull_2 +v 0.033184 -0.043115 -0.001496 +v 0.021546 -0.080619 0.050235 +v 0.021115 -0.080619 0.050235 +v 0.039651 -0.068111 0.049366 +v 0.021115 -0.040100 -0.009251 +v 0.039651 -0.040100 0.010149 +v 0.021115 -0.076305 0.049794 +v 0.040082 -0.072857 0.048938 +v 0.021546 -0.040100 -0.017020 +v 0.040082 -0.040100 0.002816 +v 0.030600 -0.077600 0.049366 +v 0.040082 -0.058200 0.026950 +v 0.021115 -0.057343 0.010584 +v 0.040082 -0.068977 0.050235 +v 0.040082 -0.039667 0.009280 +v 0.021115 -0.039667 -0.017020 +v 0.021979 -0.078891 0.046785 +v 0.034478 -0.075439 0.048503 +v 0.040082 -0.073286 0.050235 +v 0.024996 -0.040100 -0.013991 +v 0.021979 -0.056914 0.010149 +v 0.040082 -0.050876 0.016608 +v 0.034911 -0.039667 -0.003649 +v 0.021115 -0.039667 -0.010114 +v 0.040082 -0.066387 0.039023 +v 0.034911 -0.040096 -0.003649 +v 0.038359 -0.073286 0.048075 +v 0.021979 -0.050010 -0.001055 +v 0.024132 -0.079320 0.048510 +v 0.021979 -0.076305 0.050235 +v 0.040082 -0.041391 0.004113 +v 0.021979 -0.065529 0.024363 +v 0.028013 -0.041395 -0.009251 +v 0.021115 -0.079753 0.048075 +v 0.039651 -0.039667 0.001953 +v 0.022409 -0.046562 -0.006230 +v 0.028013 -0.076734 0.046351 +v 0.034048 -0.076305 0.050235 +vt 0.980717 0.810475 +vt 1.000000 0.820950 +vt 1.000000 0.894665 +vt 0.115505 0.010573 +vt 1.000000 1.000000 +vt 0.993442 0.894665 +vt 0.403974 0.010573 +vt 0.987079 0.694567 +vt 0.294930 0.010573 +vt 0.653778 0.452570 +vt 0.410435 0.431620 +vt 1.000000 1.000000 +vt 1.000000 0.715712 +vt 0.391053 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.010573 +vt 0.045027 0.010573 +vt 0.230814 0.084190 +vt 0.500000 0.273715 +vt 0.198806 0.000000 +vt 0.102682 0.000000 +vt 0.833301 0.652472 +vt 0.198806 0.010475 +vt 0.974256 0.873519 +vt 0.967893 0.820950 +vt 0.237373 0.252570 +vt 0.987079 0.926285 +vt 0.403974 0.421145 +vt 0.974354 0.968282 +vt 1.000000 0.894665 +vt 0.314213 0.042095 +vt 0.615309 0.631522 +vt 0.948708 0.957807 +vt 0.115505 0.042193 +vt 0.967893 0.978855 +vt 0.282106 0.000000 +vt 0.160435 0.168380 +vt 0.942247 0.905140 +vn 0.4290 -0.8576 -0.2837 +vn -1.0000 -0.0000 0.0000 +vn -0.4800 0.7479 0.4586 +vn -0.3273 0.7689 0.5492 +vn 1.0000 -0.0000 0.0000 +vn 0.0000 -0.0000 1.0000 +vn 0.3342 0.7669 0.5478 +vn 0.4184 0.7386 0.5286 +vn -0.6461 -0.6428 -0.4116 +vn 0.5515 0.5487 -0.6283 +vn 0.5136 -0.7002 -0.4959 +vn 0.0000 1.0000 -0.0000 +vn 0.4422 0.7722 -0.4563 +vn -0.4251 0.8089 0.4061 +vn -0.3056 0.9040 0.2989 +vn 0.4357 -0.7509 -0.4963 +vn 0.5513 -0.6699 -0.4973 +vn 0.7219 0.0000 -0.6920 +vn 0.4078 -0.8164 -0.4088 +vn 0.4342 -0.7544 -0.4923 +vn 0.4258 -0.7569 -0.4958 +vn 0.0769 -0.8462 -0.5274 +vn 0.3360 -0.8009 -0.4957 +vn 0.1571 -0.8408 -0.5180 +vn 0.3247 -0.8053 -0.4961 +vn 0.2808 -0.9204 -0.2721 +vn -0.4531 0.0907 0.8869 +vn -0.3098 0.7324 0.6064 +vn -0.2512 0.6205 0.7429 +vn 0.5779 -0.6500 -0.4935 +vn 0.6612 -0.5317 -0.5292 +vn 0.1619 -0.8439 -0.5115 +vn 0.2323 -0.8355 -0.4979 +vn 0.5106 -0.7022 -0.4962 +vn 0.4689 -0.7311 -0.4957 +vn 0.4642 -0.7338 -0.4960 +vn 0.5394 -0.6712 -0.5085 +vn 0.5501 -0.6477 -0.5271 +vn 0.0000 -0.9281 -0.3722 +vn 0.1862 -0.8985 -0.3975 +vn 0.1903 -0.8704 -0.4541 +vn 0.0494 -0.8573 -0.5124 +vn 0.0922 -0.8554 -0.5097 +vn 0.7508 0.6591 -0.0441 +vn 0.7072 -0.4237 -0.5660 +vn 0.7634 0.0000 -0.6459 +vn 0.3788 -0.7814 -0.4958 +vn 0.3882 -0.7766 -0.4962 +vn 0.3293 -0.7982 -0.5044 +vn 0.3606 -0.7898 -0.4962 +vn 0.3061 -0.8126 -0.4959 +vn 0.2842 -0.8289 -0.4819 +vn 0.2881 -0.8189 -0.4964 +vn 0.2738 -0.8245 -0.4953 +vn 0.3241 -0.9392 0.1137 +vn 0.4167 -0.8503 -0.3216 +vn 0.4034 -0.8546 -0.3271 +usemtl None +s off +f 130/123/185 141/124/185 160/125/185 +f 127/126/186 125/127/186 129/128/186 +f 128/129/187 127/126/187 129/128/187 +f 126/130/188 128/129/188 129/128/188 +f 132/131/189 130/123/189 134/132/189 +f 125/127/186 127/126/186 135/133/186 +f 125/127/190 124/134/190 136/135/190 +f 130/123/189 132/131/189 136/135/189 +f 128/129/191 126/130/191 137/136/191 +f 126/130/192 136/135/192 137/136/192 +f 136/135/189 132/131/189 137/136/189 +f 135/133/186 127/126/186 138/137/186 +f 131/138/193 135/133/193 138/137/193 +f 136/135/190 124/134/190 141/124/190 +f 130/123/189 136/135/189 141/124/189 +f 131/138/194 138/137/194 142/139/194 +f 134/132/195 123/140/195 144/141/195 +f 132/131/189 134/132/189 144/141/189 +f 138/137/196 137/136/196 145/142/196 +f 142/139/197 138/137/197 145/142/197 +f 127/126/198 128/129/198 146/143/198 +f 128/129/199 137/136/199 146/143/199 +f 138/137/186 127/126/186 146/143/186 +f 137/136/196 138/137/196 146/143/196 +f 134/132/189 130/123/189 147/144/189 +f 131/138/200 142/139/200 147/144/200 +f 144/141/201 123/140/201 148/145/201 +f 142/139/202 145/142/202 148/145/202 +f 130/123/203 140/146/203 149/147/203 +f 147/144/204 130/123/204 149/147/204 +f 131/138/205 147/144/205 149/147/205 +f 135/133/206 131/138/206 150/148/206 +f 140/146/207 133/149/207 150/148/207 +f 143/150/208 135/133/208 150/148/208 +f 133/149/209 143/150/209 150/148/209 +f 133/149/210 124/134/210 151/151/210 +f 129/128/211 125/127/211 152/152/211 +f 126/130/212 129/128/212 152/152/212 +f 125/127/190 136/135/190 152/152/190 +f 136/135/213 126/130/213 152/152/213 +f 132/131/189 144/141/189 153/153/189 +f 144/141/214 148/145/214 153/153/214 +f 148/145/215 132/131/215 153/153/215 +f 135/133/216 143/150/216 154/154/216 +f 151/151/217 139/155/217 154/154/217 +f 123/140/218 134/132/218 155/156/218 +f 134/132/219 147/144/219 155/156/219 +f 147/144/220 142/139/220 155/156/220 +f 148/145/221 123/140/221 155/156/221 +f 142/139/222 148/145/222 155/156/222 +f 124/134/223 125/127/223 156/157/223 +f 125/127/186 135/133/186 156/157/186 +f 151/151/224 124/134/224 156/157/224 +f 139/155/225 151/151/225 156/157/225 +f 135/133/226 154/154/226 156/157/226 +f 154/154/227 139/155/227 156/157/227 +f 137/136/228 132/131/228 157/158/228 +f 145/142/196 137/136/196 157/158/196 +f 132/131/229 148/145/229 157/158/229 +f 148/145/230 145/142/230 157/158/230 +f 149/147/231 140/146/231 158/159/231 +f 131/138/232 149/147/232 158/159/232 +f 150/148/233 131/138/233 158/159/233 +f 140/146/234 150/148/234 158/159/234 +f 143/150/235 133/149/235 159/160/235 +f 133/149/236 151/151/236 159/160/236 +f 154/154/237 143/150/237 159/160/237 +f 151/151/238 154/154/238 159/160/238 +f 124/134/239 133/149/239 160/125/239 +f 140/146/240 130/123/240 160/125/240 +f 133/149/241 140/146/241 160/125/241 +f 141/124/190 124/134/190 160/125/190 +o Bowl_hull_3 +v 0.071125 -0.028888 0.037727 +v 0.040084 -0.026731 -0.010980 +v 0.040517 -0.026731 -0.010980 +v 0.040084 -0.043972 0.007990 +v 0.074570 -0.026731 0.049801 +v 0.070263 -0.043972 0.048507 +v 0.040084 -0.043540 0.014887 +v 0.040517 -0.026731 -0.003652 +v 0.065948 -0.043972 0.049801 +v 0.078884 -0.026731 0.049801 +v 0.050000 -0.042678 0.018332 +v 0.042241 -0.027163 -0.008823 +v 0.074141 -0.036644 0.048075 +v 0.040950 -0.032766 -0.004946 +v 0.071550 -0.043110 0.050232 +v 0.052158 -0.027163 0.006264 +v 0.065086 -0.043972 0.040747 +v 0.065948 -0.043540 0.049801 +v 0.074570 -0.027163 0.050232 +v 0.071983 -0.042247 0.049369 +v 0.042674 -0.043972 0.010572 +v 0.040084 -0.043972 0.014887 +v 0.076727 -0.032766 0.049369 +v 0.072846 -0.026731 0.047212 +v 0.040084 -0.026731 -0.004515 +v 0.077156 -0.027593 0.046781 +v 0.055606 -0.043972 0.027380 +v 0.040517 -0.036644 -0.001064 +v 0.066381 -0.043972 0.050232 +v 0.058193 -0.027163 0.015749 +v 0.078884 -0.027163 0.050232 +v 0.040084 -0.043110 0.014455 +v 0.064657 -0.026731 0.026091 +v 0.041379 -0.029749 -0.007529 +v 0.051296 -0.029318 0.006696 +v 0.056036 -0.042247 0.026091 +v 0.068968 -0.034921 0.038590 +v 0.040084 -0.034059 -0.004083 +vt 0.098571 0.022318 +vt 0.162001 0.011159 +vt 0.112666 0.000000 +vt 0.000000 0.011159 +vt 0.000000 0.000000 +vt 0.992952 0.888802 +vt 0.309906 0.000000 +vt 0.422572 0.000000 +vt 0.119714 0.011159 +vt 0.971809 0.777800 +vt 0.992952 0.666601 +vt 0.992952 1.000000 +vt 0.035239 0.055599 +vt 0.281715 0.311179 +vt 0.845047 0.644381 +vt 0.992952 0.666601 +vt 1.000000 0.888802 +vt 1.000000 0.810983 +vt 0.985904 0.822142 +vt 0.352095 0.066758 +vt 0.422572 0.000000 +vt 0.964761 0.877741 +vt 0.985904 0.944401 +vt 0.950666 0.844362 +vt 0.105619 0.000000 +vt 0.795713 0.800020 +vt 0.943618 0.955462 +vt 0.478857 0.255579 +vt 0.626664 0.400059 +vt 1.000000 0.677760 +vt 0.436668 0.466719 +vt 1.000000 1.000000 +vt 0.415525 0.000000 +vt 0.605619 0.633320 +vt 0.056382 0.033379 +vt 0.288763 0.288959 +vt 0.605619 0.411120 +vt 0.809808 0.744420 +vn 0.3783 -0.6757 -0.6327 +vn 0.0000 1.0000 0.0000 +vn -1.0000 -0.0000 0.0000 +vn 0.0000 -1.0000 -0.0000 +vn 0.7188 0.5100 -0.4725 +vn -0.8035 0.0000 0.5953 +vn -0.7277 0.4847 0.4854 +vn 0.0000 0.7066 0.7076 +vn -0.7442 0.3772 0.5513 +vn 0.7450 -0.6201 -0.2460 +vn 0.7282 -0.4834 -0.4858 +vn 0.7352 -0.4624 -0.4956 +vn 0.8166 -0.4086 -0.4077 +vn 0.8943 -0.4474 0.0016 +vn 0.8101 -0.3147 -0.4947 +vn 0.8656 -0.2797 -0.4154 +vn 0.6729 -0.5493 -0.4955 +vn 0.6098 -0.6387 -0.4692 +vn 0.6536 -0.5707 -0.4971 +vn 0.5205 -0.6757 -0.5220 +vn 0.6294 -0.5996 -0.4943 +vn 0.1543 -0.9250 0.3471 +vn -0.7058 0.0000 0.7084 +vn 0.0000 -0.0000 1.0000 +vn -0.5375 0.2618 0.8016 +vn 0.7997 -0.3367 -0.4970 +vn 0.7898 -0.3613 -0.4956 +vn 0.8158 -0.2864 -0.5025 +vn 0.9043 -0.3017 -0.3021 +vn 0.8310 -0.3822 0.4041 +vn -0.7274 0.4858 0.4846 +vn -0.7274 0.4859 0.4846 +vn -0.7188 0.5241 0.4568 +vn -0.7931 0.4610 0.3980 +vn 0.6549 0.6240 -0.4264 +vn 0.8545 0.0833 -0.5128 +vn 0.8229 0.2209 -0.5236 +vn 0.8332 -0.2089 -0.5120 +vn 0.6212 -0.5065 -0.5980 +vn 0.4381 -0.6196 -0.6512 +vn 0.7180 -0.4879 -0.4964 +vn 0.7637 -0.4060 -0.5020 +vn 0.7441 -0.4473 -0.4962 +vn 0.6806 -0.5395 -0.4956 +vn 0.6886 -0.5361 -0.4883 +vn 0.6925 -0.5234 -0.4965 +vn 0.7066 -0.5050 -0.4958 +vn 0.7676 -0.4094 -0.4930 +vn 0.7810 -0.3783 -0.4969 +vn 0.7871 -0.3668 -0.4959 +vn 0.7671 -0.4063 -0.4964 +vn 0.7628 -0.4152 -0.4956 +vn 0.0000 -0.6853 -0.7282 +vn 0.3066 -0.6619 -0.6840 +vn -0.1858 -0.7594 -0.6235 +usemtl None +s off +f 174/161/242 188/162/242 198/163/242 +f 163/164/243 162/165/243 165/166/243 +f 162/165/244 164/167/244 167/168/244 +f 165/166/243 162/165/243 168/169/243 +f 164/167/245 166/170/245 169/171/245 +f 163/164/243 165/166/243 170/172/243 +f 172/173/246 163/164/246 176/174/246 +f 166/170/245 164/167/245 177/175/245 +f 167/168/247 169/171/247 178/176/247 +f 165/166/248 167/168/248 179/177/248 +f 170/172/249 165/166/249 179/177/249 +f 167/168/250 178/176/250 179/177/250 +f 175/178/251 166/170/251 180/179/251 +f 166/170/252 177/175/252 180/179/252 +f 177/175/253 172/173/253 180/179/253 +f 177/175/245 164/167/245 181/180/245 +f 167/168/244 164/167/244 182/181/244 +f 164/167/245 169/171/245 182/181/245 +f 169/171/247 167/168/247 182/181/247 +f 180/179/254 173/182/254 183/183/254 +f 175/178/255 180/179/255 183/183/255 +f 165/166/243 168/169/243 184/184/243 +f 162/165/244 167/168/244 185/185/244 +f 168/169/243 162/165/243 185/185/243 +f 183/183/256 161/186/256 186/187/256 +f 170/172/257 183/183/257 186/187/257 +f 171/188/258 174/161/258 187/189/258 +f 181/180/259 171/188/259 187/189/259 +f 177/175/245 181/180/245 187/189/245 +f 174/161/260 171/188/260 188/162/260 +f 181/180/261 164/167/261 188/162/261 +f 171/188/262 181/180/262 188/162/262 +f 169/171/245 166/170/245 189/190/245 +f 166/170/263 175/178/263 189/190/263 +f 178/176/264 169/171/264 189/190/264 +f 175/178/265 179/177/265 189/190/265 +f 179/177/266 178/176/266 189/190/266 +f 161/186/267 183/183/267 190/191/267 +f 183/183/268 173/182/268 190/191/268 +f 186/187/269 161/186/269 190/191/269 +f 179/177/265 175/178/265 191/192/265 +f 170/172/249 179/177/249 191/192/249 +f 183/183/270 170/172/270 191/192/270 +f 175/178/271 183/183/271 191/192/271 +f 167/168/272 165/166/272 192/193/272 +f 165/166/273 184/184/273 192/193/273 +f 184/184/274 168/169/274 192/193/274 +f 185/185/244 167/168/244 192/193/244 +f 168/169/275 185/185/275 192/193/275 +f 163/164/243 170/172/243 193/194/243 +f 176/174/276 163/164/276 193/194/276 +f 170/172/277 186/187/277 193/194/277 +f 190/191/278 176/174/278 193/194/278 +f 186/187/279 190/191/279 193/194/279 +f 163/164/280 172/173/280 194/195/280 +f 174/161/281 163/164/281 194/195/281 +f 172/173/282 177/175/282 194/195/282 +f 172/173/283 176/174/283 195/196/283 +f 180/179/284 172/173/284 195/196/284 +f 187/189/285 174/161/285 196/197/285 +f 177/175/286 187/189/286 196/197/286 +f 174/161/287 194/195/287 196/197/287 +f 194/195/288 177/175/288 196/197/288 +f 173/182/289 180/179/289 197/198/289 +f 176/174/290 190/191/290 197/198/290 +f 190/191/291 173/182/291 197/198/291 +f 195/196/292 176/174/292 197/198/292 +f 180/179/293 195/196/293 197/198/293 +f 162/165/294 163/164/294 198/163/294 +f 164/167/244 162/165/244 198/163/244 +f 163/164/295 174/161/295 198/163/295 +f 188/162/296 164/167/296 198/163/296 +o Bowl_hull_4 +v -0.022432 -0.027589 -0.050212 +v -0.014237 -0.034487 -0.033402 +v -0.014669 -0.034487 -0.033402 +v -0.030618 -0.011640 -0.033404 +v -0.014237 -0.029314 -0.050212 +v -0.029756 -0.022850 -0.033404 +v -0.033205 -0.011640 -0.050212 +v -0.014237 -0.029314 -0.033402 +v -0.035362 -0.012074 -0.033404 +v -0.030618 -0.011640 -0.050212 +v -0.030618 -0.018108 -0.050212 +v -0.014669 -0.032333 -0.050212 +v -0.022860 -0.029746 -0.033835 +v -0.025874 -0.024570 -0.049352 +v -0.033637 -0.016386 -0.034266 +v -0.018118 -0.030607 -0.050212 +v -0.032775 -0.013799 -0.050212 +v -0.025444 -0.027589 -0.033835 +v -0.018980 -0.032333 -0.033835 +v -0.035362 -0.011640 -0.034266 +v -0.028029 -0.021991 -0.049783 +v -0.031480 -0.020265 -0.034266 +v -0.027601 -0.025433 -0.033835 +v -0.014237 -0.032333 -0.050212 +v -0.030186 -0.012074 -0.033404 +v -0.020273 -0.029314 -0.049783 +v -0.034499 -0.014662 -0.033835 +v -0.022860 -0.029746 -0.033404 +vt 0.603720 0.367365 +vt 0.698091 0.469460 +vt 0.792462 0.591817 +vt 0.773568 1.000000 +vt 0.698091 0.612079 +vt 0.000000 0.102095 +vt 1.000000 0.979542 +vt 1.000000 1.000000 +vt 0.773568 1.000000 +vt 0.490651 0.265368 +vt 0.018992 0.000000 +vt 0.000000 0.224550 +vt 0.000000 0.224550 +vt 0.283113 0.224550 +vt 0.905727 0.979542 +vt 0.830152 0.816269 +vt 0.094469 0.122455 +vt 0.207734 0.081637 +vt 0.792462 0.591817 +vt 0.565932 0.449099 +vt 0.905727 0.775450 +vt 0.000000 0.000000 +vt 0.453059 0.347103 +vt 0.377484 0.183731 +vt 0.905727 1.000000 +vt 0.018992 0.245008 +vt 0.773568 0.714272 +vt 0.132256 0.040818 +vn -0.5787 -0.5789 0.5745 +vn 0.0000 -0.0000 -1.0000 +vn 0.0000 0.0000 1.0000 +vn 1.0000 0.0000 0.0000 +vn -0.0002 -0.0001 1.0000 +vn -0.0001 0.0000 1.0000 +vn -0.0000 0.0001 1.0000 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -0.9919 -0.1271 +vn -0.8878 -0.4443 -0.1201 +vn -0.6362 -0.7626 -0.1170 +vn -0.6716 -0.7306 -0.1235 +vn -0.4348 -0.8932 -0.1144 +vn -0.4446 -0.8881 -0.1170 +vn -0.0814 0.8903 0.4480 +vn -0.9722 -0.1937 -0.1315 +vn -0.9619 -0.2444 -0.1230 +vn -0.4514 -0.3898 -0.8027 +vn -0.6519 -0.6181 -0.4393 +vn -0.8684 -0.4829 -0.1123 +vn -0.8198 -0.5599 -0.1200 +vn -0.8081 -0.5776 -0.1155 +vn -0.7021 -0.7023 -0.1172 +vn -0.7722 -0.6250 -0.1142 +vn -0.7519 -0.6483 -0.1197 +vn 0.0013 0.0013 1.0000 +vn 0.7341 0.6791 0.0000 +vn 0.7085 0.7057 0.0000 +vn 0.7334 0.6798 -0.0013 +vn -0.6050 -0.7872 -0.1194 +vn -0.5305 -0.7584 -0.3786 +vn -0.5515 -0.8267 -0.1118 +vn -0.5280 -0.8412 -0.1165 +vn -0.6287 -0.3270 0.7056 +vn -0.9480 -0.2966 -0.1155 +vn -0.8997 -0.4206 -0.1169 +vn -0.8409 -0.4733 0.2625 +vn -0.8576 -0.4769 0.1923 +vn -0.0005 -0.0005 1.0000 +vn -0.6405 -0.7679 0.0000 +vn -0.4134 -0.7138 0.5653 +vn -0.5549 -0.8319 0.0000 +vn -0.5783 -0.5784 0.5753 +usemtl None +s off +f 221/199/297 216/200/297 226/201/297 +f 203/202/298 199/203/298 205/204/298 +f 201/205/299 200/206/299 206/207/299 +f 200/206/300 203/202/300 206/207/300 +f 204/208/301 201/205/301 207/209/301 +f 201/205/302 206/207/302 207/209/302 +f 206/207/303 202/210/303 207/209/303 +f 205/204/304 202/210/304 208/211/304 +f 203/202/298 205/204/298 208/211/298 +f 205/204/298 199/203/298 209/212/298 +f 200/206/305 201/205/305 210/213/305 +f 199/203/298 203/202/298 210/213/298 +f 199/203/298 210/213/298 214/214/298 +f 205/204/298 209/212/298 215/215/298 +f 209/212/306 213/216/306 215/215/306 +f 199/203/307 211/217/307 216/200/307 +f 212/218/308 199/203/308 216/200/308 +f 210/213/309 201/205/309 217/219/309 +f 214/214/310 210/213/310 217/219/310 +f 202/210/304 205/204/304 218/220/304 +f 207/209/311 202/210/311 218/220/311 +f 205/204/312 215/215/312 218/220/312 +f 215/215/313 207/209/313 218/220/313 +f 209/212/314 199/203/314 219/221/314 +f 199/203/315 212/218/315 219/221/315 +f 213/216/316 209/212/316 220/222/316 +f 209/212/317 219/221/317 220/222/317 +f 219/221/318 204/208/318 220/222/318 +f 212/218/319 216/200/319 221/199/319 +f 204/208/320 219/221/320 221/199/320 +f 219/221/321 212/218/321 221/199/321 +f 203/202/300 200/206/300 222/223/300 +f 200/206/305 210/213/305 222/223/305 +f 210/213/298 203/202/298 222/223/298 +f 202/210/322 206/207/322 223/224/322 +f 206/207/323 203/202/323 223/224/323 +f 208/211/324 202/210/324 223/224/324 +f 203/202/325 208/211/325 223/224/325 +f 211/217/326 199/203/326 224/225/326 +f 199/203/327 214/214/327 224/225/327 +f 217/219/328 211/217/328 224/225/328 +f 214/214/329 217/219/329 224/225/329 +f 204/208/330 207/209/330 225/226/330 +f 207/209/331 215/215/331 225/226/331 +f 215/215/332 213/216/332 225/226/332 +f 220/222/333 204/208/333 225/226/333 +f 213/216/334 220/222/334 225/226/334 +f 201/205/335 204/208/335 226/201/335 +f 216/200/336 211/217/336 226/201/336 +f 217/219/337 201/205/337 226/201/337 +f 211/217/338 217/219/338 226/201/338 +f 204/208/339 221/199/339 226/201/339 +o Bowl_hull_5 +v -0.012940 -0.033197 -0.049352 +v 0.005163 -0.036644 -0.033404 +v 0.005163 -0.032335 -0.033404 +v -0.014237 -0.029748 -0.033404 +v 0.005163 -0.032335 -0.050214 +v -0.013373 -0.034920 -0.033404 +v -0.002598 -0.035351 -0.050214 +v -0.014237 -0.029748 -0.050214 +v -0.004749 -0.037075 -0.033835 +v 0.005163 -0.035351 -0.048058 +v -0.014237 -0.032335 -0.050214 +v -0.012940 -0.029748 -0.050214 +v 0.002575 -0.037075 -0.035128 +v -0.008629 -0.034489 -0.049783 +v -0.014237 -0.034489 -0.034697 +v -0.009491 -0.036213 -0.033835 +v -0.012940 -0.029748 -0.033404 +v 0.002575 -0.035351 -0.050214 +v 0.004729 -0.037075 -0.033404 +v -0.000011 -0.037075 -0.035559 +v 0.005163 -0.034920 -0.050214 +v -0.006474 -0.034920 -0.049783 +vt 0.244616 0.974354 +vt 0.289056 0.025646 +vt 0.400157 0.025646 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.044538 1.000000 +vt 0.599941 0.000000 +vt 0.000000 0.000000 +vt 1.000000 0.128230 +vt 0.000000 0.000000 +vt 0.066856 0.000000 +vt 0.066856 0.051292 +vt 0.000000 0.923062 +vt 0.489037 0.974354 +vt 0.066856 1.000000 +vt 0.866582 0.000000 +vt 0.866582 0.897416 +vt 0.977584 1.000000 +vt 0.733262 0.871770 +vt 1.000000 0.000000 +vn -0.1948 -0.9740 -0.1158 +vn 0.0000 0.0000 1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn 0.1414 0.9899 0.0000 +vn 0.0000 1.0000 0.0000 +vn -0.2992 -0.8611 -0.4111 +vn -0.1346 -0.5192 -0.8440 +vn -0.8443 -0.1410 0.5170 +vn -0.4933 -0.8616 -0.1196 +vn -0.1068 -0.5878 0.8019 +vn -0.2959 -0.9478 -0.1185 +vn -0.3215 -0.9403 -0.1114 +vn -0.3243 -0.9410 -0.0970 +vn 0.0905 -0.9895 -0.1131 +vn -0.0425 -0.3566 0.9333 +vn 0.7021 -0.7094 -0.0626 +vn 0.0000 -1.0000 0.0000 +vn 0.0945 -0.9890 -0.1135 +vn -0.0400 -0.9932 -0.1098 +vn 0.0000 -0.9932 -0.1168 +vn 0.0189 -0.9934 -0.1135 +vn 0.1612 -0.9678 -0.1936 +vn -0.1229 -0.9852 -0.1198 +vn -0.1544 -0.7721 -0.6164 +vn -0.1776 -0.9776 -0.1129 +usemtl None +s off +f 242/227/340 240/228/340 248/229/340 +f 228/230/341 229/231/341 230/232/341 +f 229/231/342 228/230/342 231/233/342 +f 228/230/341 230/232/341 232/234/341 +f 231/233/343 233/235/343 234/236/343 +f 231/233/342 228/230/342 236/237/342 +f 230/232/344 234/236/344 237/238/344 +f 234/236/343 233/235/343 237/238/343 +f 229/231/345 231/233/345 238/239/345 +f 234/236/346 230/232/346 238/239/346 +f 231/233/343 234/236/343 238/239/343 +f 227/240/347 237/238/347 240/228/347 +f 237/238/348 233/235/348 240/228/348 +f 232/234/349 230/232/349 241/241/349 +f 237/238/350 227/240/350 241/241/350 +f 230/232/344 237/238/344 241/241/344 +f 235/242/351 232/234/351 242/227/351 +f 227/240/352 240/228/352 242/227/352 +f 241/241/353 227/240/353 242/227/353 +f 232/234/354 241/241/354 242/227/354 +f 230/232/341 229/231/341 243/243/341 +f 229/231/345 238/239/345 243/243/345 +f 238/239/346 230/232/346 243/243/346 +f 233/235/343 231/233/343 244/244/343 +f 239/245/355 244/244/355 245/246/355 +f 228/230/341 232/234/341 245/246/341 +f 232/234/356 235/242/356 245/246/356 +f 236/237/357 228/230/357 245/246/357 +f 235/242/358 239/245/358 245/246/358 +f 244/244/359 236/237/359 245/246/359 +f 235/242/360 233/235/360 246/247/360 +f 239/245/358 235/242/358 246/247/358 +f 233/235/361 244/244/361 246/247/361 +f 244/244/362 239/245/362 246/247/362 +f 231/233/342 236/237/342 247/248/342 +f 244/244/343 231/233/343 247/248/343 +f 236/237/363 244/244/363 247/248/363 +f 233/235/364 235/242/364 248/229/364 +f 240/228/365 233/235/365 248/229/365 +f 235/242/366 242/227/366 248/229/366 +o Bowl_hull_6 +v 0.014650 0.032333 -0.050214 +v 0.029737 0.022419 -0.033404 +v 0.029737 0.022419 -0.033835 +v 0.005163 0.032333 -0.050214 +v 0.005163 0.036644 -0.033404 +v 0.005163 0.032333 -0.033404 +v 0.023697 0.022419 -0.050214 +v 0.018958 0.032333 -0.033404 +v 0.025855 0.024575 -0.049783 +v 0.023697 0.022419 -0.033404 +v 0.005163 0.034918 -0.050214 +v 0.009479 0.036212 -0.033835 +v 0.025422 0.027592 -0.033835 +v 0.020250 0.029317 -0.049783 +v 0.027146 0.022419 -0.050214 +v 0.008613 0.034488 -0.049783 +v 0.014650 0.034488 -0.033835 +v 0.029737 0.022851 -0.033835 +v 0.011632 0.033625 -0.049783 +v 0.022838 0.029746 -0.033835 +v 0.022408 0.027592 -0.050214 +v 0.007321 0.036644 -0.033835 +v 0.017662 0.031039 -0.048921 +v 0.027579 0.025438 -0.033404 +v 0.027579 0.022851 -0.048058 +vt 0.842013 0.025646 +vt 1.000000 0.974354 +vt 0.912197 0.128230 +vt 1.000000 1.000000 +vt 0.000000 1.000000 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 0.754209 0.000000 +vt 1.000000 0.974354 +vt 0.386061 0.000000 +vt 0.561374 1.000000 +vt 0.754209 1.000000 +vt 0.000000 0.000000 +vt 0.175607 0.974354 +vt 0.894577 0.000000 +vt 0.140368 0.025646 +vt 0.386061 0.974354 +vt 0.263215 0.025646 +vt 0.613939 0.025646 +vt 0.719264 0.974354 +vt 0.701742 0.000000 +vt 0.824393 0.974354 +vt 0.087803 0.974354 +vt 0.508614 0.076938 +vt 0.912197 1.000000 +vn 0.7573 0.6428 -0.1149 +vn 0.0000 0.0000 1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.4717 -0.8818 -0.0000 +vn -0.0000 -1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.1318 0.4218 0.8970 +vn 0.1733 0.6359 -0.7521 +vn 0.1689 0.5066 0.8455 +vn 1.0000 0.0000 0.0000 +vn 0.1987 0.6949 -0.6912 +vn 0.2730 0.9547 -0.1180 +vn 0.3143 0.9429 -0.1105 +vn 0.3760 0.9187 -0.1209 +vn 0.5428 0.8325 -0.1105 +vn 0.6053 0.7870 -0.1194 +vn 0.6623 0.7392 -0.1219 +vn 0.4063 0.6648 -0.6268 +vn 0.4796 0.4393 -0.7596 +vn 0.6360 0.7628 -0.1170 +vn -0.0204 0.9946 -0.1021 +vn 0.1400 0.6997 0.7006 +vn 0.1378 0.9830 -0.1217 +vn 0.1948 0.9740 -0.1158 +vn 0.4733 0.8416 -0.2604 +vn 0.5237 0.8442 -0.1141 +vn 0.4341 0.8932 -0.1175 +vn 0.4535 0.8842 -0.1116 +vn 0.7132 0.6921 -0.1116 +vn 0.7031 0.5025 0.5031 +vn 0.7536 0.6475 -0.1135 +vn 0.4563 0.5705 0.6829 +vn 0.5412 0.6491 0.5345 +vn 0.9665 -0.2061 -0.1529 +vn 0.8018 0.5341 -0.2680 +vn 0.9887 0.0000 -0.1500 +usemtl None +s off +f 257/249/367 266/250/367 273/251/367 +f 250/252/368 253/253/368 254/254/368 +f 253/253/369 252/255/369 254/254/369 +f 254/254/370 252/255/370 255/256/370 +f 251/257/371 250/252/371 255/256/371 +f 252/255/372 249/258/372 255/256/372 +f 253/253/368 250/252/368 256/259/368 +f 250/252/368 254/254/368 258/260/368 +f 254/254/370 255/256/370 258/260/370 +f 255/256/371 250/252/371 258/260/371 +f 249/258/372 252/255/372 259/261/372 +f 252/255/369 253/253/369 259/261/369 +f 253/253/373 256/259/373 260/262/373 +f 255/256/372 249/258/372 263/263/372 +f 251/257/371 255/256/371 263/263/371 +f 249/258/374 259/261/374 264/264/374 +f 260/262/375 256/259/375 265/265/375 +f 250/252/376 251/257/376 266/250/376 +f 249/258/377 264/264/377 267/266/377 +f 264/264/378 260/262/378 267/266/378 +f 260/262/379 265/265/379 267/266/379 +f 265/265/380 249/258/380 267/266/380 +f 262/267/381 256/259/381 268/268/381 +f 262/267/382 268/268/382 269/269/382 +f 261/270/383 257/249/383 269/269/383 +f 249/258/384 262/267/384 269/269/384 +f 263/263/372 249/258/372 269/269/372 +f 257/249/385 263/263/385 269/269/385 +f 268/268/386 261/270/386 269/269/386 +f 259/261/387 253/253/387 270/271/387 +f 253/253/388 260/262/388 270/271/388 +f 264/264/389 259/261/389 270/271/389 +f 260/262/390 264/264/390 270/271/390 +f 262/267/391 249/258/391 271/272/391 +f 256/259/392 262/267/392 271/272/392 +f 249/258/393 265/265/393 271/272/393 +f 265/265/394 256/259/394 271/272/394 +f 256/259/368 250/252/368 272/273/368 +f 257/249/395 261/270/395 272/273/395 +f 250/252/396 266/250/396 272/273/396 +f 266/250/397 257/249/397 272/273/397 +f 268/268/398 256/259/398 272/273/398 +f 261/270/399 268/268/399 272/273/399 +f 251/257/400 263/263/400 273/251/400 +f 263/263/401 257/249/401 273/251/401 +f 266/250/402 251/257/402 273/251/402 +o Bowl_hull_7 +v 0.034477 0.009055 -0.048921 +v 0.024133 0.022418 -0.050214 +v 0.027583 0.022418 -0.050214 +v 0.024133 0.022418 -0.033404 +v 0.032323 0.003453 -0.050214 +v 0.036201 0.009488 -0.033404 +v 0.032323 0.003453 -0.033404 +v 0.030599 0.021554 -0.033404 +v 0.037065 0.003018 -0.034697 +v 0.032753 0.013793 -0.050214 +v 0.035339 0.003018 -0.049783 +v 0.032753 0.018104 -0.034266 +v 0.024133 0.021983 -0.033404 +v 0.029738 0.022418 -0.033404 +v 0.030170 0.018968 -0.049783 +v 0.024133 0.021983 -0.050214 +v 0.034477 0.014657 -0.033835 +v 0.032753 0.003018 -0.033404 +v 0.037065 0.004744 -0.033404 +v 0.034909 0.006037 -0.050214 +v 0.032753 0.003018 -0.050214 +v 0.034047 0.010350 -0.049783 +v 0.030599 0.021554 -0.034266 +v 0.031461 0.016812 -0.049352 +v 0.036633 0.006899 -0.034697 +vt 0.911022 1.000000 +vt 0.844362 0.000000 +vt 0.799922 0.923062 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 0.977584 0.000000 +vt 0.666503 1.000000 +vt 0.977584 1.000000 +vt 0.044538 1.000000 +vt 0.444597 0.000000 +vt 0.022416 1.000000 +vt 0.000000 1.000000 +vt 0.177858 0.025646 +vt 0.022416 0.000000 +vt 0.400059 0.974354 +vt 0.222396 0.948708 +vt 1.000000 1.000000 +vt 1.000000 0.025646 +vt 1.000000 0.923062 +vt 1.000000 0.000000 +vt 0.688821 0.076938 +vt 0.622064 0.025646 +vt 0.044538 0.948708 +vt 0.288958 0.051292 +vn 0.9850 0.1273 -0.1165 +vn 0.0000 1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -0.0000 1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.9146 -0.4043 0.0000 +vn 0.5973 0.3580 -0.7177 +vn 0.5217 0.2422 0.8180 +vn 0.8442 0.4573 0.2796 +vn -0.7108 -0.7034 0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.9899 0.0848 -0.1132 +vn 0.2334 -0.5830 0.7782 +vn 0.9854 0.1238 -0.1168 +vn 0.1633 -0.1166 -0.9797 +vn 0.9630 0.2443 -0.1138 +vn 0.9457 0.3064 -0.1083 +vn 0.9345 0.3366 -0.1161 +vn 0.9636 0.2093 -0.1666 +vn 0.7699 0.2140 -0.6013 +vn 0.8482 0.5296 0.0000 +vn 0.6623 0.7445 -0.0849 +vn 0.7084 0.7058 0.0000 +vn 0.8015 0.5858 -0.1198 +vn 0.8430 0.5264 -0.1111 +vn 0.8441 0.4462 -0.2973 +vn 0.8621 0.4932 -0.1161 +vn 0.9005 0.4188 -0.1169 +vn 0.8942 0.4331 -0.1137 +vn 0.9692 0.2185 -0.1138 +vn 0.9834 0.1790 -0.0300 +vn 0.9745 0.1903 -0.1189 +usemtl None +s off +f 292/274/403 293/275/403 298/276/403 +f 276/277/404 275/278/404 277/279/404 +f 275/278/405 276/277/405 278/280/405 +f 279/281/406 277/279/406 280/282/406 +f 277/279/406 279/281/406 281/283/406 +f 278/280/405 276/277/405 283/284/405 +f 277/279/407 275/278/407 286/285/407 +f 278/280/408 280/282/408 286/285/408 +f 280/282/406 277/279/406 286/285/406 +f 276/277/404 277/279/404 287/286/404 +f 277/279/406 281/283/406 287/286/406 +f 283/284/409 276/277/409 288/287/409 +f 275/278/405 278/280/405 289/288/405 +f 286/285/407 275/278/407 289/288/407 +f 278/280/408 286/285/408 289/288/408 +f 281/283/410 279/281/410 290/289/410 +f 285/290/411 281/283/411 290/289/411 +f 280/282/412 278/280/412 291/291/412 +f 279/281/406 280/282/406 291/291/406 +f 284/292/413 282/293/413 291/291/413 +f 282/293/414 284/292/414 292/274/414 +f 279/281/406 291/291/406 292/274/406 +f 291/291/415 282/293/415 292/274/415 +f 278/280/405 283/284/405 293/275/405 +f 292/274/416 284/292/416 293/275/416 +f 291/291/412 278/280/412 294/294/412 +f 284/292/413 291/291/413 294/294/413 +f 278/280/405 293/275/405 294/294/405 +f 293/275/417 284/292/417 294/294/417 +f 279/281/418 274/295/418 295/296/418 +f 290/289/419 279/281/419 295/296/419 +f 283/284/420 290/289/420 295/296/420 +f 274/295/421 293/275/421 295/296/421 +f 293/275/422 283/284/422 295/296/422 +f 281/283/423 285/290/423 296/297/423 +f 276/277/424 287/286/424 296/297/424 +f 287/286/425 281/283/425 296/297/425 +f 288/287/426 276/277/426 296/297/426 +f 285/290/427 288/287/427 296/297/427 +f 283/284/428 288/287/428 297/298/428 +f 288/287/429 285/290/429 297/298/429 +f 290/289/430 283/284/430 297/298/430 +f 285/290/431 290/289/431 297/298/431 +f 274/295/432 279/281/432 298/276/432 +f 279/281/433 292/274/433 298/276/433 +f 293/275/434 274/295/434 298/276/434 +o Bowl_hull_8 +v -0.030178 0.002587 -0.050214 +v 0.037056 -0.003018 -0.033404 +v 0.037056 -0.003018 -0.034697 +v 0.037056 0.003017 -0.033404 +v -0.030178 -0.002587 -0.033404 +v 0.034904 -0.003018 -0.050214 +v 0.034904 0.003017 -0.050214 +v -0.030178 0.002587 -0.033404 +v -0.030178 -0.002587 -0.050214 +v 0.035332 0.002586 -0.050214 +v 0.032745 -0.003018 -0.033404 +v 0.032745 0.003017 -0.033404 +v 0.035332 -0.002586 -0.050214 +v 0.037056 0.002586 -0.035130 +v 0.032745 -0.003018 -0.050214 +v 0.032745 0.003017 -0.050214 +vt 0.935872 1.000000 +vt 0.967985 0.000000 +vt 0.935872 0.000000 +vt 1.000000 1.000000 +vt 1.000000 0.923062 +vt 1.000000 1.000000 +vt 0.000000 1.000000 +vt 0.967985 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 0.974349 0.000000 +vt 0.935872 1.000000 +vt 0.974349 0.000000 +vt 1.000000 0.897318 +vt 0.935872 0.000000 +vn 0.0000 1.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn -0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn 0.7070 0.7014 -0.0905 +vn -0.0069 -1.0000 0.0000 +vn -0.0068 1.0000 0.0000 +vn 0.7069 -0.7004 -0.0981 +vn 0.9935 0.0000 -0.1136 +vn 0.9044 0.4139 -0.1034 +vn 0.9938 -0.0085 -0.1107 +usemtl None +s off +f 310/299/435 305/300/435 314/301/435 +f 300/302/436 301/303/436 302/304/436 +f 300/302/437 302/304/437 303/305/437 +f 301/303/438 300/302/438 304/306/438 +f 304/306/439 299/307/439 305/300/439 +f 299/307/440 303/305/440 306/308/440 +f 303/305/437 302/304/437 306/308/437 +f 303/305/440 299/307/440 307/309/440 +f 299/307/439 304/306/439 307/309/439 +f 304/306/439 305/300/439 308/310/439 +f 305/300/441 302/304/441 308/310/441 +f 300/302/437 303/305/437 309/311/437 +f 304/306/438 300/302/438 309/311/438 +f 303/305/442 307/309/442 309/311/442 +f 302/304/435 305/300/435 310/299/435 +f 306/308/437 302/304/437 310/299/437 +f 299/307/443 306/308/443 310/299/443 +f 301/303/444 304/306/444 311/312/444 +f 304/306/439 308/310/439 311/312/439 +f 311/312/445 308/310/445 312/313/445 +f 302/304/436 301/303/436 312/313/436 +f 308/310/446 302/304/446 312/313/446 +f 301/303/447 311/312/447 312/313/447 +f 307/309/439 304/306/439 313/314/439 +f 304/306/438 309/311/438 313/314/438 +f 309/311/442 307/309/442 313/314/442 +f 305/300/439 299/307/439 314/301/439 +f 299/307/443 310/299/443 314/301/443 +o Bowl_hull_9 +v 0.080174 -0.023279 0.050233 +v 0.040084 -0.012505 -0.021762 +v 0.040518 -0.012505 -0.021762 +v 0.040084 -0.026726 -0.011409 +v 0.078450 -0.012505 0.050233 +v 0.040518 -0.026296 -0.004080 +v 0.075005 -0.026726 0.050233 +v 0.040084 -0.012505 -0.015293 +v 0.082333 -0.012505 0.049366 +v 0.073280 -0.026726 0.039887 +v 0.040518 -0.020692 -0.017019 +v 0.046556 -0.013367 -0.011839 +v 0.081039 -0.018540 0.048936 +v 0.051296 -0.026726 0.004538 +v 0.078450 -0.026726 0.048506 +v 0.075005 -0.025865 0.050233 +v 0.040948 -0.016814 -0.019168 +v 0.040084 -0.026726 -0.004940 +v 0.079314 -0.023279 0.048076 +v 0.040518 -0.012505 -0.014426 +v 0.059058 -0.012935 0.009281 +v 0.061639 -0.026726 0.020916 +v 0.040948 -0.026726 -0.010980 +v 0.082333 -0.012505 0.050233 +v 0.041378 -0.014229 -0.020028 +v 0.077156 -0.012505 0.048076 +v 0.081039 -0.013367 0.047216 +v 0.078880 -0.026726 0.050233 +v 0.048707 -0.012505 -0.008393 +v 0.040948 -0.024573 -0.013136 +vt 0.365309 0.265368 +vt 0.149765 0.020458 +vt 0.119812 0.020458 +vt 0.000000 0.010278 +vt 0.000000 0.000000 +vt 1.000000 0.908085 +vt 1.000000 0.948904 +vt 1.000000 0.826547 +vt 0.143794 0.000000 +vt 0.089859 0.000000 +vt 0.987960 1.000000 +vt 0.856304 0.785728 +vt 0.065877 0.010278 +vt 0.981989 0.969362 +vt 0.976018 0.908085 +vt 0.245595 0.010278 +vt 1.000000 0.826547 +vt 0.036022 0.020458 +vt 0.233653 0.000000 +vt 0.970047 0.928544 +vt 0.137823 0.153191 +vt 0.101899 0.010278 +vt 0.431186 0.449099 +vt 0.592796 0.510180 +vt 1.000000 1.000000 +vt 0.024080 0.030638 +vt 0.970047 0.877447 +vt 0.958105 0.969362 +vt 1.000000 0.918265 +vt 0.185689 0.204092 +vn 0.7273 -0.4856 -0.4850 +vn 0.0000 1.0000 0.0000 +vn -0.0000 0.0000 1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.0000 -1.0000 0.0000 +vn 0.0000 -0.5013 -0.8653 +vn -0.9148 -0.2376 -0.3265 +vn 0.9750 -0.2027 -0.0909 +vn -0.8256 0.2129 0.5225 +vn -0.8442 0.0000 0.5360 +vn 0.1915 -0.4920 -0.8493 +vn -0.8259 -0.2111 0.5228 +vn -0.9092 0.2450 0.3366 +vn 0.8965 -0.2613 -0.3576 +vn 0.8412 -0.2162 -0.4957 +vn 0.8946 -0.2688 -0.3569 +vn 0.8260 -0.2689 -0.4954 +vn -0.8475 0.3185 0.4246 +vn 0.8455 -0.1967 -0.4965 +vn 0.7857 -0.3694 -0.4962 +vn 0.7885 -0.3628 -0.4967 +vn 0.8079 -0.3185 -0.4958 +vn 0.9805 -0.1965 0.0000 +vn 0.8455 -0.1047 -0.5236 +vn 0.6709 -0.3321 -0.6631 +vn 0.8145 -0.3005 -0.4963 +vn 0.8260 -0.2682 -0.4958 +vn 0.8280 -0.2617 -0.4960 +vn -0.8139 0.3145 0.4885 +vn -0.8066 0.3547 0.4728 +vn 0.8725 -0.1541 -0.4637 +vn 0.8640 -0.0478 -0.5012 +vn 0.8526 -0.1649 -0.4959 +vn 0.9117 -0.3423 -0.2271 +vn 0.8521 -0.0393 -0.5219 +vn 0.8577 0.1228 -0.4993 +vn 0.8554 -0.1196 -0.5039 +vn 0.2703 -0.6659 -0.6954 +vn 0.7632 -0.4129 -0.4971 +vn 0.3316 -0.6675 -0.6667 +usemtl None +s off +f 328/315/448 337/316/448 344/317/448 +f 317/318/449 316/319/449 319/320/449 +f 315/321/450 319/320/450 321/322/450 +f 316/319/451 318/323/451 322/324/451 +f 319/320/449 316/319/449 322/324/449 +f 317/318/449 319/320/449 323/325/449 +f 321/322/452 318/323/452 324/326/452 +f 316/319/453 317/318/453 325/327/453 +f 318/323/454 316/319/454 325/327/454 +f 323/325/455 315/321/455 327/328/455 +f 324/326/452 318/323/452 328/315/452 +f 321/322/452 324/326/452 329/329/452 +f 319/320/456 320/330/456 330/331/456 +f 321/322/450 319/320/450 330/331/450 +f 320/330/457 321/322/457 330/331/457 +f 325/327/458 317/318/458 331/332/458 +f 318/323/452 321/322/452 332/333/452 +f 321/322/459 320/330/459 332/333/459 +f 322/324/451 318/323/451 332/333/451 +f 320/330/460 322/324/460 332/333/460 +f 327/328/461 315/321/461 333/334/461 +f 326/335/462 327/328/462 333/334/462 +f 315/321/463 329/329/463 333/334/463 +f 329/329/464 324/326/464 333/334/464 +f 319/320/449 322/324/449 334/336/449 +f 322/324/465 320/330/465 334/336/465 +f 327/328/466 326/335/466 335/337/466 +f 324/326/452 328/315/452 336/338/452 +f 328/315/467 325/327/467 336/338/467 +f 325/327/468 331/332/468 336/338/468 +f 331/332/469 324/326/469 336/338/469 +f 328/315/452 318/323/452 337/316/452 +f 319/320/450 315/321/450 338/339/450 +f 315/321/470 323/325/470 338/339/470 +f 323/325/449 319/320/449 338/339/449 +f 317/318/471 326/335/471 339/340/471 +f 331/332/472 317/318/472 339/340/472 +f 324/326/473 331/332/473 339/340/473 +f 333/334/474 324/326/474 339/340/474 +f 326/335/475 333/334/475 339/340/475 +f 320/330/476 319/320/476 340/341/476 +f 319/320/449 334/336/449 340/341/449 +f 334/336/477 320/330/477 340/341/477 +f 323/325/478 327/328/478 341/342/478 +f 335/337/479 323/325/479 341/342/479 +f 327/328/480 335/337/480 341/342/480 +f 315/321/450 321/322/450 342/343/450 +f 329/329/481 315/321/481 342/343/481 +f 321/322/452 329/329/452 342/343/452 +f 317/318/449 323/325/449 343/344/449 +f 326/335/482 317/318/482 343/344/482 +f 323/325/483 335/337/483 343/344/483 +f 335/337/484 326/335/484 343/344/484 +f 318/323/485 325/327/485 344/317/485 +f 325/327/486 328/315/486 344/317/486 +f 337/316/487 318/323/487 344/317/487 +o Bowl_hull_10 +v 0.082330 -0.012501 0.050235 +v 0.040088 0.000431 -0.025211 +v 0.040519 0.000431 -0.025211 +v 0.079743 0.000431 0.050235 +v 0.040949 -0.012501 -0.013993 +v 0.041379 -0.012501 -0.020898 +v 0.082760 0.000431 0.048507 +v 0.040088 0.000431 -0.018742 +v 0.078021 -0.012501 0.049371 +v 0.081899 -0.008621 0.047642 +v 0.042240 -0.004312 -0.022190 +v 0.078452 0.000431 0.048507 +v 0.080173 -0.012501 0.045486 +v 0.040519 -0.007759 -0.024339 +v 0.040088 -0.012501 -0.022190 +v 0.083191 -0.004312 0.049371 +v 0.040949 -0.000434 -0.024775 +v 0.040519 -0.011638 -0.014857 +v 0.083191 0.000431 0.050235 +v 0.076726 -0.012069 0.047214 +v 0.056900 -0.012501 0.005400 +v 0.040088 -0.012501 -0.015721 +v 0.078882 -0.012501 0.050235 +v 0.040949 -0.012069 -0.013993 +v 0.057761 0.000431 0.012298 +v 0.077591 -0.003020 0.039453 +v 0.043536 -0.006035 -0.019598 +v 0.082330 -0.012501 0.049371 +v 0.053879 -0.003882 -0.001933 +vt 0.005775 0.019973 +vt 0.857087 0.870080 +vt 0.308536 0.319953 +vt 0.000000 0.009986 +vt 0.000000 0.000000 +vt 1.000000 0.920012 +vt 1.000000 0.980027 +vt 0.148688 0.019973 +vt 0.057165 0.029959 +vt 0.977095 0.990014 +vt 0.085748 0.000000 +vt 0.988547 0.880067 +vt 0.977095 0.890053 +vt 0.937060 0.929998 +vt 0.011551 0.009986 +vt 0.040035 0.000000 +vt 0.040035 0.049931 +vt 1.000000 1.000000 +vt 0.988547 1.000000 +vt 0.959965 0.850010 +vt 0.405736 0.390053 +vt 0.125783 0.000000 +vt 0.137236 0.009986 +vt 1.000000 0.900039 +vt 0.148688 0.019973 +vt 0.497161 0.410026 +vt 0.965642 0.970041 +vt 0.074393 0.079988 +vt 0.988547 0.980027 +vn 0.8675 -0.0348 -0.4963 +vn 0.0000 1.0000 0.0000 +vn -0.0000 -1.0000 -0.0000 +vn -0.7993 0.0665 0.5973 +vn 0.0000 -0.1058 -0.9944 +vn -1.0000 0.0000 0.0000 +vn -0.9205 -0.0889 -0.3804 +vn 0.6603 -0.3589 -0.6597 +vn 0.8537 0.1785 -0.4892 +vn 0.8374 -0.0813 -0.5404 +vn 0.6219 -0.0829 -0.7787 +vn 0.0000 -0.0000 1.0000 +vn 0.9374 -0.0624 0.3426 +vn 0.9694 0.0440 -0.2415 +vn -0.8612 -0.0675 0.5038 +vn -0.8498 0.0632 0.5232 +vn 0.8538 -0.1592 -0.4957 +vn 0.8424 -0.2079 -0.4972 +vn -0.9237 0.0871 0.3731 +vn -0.8951 0.0000 0.4459 +vn -0.7076 0.0471 0.7050 +vn -0.8633 0.0000 0.5046 +vn -0.8614 0.0669 0.5035 +vn 0.0001 1.0000 -0.0001 +vn -0.8619 0.1272 0.4908 +vn -0.8616 0.1233 0.4923 +vn -0.8618 0.1249 0.4917 +vn 0.8701 -0.0108 -0.4927 +vn 0.8686 -0.0009 -0.4956 +vn 0.8628 -0.0975 -0.4960 +vn 0.8617 -0.1078 -0.4958 +vn 0.8564 -0.1138 -0.5036 +vn 0.8575 -0.1361 -0.4962 +vn 0.8682 -0.1183 -0.4819 +vn 0.9945 -0.1045 0.0000 +vn 0.8957 -0.0942 -0.4345 +vn 0.8656 -0.0692 -0.4959 +vn 0.8664 -0.0609 -0.4955 +vn 0.8667 -0.0427 -0.4970 +vn 0.8671 -0.0478 -0.4958 +usemtl None +s off +f 361/345/488 370/346/488 373/347/488 +f 347/348/489 346/349/489 348/350/489 +f 345/351/490 349/352/490 350/353/490 +f 347/348/489 348/350/489 351/354/489 +f 348/350/489 346/349/489 352/355/489 +f 349/352/490 345/351/490 353/356/490 +f 348/350/489 352/355/489 356/357/489 +f 353/356/491 348/350/491 356/357/491 +f 345/351/490 350/353/490 357/358/490 +f 346/349/492 347/348/492 358/359/492 +f 350/353/490 349/352/490 359/360/490 +f 352/355/493 346/349/493 359/360/493 +f 346/349/494 358/359/494 359/360/494 +f 358/359/495 350/353/495 359/360/495 +f 347/348/496 351/354/496 361/345/496 +f 355/361/497 358/359/497 361/345/497 +f 358/359/498 347/348/498 361/345/498 +f 348/350/499 345/351/499 363/362/499 +f 351/354/489 348/350/489 363/362/489 +f 345/351/500 360/363/500 363/362/500 +f 360/363/501 351/354/501 363/362/501 +f 349/352/502 353/356/502 364/364/502 +f 353/356/503 356/357/503 364/364/503 +f 357/358/490 350/353/490 365/365/490 +f 358/359/504 357/358/504 365/365/504 +f 350/353/505 358/359/505 365/365/505 +f 359/360/490 349/352/490 366/366/490 +f 352/355/493 359/360/493 366/366/493 +f 362/367/506 352/355/506 366/366/506 +f 349/352/507 362/367/507 366/366/507 +f 345/351/499 348/350/499 367/368/499 +f 353/356/490 345/351/490 367/368/490 +f 348/350/508 353/356/508 367/368/508 +f 362/367/507 349/352/507 368/369/507 +f 349/352/509 364/364/509 368/369/509 +f 364/364/510 356/357/510 368/369/510 +f 356/357/511 352/355/511 369/370/511 +f 352/355/512 362/367/512 369/370/512 +f 368/369/513 356/357/513 369/370/513 +f 362/367/514 368/369/514 369/370/514 +f 351/354/515 360/363/515 370/346/515 +f 361/345/516 351/354/516 370/346/516 +f 355/361/517 354/371/517 371/372/517 +f 354/371/518 357/358/518 371/372/518 +f 358/359/519 355/361/519 371/372/519 +f 357/358/520 358/359/520 371/372/520 +f 345/351/490 357/358/490 372/373/490 +f 357/358/521 354/371/521 372/373/521 +f 360/363/522 345/351/522 372/373/522 +f 354/371/523 360/363/523 372/373/523 +f 354/371/524 355/361/524 373/347/524 +f 360/363/525 354/371/525 373/347/525 +f 355/361/526 361/345/526 373/347/526 +f 370/346/527 360/363/527 373/347/527 +o Bowl_hull_11 +v -0.015099 0.032335 -0.048921 +v 0.005163 0.032335 -0.033404 +v 0.005163 0.032335 -0.050214 +v 0.002145 0.037076 -0.035128 +v -0.024153 0.028023 -0.033404 +v -0.016390 0.028023 -0.050214 +v -0.009495 0.036214 -0.033404 +v -0.002599 0.035351 -0.050214 +v -0.016390 0.028023 -0.033404 +v 0.005163 0.035351 -0.048058 +v -0.021134 0.028454 -0.050214 +v -0.018979 0.032335 -0.033835 +v 0.005163 0.036644 -0.033404 +v -0.009925 0.034057 -0.050214 +v -0.004754 0.037076 -0.033835 +v -0.014666 0.034489 -0.033835 +v -0.022858 0.029748 -0.033404 +v 0.002575 0.035351 -0.050214 +v -0.018115 0.030609 -0.050214 +v -0.006479 0.034920 -0.049783 +v -0.021134 0.028023 -0.050214 +v 0.004730 0.037076 -0.033404 +v -0.011650 0.033626 -0.049783 +v -0.024153 0.028454 -0.034697 +v -0.020270 0.029317 -0.049783 +v 0.005163 0.034920 -0.050214 +v -0.000011 0.037076 -0.035559 +v -0.009495 0.036214 -0.033835 +vt 0.426488 0.025646 +vt 0.323610 0.974354 +vt 0.500000 0.974354 +vt 1.000000 0.000000 +vt 1.000000 1.000000 +vt 0.264781 0.000000 +vt 0.000000 1.000000 +vt 0.500000 1.000000 +vt 0.735219 0.000000 +vt 0.264781 1.000000 +vt 1.000000 0.128230 +vt 0.102976 0.000000 +vt 1.000000 1.000000 +vt 0.485317 0.000000 +vt 0.308829 0.076938 +vt 0.176488 0.974354 +vt 0.044146 1.000000 +vt 0.911707 0.000000 +vt 0.205951 0.000000 +vt 0.602878 0.025646 +vt 0.661707 0.974354 +vt 0.102976 0.000000 +vt 0.985219 1.000000 +vt 0.897024 0.897416 +vt 0.000000 0.923062 +vt 0.132439 0.025646 +vt 1.000000 0.000000 +vt 0.823512 0.871770 +vn -0.3144 0.9428 -0.1105 +vn 0.1962 -0.9806 -0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 -0.0000 +vn 1.0000 -0.0000 0.0000 +vn -0.4439 0.8888 -0.1142 +vn -0.2664 0.5334 0.8028 +vn -0.2285 0.4722 0.8514 +vn -0.4549 0.8828 -0.1170 +vn -0.1504 0.8514 -0.5026 +vn -0.1227 0.9852 -0.1199 +vn 0.7043 0.7071 -0.0624 +vn 0.0000 1.0000 0.0000 +vn -0.0363 0.5995 0.7995 +vn 0.0742 0.9910 -0.1112 +vn 0.0946 0.9890 -0.1136 +vn -0.3743 0.9194 -0.1206 +vn -0.3945 0.8822 -0.2570 +vn -0.3281 0.7794 -0.5338 +vn -0.7844 0.5884 0.1963 +vn -0.8698 -0.4681 -0.1562 +vn -0.9816 0.0000 -0.1910 +vn -0.5598 0.8213 -0.1101 +vn -0.5278 0.8414 -0.1165 +vn -0.5268 0.7379 -0.4219 +vn -0.6388 0.7598 -0.1209 +vn -0.6677 0.7330 -0.1299 +vn 0.1610 0.9678 -0.1934 +vn -0.0399 0.9931 -0.1099 +vn 0.0000 0.9931 -0.1169 +vn 0.0226 0.9933 -0.1130 +vn -0.1790 0.9839 0.0000 +vn -0.3164 0.9486 0.0000 +vn -0.2269 0.9663 -0.1213 +vn -0.1778 0.9776 -0.1129 +vn -0.2684 0.9559 -0.1188 +usemtl None +s off +f 396/374/528 389/375/528 401/376/528 +f 376/377/529 375/378/529 379/379/529 +f 378/380/530 375/378/530 380/381/530 +f 376/377/531 379/379/531 381/382/531 +f 375/378/530 378/380/530 382/383/530 +f 379/379/529 375/378/529 382/383/529 +f 378/380/532 379/379/532 382/383/532 +f 375/378/533 376/377/533 383/384/533 +f 381/382/531 379/379/531 384/385/531 +f 380/381/530 375/378/530 386/386/530 +f 375/378/533 383/384/533 386/386/533 +f 381/382/531 384/385/531 387/387/531 +f 374/388/534 385/389/534 389/375/534 +f 378/380/530 380/381/530 390/390/530 +f 389/375/535 385/389/535 390/390/535 +f 380/381/536 389/375/536 390/390/536 +f 376/377/531 381/382/531 391/391/531 +f 385/389/537 374/388/537 392/392/537 +f 387/387/531 384/385/531 392/392/531 +f 381/382/538 387/387/538 393/393/538 +f 388/394/539 381/382/539 393/393/539 +f 379/379/532 378/380/532 394/395/532 +f 384/385/531 379/379/531 394/395/531 +f 380/381/530 386/386/530 395/396/530 +f 386/386/540 383/384/540 395/396/540 +f 377/397/541 388/394/541 395/396/541 +f 388/394/542 380/381/542 395/396/542 +f 391/391/543 377/397/543 395/396/543 +f 383/384/544 391/391/544 395/396/544 +f 374/388/545 389/375/545 396/374/545 +f 392/392/546 374/388/546 396/374/546 +f 387/387/547 392/392/547 396/374/547 +f 378/380/548 390/390/548 397/398/548 +f 394/395/549 378/380/549 397/398/549 +f 384/385/550 394/395/550 397/398/550 +f 390/390/551 385/389/551 398/399/551 +f 385/389/552 392/392/552 398/399/552 +f 392/392/553 384/385/553 398/399/553 +f 397/398/554 390/390/554 398/399/554 +f 384/385/555 397/398/555 398/399/555 +f 383/384/533 376/377/533 399/400/533 +f 376/377/531 391/391/531 399/400/531 +f 391/391/556 383/384/556 399/400/556 +f 388/394/541 377/397/541 400/401/541 +f 381/382/557 388/394/557 400/401/557 +f 391/391/558 381/382/558 400/401/558 +f 377/397/559 391/391/559 400/401/559 +f 380/381/560 388/394/560 401/376/560 +f 389/375/561 380/381/561 401/376/561 +f 393/393/562 387/387/562 401/376/562 +f 388/394/563 393/393/563 401/376/563 +f 387/387/564 396/374/564 401/376/564 +o Bowl_hull_12 +v -0.034927 0.013366 -0.034266 +v -0.024585 0.028023 -0.035128 +v -0.024585 0.028023 -0.033404 +v -0.017255 0.027590 -0.033404 +v -0.030619 0.011211 -0.050214 +v -0.022428 0.027590 -0.050214 +v -0.030619 0.011211 -0.033404 +v -0.017255 0.027590 -0.050214 +v -0.030619 0.018109 -0.050214 +v -0.029754 0.022847 -0.033404 +v -0.033635 0.011211 -0.049352 +v -0.035362 0.011211 -0.033404 +v -0.025879 0.024572 -0.049352 +v -0.017255 0.028023 -0.050214 +v -0.032341 0.018972 -0.033835 +v -0.032772 0.013798 -0.050214 +v -0.017255 0.028023 -0.033404 +v -0.027598 0.025434 -0.033835 +v -0.028031 0.021985 -0.049783 +v -0.021998 0.028023 -0.049783 +v -0.025449 0.027590 -0.033835 +v -0.033635 0.016385 -0.034266 +vt 0.143011 0.846124 +vt 0.023982 0.871770 +vt 0.095341 0.692248 +vt 1.000000 0.025744 +vt 0.595145 0.000000 +vt 0.261942 1.000000 +vt 0.261942 1.000000 +vt 1.000000 0.025744 +vt 0.714272 0.025744 +vt 0.261942 0.589663 +vt 0.309710 0.307850 +vt 0.095341 1.000000 +vt 0.000000 1.000000 +vt 0.595145 0.000000 +vt 1.000000 0.000000 +vt 0.166797 0.538371 +vt 1.000000 0.000000 +vt 0.428739 0.153974 +vt 0.523688 0.205266 +vt 0.404855 0.359142 +vt 0.738058 0.000000 +vt 0.547475 0.025744 +vn -0.9134 0.3910 -0.1129 +vn 0.0000 -0.0000 1.0000 +vn 0.7748 -0.6322 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.9821 0.1553 -0.1063 +vn -0.0000 1.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn -0.8201 0.5604 -0.1158 +vn -0.8239 0.3456 0.4491 +vn -0.4987 0.2403 0.8328 +vn -0.9530 0.2776 -0.1213 +vn -0.2679 -0.2230 -0.9373 +vn -0.7534 0.6466 -0.1194 +vn -0.4538 0.3920 -0.8003 +vn -0.6495 0.6148 -0.4475 +vn -0.7726 0.6246 -0.1141 +vn -0.0614 0.7344 -0.6759 +vn -0.4482 0.8939 0.0000 +vn -0.5777 0.5769 0.5775 +vn -0.6706 0.7314 -0.1237 +vn -0.5807 0.5792 0.5721 +vn -0.7032 0.7013 -0.1169 +vn -0.5606 0.8222 -0.0990 +vn -0.6424 0.7572 -0.1184 +vn -0.8543 0.3657 0.3693 +vn -0.8803 0.4598 -0.1168 +vn -0.8882 0.4436 -0.1200 +usemtl None +s off +f 417/402/565 402/403/565 423/404/565 +f 405/405/566 404/406/566 408/407/566 +f 406/408/567 405/405/567 408/407/567 +f 405/405/567 406/408/567 409/409/567 +f 406/408/568 407/410/568 409/409/568 +f 407/410/568 406/408/568 410/411/568 +f 408/407/566 404/406/566 411/412/566 +f 406/408/569 408/407/569 412/413/569 +f 408/407/566 411/412/566 413/414/566 +f 402/403/570 412/413/570 413/414/570 +f 412/413/569 408/407/569 413/414/569 +f 403/415/571 404/406/571 415/416/571 +f 405/405/572 409/409/572 415/416/572 +f 409/409/568 407/410/568 415/416/568 +f 411/412/573 410/411/573 416/417/573 +f 402/403/574 413/414/574 416/417/574 +f 413/414/575 411/412/575 416/417/575 +f 410/411/568 406/408/568 417/402/568 +f 412/413/576 402/403/576 417/402/576 +f 406/408/577 412/413/577 417/402/577 +f 404/406/566 405/405/566 418/418/566 +f 415/416/571 404/406/571 418/418/571 +f 405/405/572 415/416/572 418/418/572 +f 419/419/578 414/420/578 420/421/578 +f 407/410/579 410/411/579 420/421/579 +f 410/411/573 411/412/573 420/421/573 +f 414/420/580 407/410/580 420/421/580 +f 411/412/581 419/419/581 420/421/581 +f 403/415/571 415/416/571 421/422/571 +f 415/416/582 407/410/582 421/422/582 +f 404/406/583 403/415/583 422/423/583 +f 411/412/584 404/406/584 422/423/584 +f 407/410/585 414/420/585 422/423/585 +f 419/419/586 411/412/586 422/423/586 +f 414/420/587 419/419/587 422/423/587 +f 403/415/588 421/422/588 422/423/588 +f 421/422/589 407/410/589 422/423/589 +f 402/403/590 416/417/590 423/404/590 +f 416/417/591 410/411/591 423/404/591 +f 410/411/592 417/402/592 423/404/592 +o Bowl_hull_13 +v -0.034930 -0.007758 -0.047627 +v -0.033637 0.011205 -0.050214 +v -0.030620 0.011205 -0.050214 +v -0.035361 0.011205 -0.033404 +v -0.030620 -0.011640 -0.033404 +v -0.037085 -0.004739 -0.033404 +v -0.030620 -0.011640 -0.050214 +v -0.030620 0.011205 -0.033404 +v -0.035361 -0.011640 -0.033404 +v -0.035361 0.002154 -0.050214 +v -0.037085 0.004739 -0.033835 +v -0.030189 0.002583 -0.033404 +v -0.033637 -0.011206 -0.050214 +v -0.030189 -0.002585 -0.050214 +v -0.035361 -0.002153 -0.050214 +v -0.034930 0.006895 -0.049352 +v -0.036223 0.009480 -0.033835 +v -0.036223 -0.009482 -0.033835 +v -0.030189 -0.002585 -0.033404 +v -0.030189 0.002583 -0.050214 +v -0.037085 -0.002153 -0.035128 +v -0.033637 -0.011640 -0.049352 +v -0.034930 -0.006895 -0.049352 +vt 0.981008 0.000000 +vt 1.000000 0.051292 +vt 0.792266 0.051292 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 0.697895 1.000000 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 0.396182 0.000000 +vt 0.283015 0.974354 +vt 0.377386 1.000000 +vt 0.603622 0.000000 +vt 0.584728 0.000000 +vt 0.188644 0.051292 +vt 0.075477 0.974354 +vt 0.905531 0.974354 +vt 0.603622 1.000000 +vt 0.377386 0.000000 +vt 0.584728 0.897416 +vt 0.830054 0.153876 +vn -0.9565 -0.2606 -0.1311 +vn 0.0000 1.0000 -0.0000 +vn 0.0000 -0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.3873 0.0419 0.9210 +vn 0.9988 0.0500 0.0000 +vn 0.9989 -0.0476 0.0000 +vn -0.8652 0.1648 -0.4735 +vn -0.9863 0.1118 -0.1215 +vn -0.9778 0.1778 -0.1111 +vn -0.8815 0.4634 -0.0904 +vn -0.6140 0.1117 0.7813 +vn -0.9570 0.2624 -0.1235 +vn -0.7848 -0.1961 0.5879 +vn 1.0000 0.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.9940 0.0202 -0.1078 +vn -0.9907 -0.0755 -0.1132 +vn -0.9935 0.0000 -0.1136 +vn -0.1274 -0.8860 -0.4458 +vn -0.9567 -0.2641 -0.1227 +vn -0.9171 -0.3862 -0.0992 +vn -0.9867 -0.1113 -0.1183 +vn -0.8653 -0.1648 -0.4733 +vn -0.9632 -0.2405 -0.1204 +vn -0.9796 -0.1681 -0.1097 +vn -0.9566 -0.2606 -0.1305 +usemtl None +s off +f 436/424/593 445/425/593 446/426/593 +f 426/427/594 425/428/594 427/429/594 +f 428/430/595 427/429/595 429/431/595 +f 425/428/596 426/427/596 430/432/596 +f 426/427/594 427/429/594 431/433/594 +f 427/429/595 428/430/595 431/433/595 +f 428/430/595 429/431/595 432/434/595 +f 430/432/597 428/430/597 432/434/597 +f 425/428/596 430/432/596 433/435/596 +f 429/431/598 427/429/598 434/436/598 +f 426/427/599 431/433/599 435/437/599 +f 431/433/595 428/430/595 435/437/595 +f 433/435/596 430/432/596 436/424/596 +f 430/432/596 426/427/596 437/438/596 +f 428/430/600 430/432/600 437/438/600 +f 433/435/596 436/424/596 438/439/596 +f 425/428/601 433/435/601 439/440/601 +f 433/435/602 434/436/602 439/440/602 +f 439/440/603 434/436/603 440/441/603 +f 427/429/604 425/428/604 440/441/604 +f 434/436/605 427/429/605 440/441/605 +f 425/428/606 439/440/606 440/441/606 +f 432/434/607 429/431/607 441/442/607 +f 435/437/595 428/430/595 442/443/595 +f 428/430/600 437/438/600 442/443/600 +f 437/438/608 435/437/608 442/443/608 +f 426/427/599 435/437/599 443/444/599 +f 437/438/596 426/427/596 443/444/596 +f 435/437/608 437/438/608 443/444/608 +f 429/431/609 434/436/609 444/445/609 +f 434/436/610 433/435/610 444/445/610 +f 438/439/611 429/431/611 444/445/611 +f 433/435/612 438/439/612 444/445/612 +f 430/432/597 432/434/597 445/425/597 +f 436/424/613 430/432/613 445/425/613 +f 441/442/614 424/446/614 445/425/614 +f 432/434/615 441/442/615 445/425/615 +f 429/431/616 438/439/616 446/426/616 +f 438/439/617 436/424/617 446/426/617 +f 424/446/618 441/442/618 446/426/618 +f 441/442/619 429/431/619 446/426/619 +f 445/425/620 424/446/620 446/426/620 +o Bowl_hull_14 +v 0.065950 -0.047426 0.045491 +v 0.040084 -0.043974 0.008851 +v 0.040515 -0.043974 0.008851 +v 0.040084 -0.072859 0.049372 +v 0.065950 -0.043974 0.050231 +v 0.040084 -0.068112 0.049801 +v 0.040084 -0.044407 0.016180 +v 0.056896 -0.061216 0.049801 +v 0.070693 -0.043974 0.049801 +v 0.040515 -0.046994 0.011866 +v 0.047413 -0.068112 0.048509 +v 0.049138 -0.044407 0.019198 +v 0.063364 -0.054322 0.049368 +v 0.047844 -0.068547 0.050235 +v 0.040515 -0.058201 0.027386 +v 0.051727 -0.065527 0.049372 +v 0.058621 -0.059061 0.048938 +v 0.067242 -0.049581 0.050231 +v 0.040084 -0.068547 0.050235 +v 0.057758 -0.044407 0.030833 +v 0.040084 -0.043974 0.015317 +v 0.042241 -0.070269 0.046779 +v 0.044395 -0.044407 0.013162 +v 0.054313 -0.060786 0.045920 +v 0.069830 -0.045702 0.049368 +v 0.040084 -0.072859 0.050235 +v 0.054313 -0.043977 0.026097 +v 0.040084 -0.051738 0.018335 +v 0.041810 -0.053890 0.022646 +v 0.040515 -0.072859 0.049372 +v 0.060344 -0.057769 0.050235 +v 0.065087 -0.044407 0.041180 +v 0.066813 -0.050010 0.049368 +v 0.058621 -0.057339 0.046783 +v 0.070693 -0.044407 0.050231 +v 0.041810 -0.044836 0.010573 +vt 0.895742 0.464859 +vt 0.072834 0.014096 +vt 0.041605 0.056382 +vt 0.000000 0.014096 +vt 0.000000 0.000000 +vt 0.999902 0.845047 +vt 0.979148 0.000000 +vt 0.989525 0.000000 +vt 0.177092 0.000000 +vt 0.989525 1.000000 +vt 0.989525 0.549237 +vt 1.000000 0.253524 +vt 0.979148 0.380384 +vt 0.958297 0.239428 +vt 0.979050 0.760572 +vt 0.968673 0.605619 +vt 1.000000 0.000000 +vt 0.250024 0.295811 +vt 0.531180 0.577428 +vt 0.156241 0.000000 +vt 0.447871 0.014096 +vt 0.916495 0.070478 +vt 1.000000 0.000000 +vt 0.416740 0.464859 +vt 0.104161 0.140857 +vt 0.229173 0.000000 +vt 0.333333 0.056382 +vt 0.979148 0.014096 +vt 1.000000 0.661903 +vt 0.999902 0.887236 +vt 0.885365 0.845047 +vt 0.781204 0.816856 +vt 0.979050 0.971809 +vt 0.979050 0.873238 +vt 0.916593 0.605619 +vt 0.999902 1.000000 +vn 0.5802 -0.6456 -0.4965 +vn 0.0000 1.0000 0.0000 +vn -1.0000 -0.0000 0.0000 +vn -0.6112 0.6469 0.4561 +vn 0.0000 -0.7065 -0.7078 +vn 0.6271 -0.7659 0.1420 +vn 0.5328 -0.7793 -0.3298 +vn 0.6909 -0.6660 -0.2812 +vn -0.5567 0.5861 0.5887 +vn 0.6711 -0.5499 -0.4972 +vn -0.5176 0.7649 0.3835 +vn 0.4704 -0.7299 -0.4960 +vn 0.5895 -0.6602 -0.4654 +vn 0.5583 -0.6653 -0.4957 +vn 0.5902 -0.6593 -0.4658 +vn 0.0000 0.0000 1.0000 +vn 0.0026 1.0000 -0.0019 +vn 0.7980 -0.1170 -0.5912 +vn 0.6157 0.6151 -0.4925 +vn 0.7167 0.4112 -0.5632 +vn -0.7036 -0.5498 -0.4501 +vn -0.5039 -0.7141 -0.4859 +vn 0.1346 -0.8033 -0.5801 +vn 0.4864 -0.7083 -0.5115 +vn 0.5141 -0.6997 -0.4961 +vn 0.5171 -0.6978 -0.4957 +vn 0.5479 -0.6733 -0.4965 +vn 0.5074 -0.7969 -0.3279 +vn 0.0000 -0.8320 -0.5547 +vn 0.4678 -0.7613 -0.4491 +vn 0.3835 -0.7684 -0.5123 +vn 0.0000 -1.0000 0.0000 +vn 0.4720 -0.8494 0.2360 +vn 0.7021 -0.6734 -0.2313 +vn 0.5033 -0.5838 0.6371 +vn 0.7608 -0.6408 0.1028 +vn -0.0002 0.0004 1.0000 +vn 0.7022 -0.5094 -0.4974 +vn 0.7135 -0.4987 -0.4922 +vn 0.8119 -0.2766 -0.5141 +vn 0.6834 0.5567 -0.4723 +vn 0.8041 0.1706 -0.5695 +vn 0.7787 -0.6228 -0.0764 +vn 0.7008 -0.5117 -0.4971 +vn 0.6784 -0.5426 -0.4954 +vn 0.7133 -0.4995 -0.4917 +vn 0.8132 -0.5694 -0.1202 +vn 0.6421 -0.5853 -0.4951 +vn 0.6419 -0.5991 -0.4786 +vn 0.6317 -0.5955 -0.4963 +vn 0.6076 -0.6205 -0.4958 +vn 0.0641 0.7031 0.7082 +vn 0.8703 -0.3470 -0.3496 +vn 0.8319 -0.5549 0.0009 +vn 0.0000 0.0003 1.0000 +vn 0.0028 -0.0019 1.0000 +vn 0.4259 -0.6392 -0.6403 +vn 0.7043 -0.2609 -0.6602 +vn 0.6006 -0.6273 -0.4958 +vn 0.5990 -0.6289 -0.4957 +usemtl None +s off +f 470/447/621 456/448/621 482/449/621 +f 449/450/622 448/451/622 451/452/622 +f 448/451/623 450/453/623 452/454/623 +f 448/451/623 452/454/623 453/455/623 +f 452/454/624 451/452/624 453/455/624 +f 449/450/622 451/452/622 455/456/622 +f 448/451/625 449/450/625 456/448/625 +f 454/457/626 460/458/626 462/459/626 +f 460/458/627 457/460/627 462/459/627 +f 459/461/628 454/457/628 463/462/628 +f 451/452/629 452/454/629 465/463/629 +f 452/454/623 450/453/623 465/463/623 +f 459/461/630 458/464/630 466/465/630 +f 451/452/622 448/451/622 467/466/622 +f 448/451/623 453/455/623 467/466/623 +f 453/455/631 451/452/631 467/466/631 +f 461/467/632 457/460/632 468/468/632 +f 454/457/633 462/459/633 470/447/633 +f 462/459/634 456/448/634 470/447/634 +f 463/462/635 454/457/635 470/447/635 +f 465/463/623 450/453/623 472/469/623 +f 460/458/636 465/463/636 472/469/636 +f 449/450/637 455/456/637 473/470/637 +f 466/465/638 458/464/638 473/470/638 +f 469/471/639 449/450/639 473/470/639 +f 458/464/640 469/471/640 473/470/640 +f 450/453/623 448/451/623 474/472/623 +f 448/451/641 456/448/641 474/472/641 +f 461/467/642 450/453/642 474/472/642 +f 456/448/643 461/467/643 474/472/643 +f 461/467/644 456/448/644 475/473/644 +f 457/460/645 461/467/645 475/473/645 +f 462/459/646 457/460/646 475/473/646 +f 456/448/647 462/459/647 475/473/647 +f 457/460/648 460/458/648 476/474/648 +f 450/453/649 461/467/649 476/474/649 +f 468/468/650 457/460/650 476/474/650 +f 461/467/651 468/468/651 476/474/651 +f 472/469/652 450/453/652 476/474/652 +f 460/458/653 472/469/653 476/474/653 +f 454/457/654 459/461/654 477/475/654 +f 460/458/655 454/457/655 477/475/655 +f 459/461/656 464/476/656 477/475/656 +f 451/452/657 465/463/657 477/475/657 +f 465/463/636 460/458/636 477/475/636 +f 447/477/658 466/465/658 478/478/658 +f 471/479/659 447/477/659 478/478/659 +f 455/456/660 471/479/660 478/478/660 +f 473/470/661 455/456/661 478/478/661 +f 466/465/662 473/470/662 478/478/662 +f 464/476/663 459/461/663 479/480/663 +f 466/465/664 447/477/664 479/480/664 +f 459/461/665 466/465/665 479/480/665 +f 447/477/666 471/479/666 479/480/666 +f 471/479/667 464/476/667 479/480/667 +f 458/464/668 459/461/668 480/481/668 +f 459/461/669 463/462/669 480/481/669 +f 469/471/670 458/464/670 480/481/670 +f 463/462/671 469/471/671 480/481/671 +f 455/456/672 451/452/672 481/482/672 +f 471/479/673 455/456/673 481/482/673 +f 464/476/674 471/479/674 481/482/674 +f 451/452/675 477/475/675 481/482/675 +f 477/475/676 464/476/676 481/482/676 +f 456/448/677 449/450/677 482/449/677 +f 449/450/678 469/471/678 482/449/678 +f 469/471/679 463/462/679 482/449/679 +f 463/462/680 470/447/680 482/449/680 +o Bowl_hull_15 +v 0.012061 -0.035350 -0.034266 +v 0.024133 -0.028455 -0.033404 +v 0.024133 -0.028455 -0.035128 +v 0.005163 -0.032333 -0.033404 +v 0.023700 -0.022419 -0.050214 +v 0.006027 -0.034918 -0.050214 +v 0.023700 -0.022419 -0.033404 +v 0.018096 -0.030608 -0.050214 +v 0.005163 -0.032333 -0.050214 +v 0.005163 -0.036644 -0.033404 +v 0.024133 -0.026300 -0.049352 +v 0.018956 -0.032333 -0.033404 +v 0.013786 -0.032763 -0.050214 +v 0.024133 -0.022419 -0.033404 +v 0.009475 -0.036212 -0.033835 +v 0.005163 -0.034918 -0.050214 +v 0.014648 -0.034488 -0.033835 +v 0.021113 -0.028885 -0.048489 +v 0.011633 -0.033625 -0.049783 +v 0.024133 -0.022419 -0.050214 +v 0.021544 -0.030608 -0.034266 +v 0.005596 -0.036644 -0.035559 +v 0.024133 -0.025868 -0.050214 +v 0.008615 -0.034488 -0.049783 +v 0.015079 -0.032333 -0.049352 +vt 0.500000 0.974354 +vt 0.454581 0.000000 +vt 0.522709 0.051292 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 0.977193 1.000000 +vt 0.977193 0.000000 +vt 0.045517 0.000000 +vt 0.681774 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 0.897416 +vt 1.000000 0.051292 +vt 0.727095 1.000000 +vt 1.000000 1.000000 +vt 0.227291 0.974354 +vt 0.000000 0.000000 +vt 0.363645 0.948708 +vt 0.840838 0.102584 +vt 0.341034 0.025646 +vt 1.000000 0.000000 +vt 0.863547 0.948708 +vt 0.022807 0.871770 +vt 1.000000 0.000000 +vt 0.181969 0.025646 +vn 0.3829 -0.9164 -0.1167 +vn 0.0000 -0.0000 1.0000 +vn -0.4716 0.8818 0.0000 +vn 0.0000 0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.1319 -0.4222 0.8969 +vn 0.3161 -0.9487 0.0000 +vn 0.1687 -0.5064 0.8456 +vn 0.6266 -0.7706 -0.1168 +vn 0.5855 -0.7691 -0.2563 +vn 0.2970 -0.9481 -0.1136 +vn 0.3310 -0.9368 -0.1133 +vn 0.3488 -0.9299 -0.1163 +vn 0.6394 -0.7689 0.0000 +vn 0.5880 -0.7851 0.1946 +vn 0.5246 -0.8438 -0.1134 +vn 0.6127 -0.7821 -0.1133 +vn 0.5420 -0.8322 -0.1172 +vn 0.1585 -0.9811 -0.1108 +vn 0.1016 -0.9946 0.0204 +vn 0.0000 -0.9931 -0.1169 +vn -0.4534 -0.8867 -0.0910 +vn 0.5746 -0.7318 -0.3664 +vn 0.2249 -0.8096 -0.5422 +vn 0.1815 -0.9766 -0.1153 +vn 0.2412 -0.8432 -0.4804 +vn 0.2731 -0.9547 -0.1179 +vn 0.4684 -0.8762 -0.1139 +vn 0.4365 -0.8727 -0.2187 +vn 0.4535 -0.8844 -0.1103 +usemtl None +s off +f 499/483/681 495/484/681 507/485/681 +f 486/486/682 484/487/682 489/488/682 +f 487/489/683 486/486/683 489/488/683 +f 488/490/684 487/489/684 490/491/684 +f 486/486/683 487/489/683 491/492/683 +f 487/489/684 488/490/684 491/492/684 +f 484/487/682 486/486/682 492/493/682 +f 486/486/685 491/492/685 492/493/685 +f 484/487/686 485/494/686 493/495/686 +f 484/487/682 492/493/682 494/496/682 +f 488/490/684 490/491/684 495/484/684 +f 489/488/682 484/487/682 496/497/682 +f 487/489/687 489/488/687 496/497/687 +f 484/487/686 493/495/686 496/497/686 +f 494/496/688 492/493/688 497/498/688 +f 491/492/684 488/490/684 498/499/684 +f 492/493/685 491/492/685 498/499/685 +f 497/498/689 483/500/689 499/483/689 +f 494/496/690 497/498/690 499/483/690 +f 493/495/691 485/494/691 500/501/691 +f 490/491/692 493/495/692 500/501/692 +f 483/500/693 497/498/693 501/502/693 +f 499/483/694 483/500/694 501/502/694 +f 495/484/695 499/483/695 501/502/695 +f 490/491/684 487/489/684 502/503/684 +f 487/489/687 496/497/687 502/503/687 +f 496/497/686 493/495/686 502/503/686 +f 485/494/696 484/487/696 503/504/696 +f 484/487/697 494/496/697 503/504/697 +f 494/496/698 490/491/698 503/504/698 +f 500/501/699 485/494/699 503/504/699 +f 490/491/700 500/501/700 503/504/700 +f 488/490/701 497/498/701 504/505/701 +f 497/498/702 492/493/702 504/505/702 +f 498/499/703 488/490/703 504/505/703 +f 492/493/704 498/499/704 504/505/704 +f 493/495/705 490/491/705 505/506/705 +f 490/491/684 502/503/684 505/506/684 +f 502/503/686 493/495/686 505/506/686 +f 488/490/706 495/484/706 506/507/706 +f 497/498/707 488/490/707 506/507/707 +f 495/484/708 501/502/708 506/507/708 +f 501/502/709 497/498/709 506/507/709 +f 490/491/710 494/496/710 507/485/710 +f 495/484/711 490/491/711 507/485/711 +f 494/496/712 499/483/712 507/485/712 +o Bowl_hull_16 +v 0.032323 -0.018968 -0.033404 +v 0.032753 -0.003020 -0.050214 +v 0.034909 -0.003020 -0.050214 +v 0.024133 -0.025434 -0.050214 +v 0.032323 -0.003453 -0.033404 +v 0.024133 -0.021986 -0.033404 +v 0.037065 -0.003020 -0.033404 +v 0.032753 -0.013797 -0.050214 +v 0.024565 -0.028020 -0.033404 +v 0.024133 -0.021986 -0.050214 +v 0.028014 -0.021986 -0.050214 +v 0.036201 -0.009488 -0.033835 +v 0.034909 -0.006901 -0.049352 +v 0.027583 -0.025434 -0.033835 +v 0.032323 -0.003453 -0.050214 +v 0.024565 -0.025864 -0.049352 +v 0.034477 -0.014659 -0.033835 +v 0.031461 -0.016812 -0.049352 +v 0.024133 -0.028020 -0.033404 +v 0.037065 -0.004315 -0.034266 +v 0.034047 -0.010349 -0.049783 +v 0.030599 -0.021552 -0.034266 +v 0.035339 -0.003453 -0.049783 +v 0.032753 -0.003020 -0.033404 +v 0.030170 -0.018968 -0.049783 +v 0.025428 -0.027587 -0.033835 +v 0.025859 -0.024570 -0.049783 +vt 0.896535 0.974354 +vt 0.982674 0.974354 +vt 0.861981 0.025646 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.896535 0.000000 +vt 0.637921 1.000000 +vt 0.017326 1.000000 +vt 0.758614 1.000000 +vt 0.000000 1.000000 +vt 0.431089 0.000000 +vt 1.000000 1.000000 +vt 0.758614 0.000000 +vt 0.758614 0.000000 +vt 0.258712 0.974354 +vt 0.017326 0.000000 +vt 0.465544 0.974354 +vt 0.551684 0.051292 +vt 1.000000 1.000000 +vt 0.913763 0.051292 +vt 0.051782 0.948708 +vt 0.155247 0.051292 +vt 0.293168 0.025646 +vt 0.741288 0.948708 +vt 0.017326 0.025646 +vt 0.000000 1.000000 +vt 0.637921 0.025646 +vn 0.7021 -0.7029 -0.1140 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 1.0000 0.0000 +vn -0.9147 0.4042 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.3745 -0.1113 0.9205 +vn 0.4390 -0.3762 0.8159 +vn -0.7094 0.7049 0.0000 +vn 0.5075 -0.1692 0.8448 +vn 0.8847 -0.4532 -0.1091 +vn 0.9003 -0.4194 -0.1168 +vn -0.5625 -0.8172 -0.1257 +vn 0.0000 -0.9910 -0.1340 +vn 0.9660 -0.1433 0.2151 +vn 0.9788 -0.1725 -0.1103 +vn 0.5771 -0.1154 -0.8085 +vn 0.9667 -0.2269 -0.1183 +vn 0.9346 -0.3362 -0.1161 +vn 0.9429 -0.3144 -0.1104 +vn 0.7850 -0.5884 0.1937 +vn 0.7790 -0.6174 -0.1095 +vn 0.7524 0.6516 -0.0965 +vn 0.9918 0.0708 -0.1064 +vn 0.9836 -0.1374 -0.1170 +vn 0.6398 -0.1199 -0.7592 +vn 0.8819 -0.1653 -0.4415 +vn -0.7093 0.7049 0.0000 +vn 0.6687 -0.3871 -0.6349 +vn 0.8444 -0.4466 -0.2958 +vn 0.8622 -0.4937 -0.1133 +vn 0.8434 -0.5257 -0.1109 +vn 0.8159 -0.5662 -0.1169 +vn 0.5783 -0.5790 0.5748 +vn 0.3957 -0.9101 -0.1230 +vn 0.6825 -0.7213 -0.1180 +vn 0.4332 -0.4876 -0.7580 +vn 0.7532 -0.6474 -0.1165 +vn 0.4767 -0.6671 -0.5725 +usemtl None +s off +f 521/508/713 533/509/713 534/510/713 +f 509/511/714 510/512/714 511/513/714 +f 508/514/715 512/515/715 513/516/715 +f 510/512/716 509/511/716 514/517/716 +f 512/515/715 508/514/715 514/517/715 +f 511/513/714 510/512/714 515/518/714 +f 508/514/715 513/516/715 516/519/715 +f 509/511/714 511/513/714 517/520/714 +f 513/516/717 512/515/717 517/520/717 +f 511/513/718 513/516/718 517/520/718 +f 511/513/714 515/518/714 518/521/714 +f 514/517/719 508/514/719 519/522/719 +f 508/514/720 516/519/720 521/508/720 +f 512/515/721 509/511/721 522/523/721 +f 509/511/714 517/520/714 522/523/714 +f 517/520/717 512/515/717 522/523/717 +f 519/522/722 508/514/722 524/524/722 +f 524/524/723 508/514/723 525/525/723 +f 515/518/724 524/524/724 525/525/724 +f 513/516/718 511/513/718 526/526/718 +f 516/519/715 513/516/715 526/526/715 +f 511/513/725 523/527/725 526/526/725 +f 523/527/726 516/519/726 526/526/726 +f 514/517/727 519/522/727 527/528/727 +f 519/522/728 520/529/728 527/528/728 +f 515/518/729 510/512/729 528/530/729 +f 520/529/730 519/522/730 528/530/730 +f 524/524/731 515/518/731 528/530/731 +f 519/522/732 524/524/732 528/530/732 +f 508/514/733 521/508/733 529/531/733 +f 521/508/734 518/521/734 529/531/734 +f 510/512/735 514/517/735 530/532/735 +f 514/517/736 527/528/736 530/532/736 +f 527/528/737 520/529/737 530/532/737 +f 528/530/738 510/512/738 530/532/738 +f 520/529/739 528/530/739 530/532/739 +f 509/511/740 512/515/740 531/533/740 +f 514/517/716 509/511/716 531/533/716 +f 512/515/715 514/517/715 531/533/715 +f 518/521/741 515/518/741 532/534/741 +f 515/518/742 525/525/742 532/534/742 +f 525/525/743 508/514/743 532/534/743 +f 508/514/744 529/531/744 532/534/744 +f 529/531/745 518/521/745 532/534/745 +f 521/508/746 516/519/746 533/509/746 +f 516/519/747 523/527/747 533/509/747 +f 533/509/748 523/527/748 534/510/748 +f 511/513/749 518/521/749 534/510/749 +f 518/521/750 521/508/750 534/510/750 +f 523/527/751 511/513/751 534/510/751 +o Bowl_hull_17 +v -0.040537 0.051736 0.018334 +v -0.069415 0.046132 0.049371 +v -0.068554 0.046132 0.048076 +v -0.045711 0.069838 0.049371 +v -0.040107 0.068115 0.049801 +v -0.040104 0.045698 0.017904 +v -0.065105 0.045698 0.050235 +v -0.057349 0.060785 0.049801 +v -0.046141 0.046132 0.017470 +v -0.040107 0.072858 0.050235 +v -0.040104 0.045698 0.011003 +v -0.063814 0.053031 0.048507 +v -0.054333 0.063372 0.049371 +v -0.069415 0.045698 0.050235 +v -0.040968 0.072427 0.048941 +v -0.064244 0.045698 0.049371 +v -0.057349 0.046132 0.032124 +v -0.059932 0.055617 0.046352 +v -0.061226 0.056909 0.050235 +v -0.040968 0.046562 0.011867 +v -0.050023 0.066820 0.049371 +v -0.040537 0.059065 0.028680 +v -0.040107 0.068546 0.050235 +v -0.053900 0.056479 0.039885 +v -0.057349 0.045698 0.032124 +v -0.049590 0.067251 0.050235 +v -0.040104 0.059065 0.028680 +v -0.066830 0.049580 0.048937 +v -0.051745 0.047426 0.026095 +vt 0.901038 0.323544 +vt 0.164839 0.794028 +vt 0.384691 0.602839 +vt 0.175901 1.000000 +vt 1.000000 0.147039 +vt 0.000000 1.000000 +vt 0.977976 0.000000 +vt 0.944988 0.029369 +vt 1.000000 0.000000 +vt 1.000000 0.999902 +vt 0.977976 0.808713 +vt 0.967013 0.970534 +vt 0.988939 0.999902 +vt 0.977976 0.176407 +vt 0.955951 0.191092 +vt 0.988939 0.411650 +vt 1.000000 0.279393 +vt 0.186864 0.985218 +vt 0.022024 0.970534 +vt 0.977976 0.514538 +vt 0.977976 0.661576 +vt 0.450568 0.985218 +vt 1.000000 0.999902 +vt 0.736198 0.529320 +vt 0.538371 0.411650 +vt 0.538371 0.411650 +vt 1.000000 0.676358 +vt 0.450568 1.000000 +vt 0.966915 0.088204 +vn -0.6244 0.6032 -0.4962 +vn -0.0000 -1.0000 0.0000 +vn -0.5589 -0.7413 -0.3717 +vn 0.0000 -0.0000 1.0000 +vn -0.4773 0.8784 0.0251 +vn 0.5998 -0.6546 0.4601 +vn 0.5596 -0.6132 0.5575 +vn -0.6539 0.6180 -0.4364 +vn -0.6700 0.6253 -0.4000 +vn -0.7743 0.5656 0.2837 +vn 0.1441 0.7680 -0.6240 +vn -0.7317 -0.0518 -0.6796 +vn -0.5549 0.6672 -0.4968 +vn -0.5426 0.6783 -0.4955 +vn -0.4498 0.7412 -0.4983 +vn -0.5106 0.7016 -0.4971 +vn -0.4981 0.7119 -0.4952 +vn 1.0000 -0.0003 0.0003 +vn 0.5442 -0.5955 0.5910 +vn -0.6083 0.6286 -0.4846 +vn -0.6092 0.6277 -0.4846 +vn -0.6185 0.6099 -0.4956 +vn -0.5917 0.6343 -0.4976 +vn -0.5795 0.6464 -0.4963 +vn -0.4603 -0.8043 -0.3759 +vn -0.5575 -0.7424 -0.3715 +vn -0.7943 0.0000 -0.6075 +vn -0.8183 0.0000 -0.5748 +vn -0.4885 0.8263 0.2803 +vn -0.6404 0.7623 0.0938 +vn -0.5336 0.6003 0.5957 +vn -0.5691 0.8134 -0.1201 +vn -0.6229 0.7786 -0.0757 +vn 1.0000 0.0000 0.0000 +vn 0.6726 0.5902 -0.4463 +vn 0.3624 0.7851 -0.5023 +vn 0.0000 0.8160 -0.5781 +vn 0.0000 0.8348 -0.5505 +vn 1.0000 -0.0002 0.0002 +vn 1.0000 -0.0000 0.0001 +vn -0.7281 0.4850 -0.4843 +vn -0.7162 0.4837 -0.5031 +vn -0.6837 0.5358 -0.4954 +vn -0.7971 0.6026 0.0389 +vn -0.7416 0.6146 -0.2688 +vn -0.6784 0.5202 -0.5189 +vn -0.6640 0.5585 -0.4972 +vn -0.6550 0.5705 -0.4954 +usemtl None +s off +f 552/535/752 543/536/752 563/537/752 +f 540/538/753 541/539/753 545/540/753 +f 536/541/754 537/542/754 548/543/754 +f 541/539/755 544/544/755 548/543/755 +f 545/540/753 541/539/753 548/543/753 +f 538/545/756 544/544/756 549/546/756 +f 540/538/757 539/547/757 550/548/757 +f 541/539/753 540/538/753 550/548/753 +f 539/547/758 541/539/758 550/548/758 +f 546/549/759 542/550/759 552/535/759 +f 542/550/760 546/549/760 553/551/760 +f 536/541/761 548/543/761 553/551/761 +f 548/543/755 544/544/755 553/551/755 +f 535/552/762 545/540/762 554/553/762 +f 545/540/763 543/536/763 554/553/763 +f 547/554/764 535/552/764 554/553/764 +f 535/552/765 547/554/765 555/555/765 +f 538/545/766 549/546/766 556/556/766 +f 535/552/767 555/555/767 556/556/767 +f 555/555/768 538/545/768 556/556/768 +f 539/547/769 540/538/769 557/557/769 +f 541/539/770 539/547/770 557/557/770 +f 544/544/755 541/539/755 557/557/755 +f 542/550/771 547/554/771 558/558/771 +f 552/535/772 542/550/772 558/558/772 +f 543/536/773 552/535/773 558/558/773 +f 554/553/774 543/536/774 558/558/774 +f 547/554/775 554/553/775 558/558/775 +f 543/536/776 545/540/776 559/559/776 +f 548/543/777 537/542/777 559/559/777 +f 545/540/753 548/543/753 559/559/753 +f 551/560/778 543/536/778 559/559/778 +f 537/542/779 551/560/779 559/559/779 +f 544/544/780 538/545/780 560/561/780 +f 547/554/781 542/550/781 560/561/781 +f 542/550/782 553/551/782 560/561/782 +f 553/551/755 544/544/755 560/561/755 +f 538/545/783 555/555/783 560/561/783 +f 555/555/784 547/554/784 560/561/784 +f 540/538/785 545/540/785 561/562/785 +f 545/540/786 535/552/786 561/562/786 +f 549/546/787 544/544/787 561/562/787 +f 535/552/788 556/556/788 561/562/788 +f 556/556/789 549/546/789 561/562/789 +f 557/557/790 540/538/790 561/562/790 +f 544/544/791 557/557/791 561/562/791 +f 537/542/792 536/541/792 562/563/792 +f 551/560/793 537/542/793 562/563/793 +f 546/549/794 551/560/794 562/563/794 +f 536/541/795 553/551/795 562/563/795 +f 553/551/796 546/549/796 562/563/796 +f 543/536/797 551/560/797 563/537/797 +f 551/560/798 546/549/798 563/537/798 +f 546/549/799 552/535/799 563/537/799 +o Bowl_hull_18 +v -0.047003 0.043110 0.014881 +v -0.078037 0.029318 0.049367 +v -0.078037 0.028886 0.049367 +v -0.040969 0.028886 -0.008389 +v -0.040104 0.045266 0.017038 +v -0.069418 0.045697 0.048940 +v -0.073729 0.028886 0.049801 +v -0.040538 0.028886 -0.001492 +v -0.065106 0.045266 0.050235 +v -0.040104 0.045697 0.010574 +v -0.055195 0.029318 0.012731 +v -0.072868 0.039660 0.048506 +v -0.042261 0.031473 -0.004510 +v -0.055195 0.045697 0.028676 +v -0.040104 0.033629 -0.004510 +v -0.073298 0.040092 0.050235 +v -0.065106 0.045697 0.050235 +v -0.047865 0.029318 0.001520 +v -0.073729 0.029318 0.050235 +v -0.040969 0.045266 0.010140 +v -0.075883 0.034060 0.048940 +v -0.040104 0.044403 0.016176 +v -0.062091 0.044834 0.037296 +v -0.040538 0.036647 -0.001064 +v -0.040969 0.045697 0.018333 +v -0.040104 0.028886 -0.002359 +v -0.067695 0.042679 0.043332 +v -0.040969 0.045266 0.018333 +v -0.062091 0.029318 0.023501 +v -0.078037 0.028886 0.050235 +v -0.069849 0.045697 0.050235 +v -0.040104 0.028886 -0.008828 +v -0.055195 0.028886 0.012731 +v -0.042261 0.029318 -0.006666 +v -0.072868 0.028886 0.048506 +v -0.040969 0.032336 -0.005377 +v -0.042692 0.045697 0.012731 +v -0.074160 0.029318 0.042904 +vt 0.978074 0.056779 +vt 0.547377 0.420362 +vt 0.875881 0.102203 +vt 0.985317 0.000000 +vt 0.007439 0.977190 +vt 0.992659 0.113559 +vt 0.124217 0.988546 +vt 0.978074 0.227215 +vt 0.328504 1.000000 +vt 0.634984 0.602154 +vt 0.437940 1.000000 +vt 0.073121 1.000000 +vt 0.970732 0.136270 +vt 1.000000 0.124915 +vt 1.000000 0.340871 +vt 1.000000 0.340871 +vt 0.365016 0.602154 +vt 0.175215 0.795399 +vt 1.000000 0.113559 +vt 0.985317 0.000000 +vt 0.423355 1.000000 +vt 0.780932 0.420362 +vt 0.401429 0.818111 +vt 0.131460 0.988546 +vt 0.321163 0.977190 +vt 0.459867 0.977190 +vt 0.109534 1.000000 +vt 0.883124 0.272638 +vt 0.459867 0.977190 +vt 1.000000 0.000000 +vt 1.000000 0.215859 +vt 0.000000 1.000000 +vt 0.365016 0.602154 +vt 0.036609 0.943123 +vt 0.073121 0.943123 +vt 0.970732 0.136270 +vt 0.058438 0.977190 +vt 0.365016 0.931767 +vn -0.7980 0.3418 -0.4964 +vn 0.0000 -1.0000 -0.0000 +vn -0.0000 1.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn -0.8113 0.4869 -0.3236 +vn 0.0000 0.0000 1.0000 +vn -0.7595 0.4201 -0.4966 +vn -0.9104 0.4066 -0.0764 +vn -0.8449 0.4303 -0.3179 +vn -0.6383 0.6260 -0.4480 +vn -0.6565 0.5680 -0.4964 +vn 0.4252 0.7067 -0.5654 +vn -0.0872 0.7880 -0.6095 +vn 0.5125 0.8568 0.0572 +vn 0.7975 0.0000 0.6034 +vn 0.7883 -0.4718 0.3949 +vn -0.7474 0.4615 -0.4780 +vn -0.7507 0.4369 -0.4956 +vn -0.7171 0.4975 -0.4881 +vn 0.7181 -0.4935 0.4907 +vn 0.7323 -0.3959 0.5541 +vn 0.7171 -0.4985 0.4871 +vn 0.7270 -0.4852 0.4857 +vn 0.8315 0.0000 0.5555 +vn -0.7748 0.3920 -0.4960 +vn -0.7807 0.3821 -0.4945 +vn -1.0000 0.0000 0.0000 +vn -0.9042 0.3824 0.1901 +vn 0.0708 -0.7073 0.7033 +vn -0.8194 0.5043 -0.2725 +vn -0.7633 -0.3910 -0.5142 +vn -0.8369 0.0000 -0.5473 +vn -0.7995 -0.3352 -0.4984 +vn -0.8422 0.0000 -0.5392 +vn -0.8066 -0.2114 -0.5521 +vn -0.7120 0.4966 -0.4964 +vn -0.7252 0.4771 -0.4964 +vn -0.7206 0.4844 -0.4960 +vn 0.7127 -0.5170 0.4741 +vn 0.7067 -0.5401 0.4570 +vn -0.6861 0.5326 -0.4956 +vn -0.6871 0.5312 -0.4957 +vn -0.6605 0.5630 -0.4968 +vn -0.3699 0.6753 -0.6381 +vn -0.3573 0.6143 -0.7035 +vn -0.2566 0.6507 -0.7146 +vn -0.6173 0.5175 -0.5926 +vn -0.6874 0.5137 -0.5135 +vn -0.6149 0.6240 -0.4822 +vn -0.2798 0.8994 -0.3359 +vn -0.6152 0.6117 -0.4974 +vn -0.5993 0.6232 -0.5024 +vn -0.8576 0.0000 -0.5144 +vn -0.8112 0.3245 -0.4865 +vn -0.8171 -0.2722 -0.5082 +usemtl None +s off +f 584/564/800 592/565/800 601/566/800 +f 566/567/801 567/568/801 570/569/801 +f 570/569/801 567/568/801 571/570/801 +f 569/571/802 573/572/802 577/573/802 +f 573/572/803 568/574/803 578/575/803 +f 569/571/804 575/576/804 579/577/804 +f 573/572/802 569/571/802 580/578/802 +f 579/577/805 572/579/805 580/578/805 +f 574/580/806 575/576/806 581/581/806 +f 572/579/805 579/577/805 582/582/805 +f 565/583/807 579/577/807 584/564/807 +f 579/577/808 575/576/808 584/564/808 +f 578/575/803 568/574/803 585/584/803 +f 569/571/809 577/573/809 586/585/809 +f 577/573/810 564/586/810 587/587/810 +f 573/572/811 578/575/811 587/587/811 +f 583/588/812 573/572/812 587/587/812 +f 568/574/813 573/572/813 588/589/813 +f 580/578/814 572/579/814 588/589/814 +f 573/572/802 580/578/802 588/589/802 +f 571/570/801 567/568/801 589/590/801 +f 585/584/815 571/570/815 589/590/815 +f 578/575/803 585/584/803 589/590/803 +f 575/576/816 569/571/816 590/591/816 +f 581/581/817 575/576/817 590/591/817 +f 569/571/818 586/585/818 590/591/818 +f 582/582/819 570/569/819 591/592/819 +f 572/579/820 582/582/820 591/592/820 +f 570/569/821 585/584/821 591/592/821 +f 585/584/822 568/574/822 591/592/822 +f 568/574/823 588/589/823 591/592/823 +f 588/589/814 572/579/814 591/592/814 +f 575/576/824 574/580/824 592/565/824 +f 584/564/825 575/576/825 592/565/825 +f 565/583/826 566/567/826 593/593/826 +f 566/567/801 570/569/801 593/593/801 +f 579/577/827 565/583/827 593/593/827 +f 570/569/828 582/582/828 593/593/828 +f 582/582/805 579/577/805 593/593/805 +f 569/571/829 579/577/829 594/594/829 +f 580/578/802 569/571/802 594/594/802 +f 579/577/805 580/578/805 594/594/805 +f 589/590/801 567/568/801 595/595/801 +f 578/575/803 589/590/803 595/595/803 +f 567/568/801 566/567/801 596/596/801 +f 581/581/830 567/568/830 596/596/830 +f 574/580/831 581/581/831 596/596/831 +f 566/567/832 592/565/832 596/596/832 +f 592/565/833 574/580/833 596/596/833 +f 567/568/834 581/581/834 597/597/834 +f 586/585/835 576/598/835 597/597/835 +f 581/581/836 590/591/836 597/597/836 +f 590/591/837 586/585/837 597/597/837 +f 570/569/801 571/570/801 598/599/801 +f 585/584/838 570/569/838 598/599/838 +f 571/570/839 585/584/839 598/599/839 +f 586/585/840 577/573/840 599/600/840 +f 576/598/841 586/585/841 599/600/841 +f 577/573/842 587/587/842 599/600/842 +f 587/587/843 578/575/843 599/600/843 +f 595/595/844 567/568/844 599/600/844 +f 578/575/845 595/595/845 599/600/845 +f 567/568/846 597/597/846 599/600/846 +f 597/597/847 576/598/847 599/600/847 +f 564/586/848 577/573/848 600/601/848 +f 577/573/802 573/572/802 600/601/802 +f 573/572/849 583/588/849 600/601/849 +f 587/587/850 564/586/850 600/601/850 +f 583/588/851 587/587/851 600/601/851 +f 566/567/852 565/583/852 601/566/852 +f 565/583/853 584/564/853 601/566/853 +f 592/565/854 566/567/854 601/566/854 +o Bowl_hull_19 +v -0.044848 0.027158 -0.004945 +v -0.081920 0.015521 0.049370 +v -0.081920 0.015089 0.049370 +v -0.074160 0.028453 0.050235 +v -0.040968 0.015089 -0.012274 +v -0.040538 0.028453 -0.001928 +v -0.077176 0.015089 0.048934 +v -0.040538 0.015521 -0.020469 +v -0.077176 0.028885 0.047639 +v -0.040538 0.028885 -0.009257 +v -0.079763 0.024142 0.049370 +v -0.040108 0.028885 -0.002793 +v -0.060369 0.028885 0.020482 +v -0.050022 0.015521 -0.004945 +v -0.040108 0.015089 -0.020469 +v -0.041401 0.017678 -0.017873 +v -0.074160 0.028885 0.050235 +v -0.081920 0.015089 0.050235 +v -0.078470 0.028453 0.050235 +v -0.040108 0.015089 -0.013998 +v -0.040538 0.020695 -0.017015 +v -0.079763 0.020695 0.047639 +v -0.078040 0.015089 0.050235 +v -0.040108 0.028885 -0.009257 +v -0.076746 0.025002 0.044629 +v -0.068556 0.026727 0.032123 +v -0.044848 0.015521 -0.013568 +v -0.062518 0.015521 0.016170 +v -0.054332 0.028885 0.011007 +v -0.050022 0.015089 -0.004945 +v -0.073296 0.028453 0.048934 +v -0.042261 0.028885 -0.007097 +v -0.060799 0.028022 0.020482 +vt 0.445184 0.659814 +vt 0.048845 0.989721 +vt 0.579189 0.505140 +vt 0.115897 0.979442 +vt 0.262236 0.989721 +vt 0.981597 0.113461 +vt 0.987764 0.000000 +vt 0.158575 0.989721 +vt 0.963293 0.113461 +vt 0.250000 1.000000 +vt 0.579189 0.515418 +vt 0.000000 1.000000 +vt 1.000000 0.185609 +vt 0.987764 0.000000 +vt 1.000000 0.000000 +vt 0.987764 0.051591 +vt 1.000000 0.185609 +vt 1.000000 0.082526 +vt 0.091523 1.000000 +vt 0.000000 0.989721 +vt 0.036707 0.969065 +vt 0.963293 0.051591 +vt 1.000000 0.092805 +vt 0.158575 1.000000 +vt 0.920713 0.123740 +vt 0.219558 0.762898 +vt 0.743833 0.319628 +vt 0.097592 0.886637 +vt 0.518207 0.464023 +vt 0.219558 0.886637 +vt 0.219558 0.762898 +vt 0.981597 0.206265 +vt 0.189115 0.948507 +vn -0.7778 0.3862 -0.4958 +vn 0.7930 -0.3887 0.4691 +vn -0.0000 -1.0000 0.0000 +vn -0.0000 1.0000 0.0000 +vn 0.8173 0.2378 0.5248 +vn -1.0000 0.0000 0.0000 +vn -0.9630 0.2410 0.1204 +vn 0.0000 0.0000 1.0000 +vn -0.8645 0.3347 -0.3751 +vn -0.0991 0.9884 0.1152 +vn -0.9491 0.2451 0.1980 +vn 0.8381 -0.3506 0.4180 +vn 0.9101 -0.2612 0.3217 +vn 1.0000 0.0000 0.0000 +vn 0.4874 0.4848 -0.7262 +vn -0.7438 0.3711 -0.5559 +vn -0.8733 0.2185 -0.4354 +vn 0.8098 -0.2351 0.5375 +vn 0.0000 0.6877 -0.7260 +vn 0.8935 0.2832 -0.3485 +vn -0.8323 0.2792 -0.4789 +vn -0.8375 0.2451 -0.4884 +vn -0.8351 0.2383 -0.4958 +vn -0.8178 0.2934 -0.4951 +vn -0.8183 0.2906 -0.4959 +vn -0.8128 0.2855 -0.5077 +vn -0.8272 0.2634 -0.4963 +vn -0.8121 0.3066 -0.4965 +vn -0.8634 0.0000 -0.5046 +vn -0.8480 0.1878 -0.4956 +vn -0.8388 0.2236 -0.4964 +vn -0.7586 0.4216 -0.4967 +vn -0.6459 -0.6424 -0.4125 +vn -0.7826 -0.3854 -0.4889 +vn -0.8575 0.0000 -0.5145 +vn -0.8470 -0.1876 -0.4974 +vn -0.8606 0.0000 -0.5093 +vn 0.8167 -0.2372 0.5260 +vn 0.8332 0.0000 0.5530 +vn 0.8397 0.0499 0.5408 +vn -0.7289 0.4603 -0.5068 +vn -0.6729 0.5087 -0.5370 +vn -0.7275 0.4852 -0.4851 +vn -0.7830 0.3900 -0.4846 +vn -0.7867 0.3665 -0.4967 +vn -0.7964 0.3524 -0.4915 +vn -0.8003 0.3374 -0.4957 +vn -0.7775 0.3873 -0.4955 +usemtl None +s off +f 630/602/855 622/603/855 634/604/855 +f 606/605/856 607/606/856 608/607/856 +f 604/608/857 606/605/857 608/607/857 +f 611/609/858 610/610/858 613/611/858 +f 610/610/858 611/609/858 614/612/858 +f 606/605/857 604/608/857 616/613/857 +f 607/606/859 613/611/859 618/614/859 +f 613/611/858 610/610/858 618/614/858 +f 603/615/860 604/608/860 619/616/860 +f 604/608/857 608/607/857 619/616/857 +f 612/617/861 603/615/861 619/616/861 +f 605/618/862 618/614/862 619/616/862 +f 619/616/862 618/614/862 620/619/862 +f 610/610/863 612/617/863 620/619/863 +f 618/614/864 610/610/864 620/619/864 +f 612/617/865 619/616/865 620/619/865 +f 607/606/866 606/605/866 621/620/866 +f 613/611/867 607/606/867 621/620/867 +f 606/605/857 616/613/857 621/620/857 +f 616/613/868 613/611/868 621/620/868 +f 616/613/869 609/621/869 622/603/869 +f 609/621/870 617/622/870 622/603/870 +f 603/615/871 612/617/871 623/623/871 +f 608/607/872 605/618/872 624/624/872 +f 619/616/857 608/607/857 624/624/857 +f 605/618/862 619/616/862 624/624/862 +f 611/609/858 613/611/858 625/625/858 +f 613/611/868 616/613/868 625/625/868 +f 622/603/873 611/609/873 625/625/873 +f 616/613/874 622/603/874 625/625/874 +f 612/617/875 610/610/875 626/626/875 +f 623/623/876 612/617/876 626/626/876 +f 615/627/877 623/623/877 626/626/877 +f 626/626/878 610/610/878 627/628/878 +f 626/626/879 627/628/879 628/629/879 +f 617/622/880 609/621/880 628/629/880 +f 615/627/881 626/626/881 628/629/881 +f 627/628/882 617/622/882 628/629/882 +f 604/608/883 603/615/883 629/630/883 +f 603/615/884 623/623/884 629/630/884 +f 623/623/885 615/627/885 629/630/885 +f 614/612/858 611/609/858 630/602/858 +f 602/631/886 622/603/886 630/602/886 +f 616/613/857 604/608/857 631/632/857 +f 609/621/887 616/613/887 631/632/887 +f 628/629/888 609/621/888 631/632/888 +f 615/627/889 628/629/889 631/632/889 +f 604/608/890 629/630/890 631/632/890 +f 629/630/891 615/627/891 631/632/891 +f 608/607/892 607/606/892 632/633/892 +f 605/618/872 608/607/872 632/633/872 +f 618/614/893 605/618/893 632/633/893 +f 607/606/894 618/614/894 632/633/894 +f 622/603/895 602/631/895 633/634/895 +f 611/609/896 622/603/896 633/634/896 +f 602/631/897 630/602/897 633/634/897 +f 630/602/858 611/609/858 633/634/858 +f 610/610/898 614/612/898 634/604/898 +f 622/603/899 617/622/899 634/604/899 +f 627/628/900 610/610/900 634/604/900 +f 617/622/901 627/628/901 634/604/901 +f 614/612/902 630/602/902 634/604/902 +o Bowl_hull_20 +v -0.040969 0.014656 -0.020462 +v -0.083210 0.003451 0.049363 +v -0.082779 0.006900 0.048935 +v -0.078040 0.014656 0.050235 +v -0.040539 0.000433 -0.017877 +v -0.041399 0.000433 -0.023911 +v -0.079332 0.000433 0.049799 +v -0.040104 0.015086 -0.014000 +v -0.081488 0.015086 0.048507 +v -0.083210 0.000433 0.049363 +v -0.040539 0.007330 -0.024347 +v -0.078471 0.000433 0.048507 +v -0.054764 0.015086 0.002815 +v -0.040539 0.003881 -0.025211 +v -0.081918 0.015086 0.050235 +v -0.040104 0.014656 -0.014000 +v -0.040104 0.015086 -0.020898 +v -0.040104 0.000433 -0.025211 +v -0.078040 0.015086 0.050235 +v -0.076314 0.009914 0.038160 +v -0.083210 0.000433 0.050235 +v -0.042695 0.009482 -0.020034 +v -0.040104 0.000433 -0.018742 +v -0.046573 0.007330 -0.014000 +v -0.048299 0.002157 -0.011844 +v -0.079766 0.000433 0.050235 +v -0.082779 0.000433 0.048507 +v -0.082779 0.009482 0.049363 +v -0.071575 0.005176 0.029106 +v -0.041399 0.011639 -0.021326 +v -0.063381 0.015086 0.017460 +vt 0.371476 0.659912 +vt 0.068618 0.939892 +vt 0.565583 0.460010 +vt 0.017228 0.969946 +vt 0.097200 0.989917 +vt 0.994225 0.089966 +vt 0.988450 0.000000 +vt 1.000000 0.119922 +vt 0.977095 0.109936 +vt 0.977095 0.039941 +vt 0.148590 1.000000 +vt 1.000000 0.029956 +vt 0.148590 1.000000 +vt 0.011453 0.989917 +vt 0.062940 0.979932 +vt 0.057165 1.000000 +vt 0.000000 1.000000 +vt 0.000000 0.989917 +vt 1.000000 0.119922 +vt 0.988450 0.000000 +vt 1.000000 0.000000 +vt 0.085748 1.000000 +vt 0.148590 0.849927 +vt 0.839957 0.159961 +vt 0.177173 0.809887 +vt 1.000000 0.079882 +vt 0.977095 0.009985 +vt 0.982772 0.009985 +vt 0.988450 0.009985 +vt 0.719949 0.269897 +vt 0.051488 0.969946 +vn -0.8432 0.2070 -0.4961 +vn 0.0000 -1.0000 -0.0000 +vn 0.8287 -0.0921 0.5520 +vn 0.0000 1.0000 0.0000 +vn 0.8610 0.0000 0.5085 +vn 0.8577 -0.0875 0.5066 +vn 0.8571 -0.1597 0.4898 +vn -0.5569 0.3633 -0.7469 +vn -0.5507 0.7622 -0.3404 +vn 1.0000 0.0000 0.0000 +vn -0.7055 -0.0889 -0.7031 +vn 0.8877 0.1119 -0.4466 +vn 0.9321 0.1023 -0.3474 +vn 0.0000 0.0000 1.0000 +vn -1.0000 0.0000 0.0000 +vn 0.8835 -0.1481 0.4444 +vn -0.8570 0.1252 -0.4998 +vn -0.8580 0.1337 -0.4959 +vn -0.8615 0.1065 -0.4965 +vn -0.8550 0.1427 -0.4987 +vn -0.8552 0.1497 -0.4963 +vn -0.8660 0.0280 -0.4992 +vn 0.7054 -0.0856 0.7036 +vn -0.8936 0.0000 -0.4490 +vn -0.8684 0.0168 -0.4956 +vn -0.8682 -0.0021 -0.4961 +vn -0.9166 0.0654 -0.3944 +vn -0.9539 0.1835 -0.2376 +vn -0.8616 0.1233 -0.4924 +vn -0.9685 0.0691 0.2394 +vn -0.9186 0.0809 0.3869 +vn -0.8679 0.0469 -0.4945 +vn -0.8644 0.0831 -0.4959 +vn -0.8679 0.0323 -0.4957 +vn -0.8665 0.0519 -0.4964 +vn -0.8646 0.0822 -0.4957 +vn -0.8646 0.0826 -0.4957 +vn -0.7401 0.2806 -0.6112 +vn -0.8285 0.2602 -0.4958 +vn -0.8354 0.1937 -0.5143 +vn -0.8427 0.2088 -0.4963 +vn -0.8498 0.1792 -0.4956 +usemtl None +s off +f 647/635/903 656/636/903 665/637/903 +f 640/638/904 639/639/904 641/640/904 +f 640/638/904 641/640/904 644/641/904 +f 638/642/905 641/640/905 646/643/905 +f 641/640/904 639/639/904 646/643/904 +f 643/644/906 642/645/906 647/635/906 +f 642/645/906 643/644/906 649/646/906 +f 642/645/907 638/642/907 650/647/907 +f 638/642/908 646/643/908 650/647/908 +f 646/643/909 639/639/909 650/647/909 +f 645/648/910 635/649/910 651/650/910 +f 635/649/911 647/635/911 651/650/911 +f 647/635/906 642/645/906 651/650/906 +f 642/645/912 650/647/912 651/650/912 +f 651/650/912 650/647/912 652/651/912 +f 639/639/904 640/638/904 652/651/904 +f 640/638/913 648/652/913 652/651/913 +f 648/652/914 645/648/914 652/651/914 +f 645/648/915 651/650/915 652/651/915 +f 638/642/907 642/645/907 653/653/907 +f 649/646/916 638/642/916 653/653/916 +f 642/645/906 649/646/906 653/653/906 +f 636/654/917 644/641/917 655/655/917 +f 644/641/904 641/640/904 655/655/904 +f 638/642/916 649/646/916 655/655/916 +f 650/647/918 639/639/918 657/656/918 +f 652/651/912 650/647/912 657/656/912 +f 639/639/904 652/651/904 657/656/904 +f 645/648/919 648/652/919 658/657/919 +f 654/658/920 643/644/920 658/657/920 +f 648/652/921 654/658/921 658/657/921 +f 656/636/922 645/648/922 658/657/922 +f 643/644/923 656/636/923 658/657/923 +f 648/652/924 640/638/924 659/659/924 +f 641/640/925 638/642/925 660/660/925 +f 638/642/916 655/655/916 660/660/916 +f 655/655/904 641/640/904 660/660/904 +f 644/641/926 636/654/926 661/661/926 +f 640/638/904 644/641/904 661/661/904 +f 636/654/927 659/659/927 661/661/927 +f 659/659/928 640/638/928 661/661/928 +f 637/662/929 636/654/929 662/663/929 +f 649/646/930 643/644/930 662/663/930 +f 643/644/931 654/658/931 662/663/931 +f 636/654/932 655/655/932 662/663/932 +f 655/655/933 649/646/933 662/663/933 +f 636/654/934 637/662/934 663/664/934 +f 654/658/935 648/652/935 663/664/935 +f 659/659/936 636/654/936 663/664/936 +f 648/652/937 659/659/937 663/664/937 +f 637/662/938 662/663/938 663/664/938 +f 662/663/939 654/658/939 663/664/939 +f 635/649/940 645/648/940 664/665/940 +f 647/635/941 635/649/941 664/665/941 +f 645/648/942 656/636/942 664/665/942 +f 656/636/943 647/635/943 664/665/943 +f 643/644/906 647/635/906 665/637/906 +f 656/636/944 643/644/944 665/637/944 +o Bowl_hull_21 +v -0.030189 0.064663 0.028240 +v -0.039671 0.039663 0.009287 +v -0.039240 0.040096 0.009715 +v -0.020704 0.040096 -0.017020 +v -0.020704 0.076738 0.050235 +v -0.040102 0.072853 0.048931 +v -0.020704 0.040096 -0.009679 +v -0.040102 0.040958 0.003678 +v -0.021137 0.080619 0.049366 +v -0.040102 0.068111 0.049366 +v -0.025016 0.040096 -0.013998 +v -0.040102 0.053033 0.019623 +v -0.021137 0.050872 -0.000193 +v -0.029327 0.078029 0.049366 +v -0.040102 0.073286 0.050235 +v -0.020704 0.080619 0.050235 +v -0.034931 0.040096 -0.003649 +v -0.039240 0.068977 0.050235 +v -0.021566 0.040096 -0.017020 +v -0.021566 0.039663 -0.017020 +v -0.040102 0.039663 0.002816 +v -0.039671 0.040096 0.010143 +v -0.038809 0.059928 0.028240 +v -0.040102 0.040096 0.010143 +v -0.021137 0.059070 0.013171 +v -0.031480 0.076734 0.048503 +v -0.020704 0.075876 0.048938 +v -0.020704 0.039663 -0.010542 +v -0.039671 0.068111 0.049366 +v -0.026309 0.078887 0.048938 +v -0.036224 0.072424 0.045054 +v -0.031049 0.042257 -0.004939 +v -0.038378 0.066820 0.038154 +v -0.020704 0.059070 0.013171 +v -0.020704 0.041391 -0.007527 +v -0.021566 0.076738 0.042901 +v -0.029758 0.078029 0.050235 +v -0.021566 0.046133 -0.007527 +v -0.040102 0.045700 0.009715 +v -0.040102 0.059062 0.028240 +v -0.033636 0.076305 0.049366 +v -0.031049 0.040096 -0.007961 +vt 0.544832 0.673551 +vt 0.179620 0.936668 +vt 0.134691 0.989428 +vt 0.000000 0.989428 +vt 1.000000 0.094753 +vt 0.109143 0.989428 +vt 0.980619 0.189605 +vt 0.307753 0.968383 +vt 0.987079 0.305403 +vt 1.000000 0.179033 +vt 1.000000 0.000000 +vt 1.000000 0.284260 +vt 0.250196 0.726312 +vt 0.000000 0.989428 +vt 0.000000 1.000000 +vt 0.044930 0.989428 +vt 0.294930 1.000000 +vt 0.198806 0.989428 +vt 0.391151 1.000000 +vt 0.397514 0.989428 +vt 0.403876 0.989428 +vt 0.403876 0.989428 +vt 0.448904 0.526136 +vt 0.974256 0.094851 +vt 0.980717 0.115799 +vt 0.096319 1.000000 +vt 0.987079 0.305403 +vt 0.987079 0.063234 +vt 0.987079 0.000000 +vt 0.980717 0.042287 +vt 0.820380 0.336922 +vt 0.672964 0.505188 +vt 0.922964 0.200078 +vt 0.448904 0.526136 +vt 0.141151 0.957811 +vt 0.890955 0.094753 +vt 1.000000 0.063234 +vt 0.141151 0.842013 +vt 0.672964 0.389585 +vt 0.397514 0.852584 +vt 0.672964 0.526331 +vt 0.987079 0.105325 +vn -0.5207 0.6944 -0.4966 +vn 1.0000 0.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn -0.6376 -0.1276 0.7597 +vn 0.0000 0.8421 -0.5393 +vn 0.0000 0.0000 -1.0000 +vn -0.6588 0.0000 -0.7523 +vn -0.7359 0.3753 -0.5635 +vn 0.0000 -1.0000 0.0000 +vn 0.4089 -0.8143 0.4120 +vn -0.6630 -0.7474 0.0442 +vn 0.0000 -0.8923 0.4514 +vn 0.0000 -0.8137 0.5812 +vn -0.3139 0.8093 -0.4965 +vn 0.4639 -0.7526 0.4673 +vn 0.4019 -0.7626 0.5068 +vn 0.4195 -0.8142 0.4013 +vn 0.4250 -0.8090 0.4062 +vn 0.4480 -0.8920 -0.0596 +vn 0.3123 -0.7459 0.5883 +vn 0.0000 -0.7083 0.7059 +vn 0.3249 -0.7696 0.5497 +vn -0.2948 0.9323 -0.2096 +vn -0.3022 0.8230 -0.4811 +vn -0.2981 0.8160 -0.4952 +vn -0.4347 0.7514 -0.4964 +vn -0.4840 0.7283 -0.4852 +vn -0.4520 0.7415 -0.4958 +vn -0.4078 0.7668 -0.4957 +vn -0.4098 0.7664 -0.4947 +vn 0.3654 0.7881 -0.4953 +vn 0.7102 0.6086 -0.3539 +vn 0.0000 0.8524 -0.5229 +vn 0.0000 0.8593 -0.5116 +vn 0.4747 -0.7542 0.4537 +vn 0.4782 -0.7495 0.4578 +vn 1.0000 -0.0002 0.0000 +vn -0.0638 0.8575 -0.5105 +vn -0.2406 0.8392 -0.4878 +vn -0.2562 0.8293 -0.4965 +vn -0.2982 0.9430 -0.1479 +vn -0.2725 0.9525 0.1357 +vn -0.1447 0.8349 -0.5310 +vn -0.3482 0.7954 -0.4960 +vn -0.3393 0.7990 -0.4964 +vn -0.3751 0.7830 -0.4961 +vn -0.3806 0.7803 -0.4963 +vn -0.5971 0.6308 -0.4956 +vn -0.5544 0.6690 -0.4951 +vn -0.4867 0.7269 -0.4845 +vn -0.4830 0.7213 -0.4964 +vn -0.4888 0.7172 -0.4966 +vn -0.5018 0.7087 -0.4959 +vn -0.4367 0.8537 -0.2836 +vn -0.3558 0.7927 -0.4949 +vn -0.3366 0.8414 -0.4228 +vn -0.3613 0.7905 -0.4946 +vn -0.3890 0.7886 -0.4762 +vn -0.3653 0.9131 -0.1812 +vn -0.4161 0.9076 0.0565 +vn -0.5507 0.6716 -0.4957 +vn -0.5785 -0.5754 -0.5782 +vn -0.4967 -0.7439 -0.4472 +vn -0.3675 -0.8643 -0.3434 +vn -0.5030 0.7030 -0.5027 +usemtl None +s off +f 677/666/945 697/667/945 707/668/945 +f 669/669/946 670/670/946 672/671/946 +f 671/672/947 673/673/947 675/674/947 +f 673/673/947 671/672/947 677/666/947 +f 671/672/947 675/674/947 680/675/947 +f 670/670/946 669/669/946 681/676/946 +f 680/675/948 670/670/948 681/676/948 +f 670/670/948 680/675/948 683/677/948 +f 680/675/949 675/674/949 683/677/949 +f 678/678/950 669/669/950 684/679/950 +f 684/679/951 669/669/951 685/680/951 +f 676/681/952 684/679/952 685/680/952 +f 675/674/947 673/673/947 686/682/947 +f 673/673/953 682/683/953 686/682/953 +f 685/680/954 667/684/954 686/682/954 +f 667/684/955 668/685/955 687/686/955 +f 686/682/956 667/684/956 689/687/956 +f 675/674/947 686/682/947 689/687/947 +f 667/684/957 687/686/957 689/687/957 +f 687/686/958 675/674/958 689/687/958 +f 690/688/959 678/678/959 691/689/959 +f 672/671/946 670/670/946 692/690/946 +f 687/686/960 668/685/960 692/690/960 +f 670/670/961 687/686/961 692/690/961 +f 668/685/962 667/684/962 693/691/962 +f 672/671/963 668/685/963 693/691/963 +f 669/669/946 672/671/946 693/691/946 +f 667/684/954 685/680/954 693/691/954 +f 685/680/964 669/669/964 693/691/964 +f 670/670/965 683/677/965 694/692/965 +f 683/677/966 675/674/966 694/692/966 +f 687/686/967 670/670/967 694/692/967 +f 675/674/958 687/686/958 694/692/958 +f 679/693/968 674/694/968 695/695/968 +f 691/689/969 679/693/969 695/695/969 +f 690/688/970 691/689/970 695/695/970 +f 684/679/971 676/681/971 698/696/971 +f 688/697/972 671/672/972 698/696/972 +f 676/681/973 688/697/973 698/696/973 +f 696/698/974 684/679/974 698/696/974 +f 671/672/975 696/698/975 698/696/975 +f 669/669/976 678/678/976 699/699/976 +f 681/676/946 669/669/946 699/699/946 +f 674/694/977 681/676/977 699/699/977 +f 678/678/978 690/688/978 699/699/978 +f 690/688/979 674/694/979 699/699/979 +f 668/685/980 672/671/980 700/700/980 +f 692/690/981 668/685/981 700/700/981 +f 672/671/982 692/690/982 700/700/982 +f 674/694/983 690/688/983 701/701/983 +f 695/695/984 674/694/984 701/701/984 +f 690/688/985 695/695/985 701/701/985 +f 674/694/986 679/693/986 702/702/986 +f 680/675/948 681/676/948 702/702/948 +f 681/676/987 674/694/987 702/702/987 +f 678/678/988 684/679/988 703/703/988 +f 666/704/989 691/689/989 703/703/989 +f 691/689/990 678/678/990 703/703/990 +f 696/698/991 666/704/991 703/703/991 +f 684/679/992 696/698/992 703/703/992 +f 673/673/947 677/666/947 704/705/947 +f 682/683/993 673/673/993 704/705/993 +f 677/666/994 682/683/994 704/705/994 +f 677/666/947 671/672/947 705/706/947 +f 671/672/995 688/697/995 705/706/995 +f 688/697/996 676/681/996 705/706/996 +f 676/681/997 697/667/997 705/706/997 +f 697/667/998 677/666/998 705/706/998 +f 671/672/999 680/675/999 706/707/999 +f 691/689/1000 666/704/1000 706/707/1000 +f 679/693/1001 691/689/1001 706/707/1001 +f 666/704/1002 696/698/1002 706/707/1002 +f 696/698/1003 671/672/1003 706/707/1003 +f 702/702/1004 679/693/1004 706/707/1004 +f 680/675/1005 702/702/1005 706/707/1005 +f 682/683/1006 677/666/1006 707/668/1006 +f 676/681/1007 685/680/1007 707/668/1007 +f 686/682/1008 682/683/1008 707/668/1008 +f 685/680/1009 686/682/1009 707/668/1009 +f 697/667/1010 676/681/1010 707/668/1010 +o Bowl_hull_22 +v -0.013373 0.082336 0.050235 +v -0.009065 0.039663 -0.017450 +v -0.009496 0.039663 -0.017450 +v -0.002167 0.041389 -0.023911 +v -0.001305 0.079318 0.049796 +v -0.020704 0.040528 -0.009250 +v -0.020704 0.040528 -0.017011 +v -0.020704 0.076735 0.050235 +v -0.001305 0.082771 0.048504 +v -0.001305 0.040532 -0.017880 +v -0.020704 0.079753 0.047643 +v -0.011649 0.040097 -0.023481 +v -0.011649 0.081045 0.046774 +v -0.001305 0.039663 -0.025642 +v -0.008201 0.042689 -0.020465 +v -0.019840 0.039667 -0.010973 +v -0.001305 0.078462 0.048504 +v -0.020704 0.060791 0.015735 +v -0.006478 0.082340 0.048073 +v -0.020704 0.039667 -0.017450 +v -0.017686 0.081475 0.049366 +v -0.001305 0.083206 0.050235 +v -0.005616 0.040097 -0.025642 +v -0.020271 0.040528 -0.009250 +v -0.020271 0.076735 0.050235 +v -0.015960 0.041824 -0.018311 +v -0.001305 0.039663 -0.019604 +v -0.020704 0.080614 0.050235 +v -0.001305 0.041389 -0.023911 +v -0.001305 0.079753 0.050235 +v -0.003892 0.083206 0.049366 +v -0.009496 0.042689 -0.020034 +v -0.009496 0.039663 -0.024342 +v -0.020704 0.050011 -0.001919 +v -0.012942 0.082336 0.049366 +v -0.005616 0.046568 -0.014427 +v -0.020704 0.075444 0.040312 +v -0.018115 0.040097 -0.019596 +v -0.001305 0.042250 -0.014858 +vt 0.977193 0.108947 +vt 0.216034 0.980129 +vt 0.142130 0.940583 +vt 0.113743 0.980129 +vt 0.216034 0.980129 +vt 1.000000 0.148590 +vt 0.977193 0.009984 +vt 0.994225 0.089272 +vt 0.102291 0.980031 +vt 0.965838 0.079287 +vt 0.107968 1.000000 +vt 0.107968 1.000000 +vt 0.000000 1.000000 +vt 0.193324 0.999902 +vt 0.545321 0.514781 +vt 0.107968 0.999902 +vt 1.000000 0.019969 +vt 1.000000 0.000000 +vt 0.068226 0.930501 +vt 0.954385 0.049628 +vt 0.000000 0.990016 +vt 1.000000 0.148590 +vt 0.028485 0.990016 +vt 0.096613 0.950372 +vt 0.079581 1.000000 +vt 1.000000 0.059514 +vt 0.988547 0.039742 +vt 0.022807 0.960356 +vt 0.022807 0.960356 +vt 1.000000 0.079287 +vt 0.988547 0.000000 +vt 0.971515 0.019871 +vt 0.073904 0.930501 +vt 0.017130 1.000000 +vt 0.312647 0.762334 +vt 0.988547 0.019969 +vt 0.147807 0.841425 +vt 0.869225 0.178250 +vt 0.079679 0.990016 +vn 0.2200 -0.8469 0.4840 +vn -1.0000 0.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 -1.0000 0.0006 +vn -0.0004 -1.0000 0.0000 +vn -0.6164 -0.7832 0.0822 +vn 0.0000 0.0000 1.0000 +vn -0.1338 0.8578 -0.4962 +vn 0.0000 -0.8542 0.5199 +vn 0.0000 -0.8946 0.4470 +vn 0.2183 -0.8500 0.4793 +vn 0.1242 -0.8476 0.5159 +vn 0.1253 -0.8269 0.5482 +vn -0.2654 0.8261 -0.4972 +vn 0.0003 -1.0000 0.0012 +vn 0.2051 -0.8738 0.4409 +vn -0.2254 0.9597 0.1680 +vn -0.3400 0.8925 -0.2964 +vn 0.0000 0.8682 -0.4962 +vn 0.0000 0.8014 -0.5981 +vn 0.0712 0.7062 -0.7044 +vn 0.1122 -0.7054 0.6998 +vn -0.0193 0.8682 -0.4959 +vn -0.0423 0.8673 -0.4959 +vn -0.0703 0.9754 0.2092 +vn 0.0816 0.9666 -0.2428 +vn -0.1992 0.8452 -0.4959 +vn -0.1650 0.8525 -0.4959 +vn -0.1843 0.8374 -0.5145 +vn -0.1687 0.8451 -0.5073 +vn -0.0848 -0.8409 -0.5344 +vn -0.3310 0.1915 -0.9240 +vn -0.3113 0.8111 -0.4952 +vn -0.1383 0.8572 -0.4961 +vn -0.0970 0.8707 -0.4822 +vn -0.1779 0.9801 -0.0882 +vn -0.1551 0.8545 -0.4957 +vn -0.0864 0.8991 -0.4291 +vn -0.0955 0.9943 -0.0474 +vn -0.0652 0.8657 -0.4964 +vn -0.0918 0.8637 -0.4956 +vn -0.0734 0.8639 -0.4984 +vn -0.1183 0.8601 -0.4962 +vn -0.2471 0.8323 -0.4962 +vn -0.2046 0.8439 -0.4960 +vn -0.2169 0.8405 -0.4965 +vn -0.6315 0.3517 -0.6910 +vn -0.3169 0.7883 -0.5275 +vn -0.3920 -0.6485 -0.6525 +vn -0.3535 -0.7384 -0.5743 +vn -0.3637 0.7887 -0.4956 +vn -0.3421 0.7973 -0.4973 +vn 0.2195 -0.8482 0.4820 +usemtl None +s off +f 724/708/1011 731/709/1011 746/710/1011 +f 714/711/1012 713/712/1012 715/713/1012 +f 716/714/1013 712/715/1013 717/716/1013 +f 714/711/1012 715/713/1012 718/717/1012 +f 709/718/1014 710/719/1014 721/720/1014 +f 716/714/1013 717/716/1013 721/720/1013 +f 710/719/1015 709/718/1015 723/721/1015 +f 717/716/1013 712/715/1013 724/708/1013 +f 714/711/1012 718/717/1012 725/722/1012 +f 713/712/1012 714/711/1012 727/723/1012 +f 710/719/1016 723/721/1016 727/723/1016 +f 723/721/1017 713/712/1017 727/723/1017 +f 708/724/1018 715/713/1018 729/725/1018 +f 712/715/1013 716/714/1013 729/725/1013 +f 722/726/1019 720/727/1019 730/728/1019 +f 715/713/1020 713/712/1020 731/709/1020 +f 713/712/1021 723/721/1021 731/709/1021 +f 723/721/1022 717/716/1022 731/709/1022 +f 731/709/1023 724/708/1023 732/729/1023 +f 724/708/1024 712/715/1024 732/729/1024 +f 729/725/1018 715/713/1018 732/729/1018 +f 715/713/1020 731/709/1020 732/729/1020 +f 725/722/1025 719/730/1025 733/731/1025 +f 709/718/1014 721/720/1014 734/732/1014 +f 721/720/1013 717/716/1013 734/732/1013 +f 723/721/1026 709/718/1026 734/732/1026 +f 717/716/1027 723/721/1027 734/732/1027 +f 715/713/1018 708/724/1018 735/733/1018 +f 718/717/1012 715/713/1012 735/733/1012 +f 708/724/1028 728/734/1028 735/733/1028 +f 728/734/1029 718/717/1029 735/733/1029 +f 711/735/1030 716/714/1030 736/736/1030 +f 716/714/1013 721/720/1013 736/736/1013 +f 730/728/1031 711/735/1031 736/736/1031 +f 721/720/1032 730/728/1032 736/736/1032 +f 712/715/1013 729/725/1013 737/737/1013 +f 732/729/1033 712/715/1033 737/737/1033 +f 729/725/1018 732/729/1018 737/737/1018 +f 716/714/1034 711/735/1034 738/738/1034 +f 711/735/1035 726/739/1035 738/738/1035 +f 708/724/1036 729/725/1036 738/738/1036 +f 729/725/1037 716/714/1037 738/738/1037 +f 718/717/1038 728/734/1038 739/740/1038 +f 728/734/1039 722/726/1039 739/740/1039 +f 730/728/1040 719/730/1040 739/740/1040 +f 722/726/1041 730/728/1041 739/740/1041 +f 721/720/1014 710/719/1014 740/741/1014 +f 710/719/1016 727/723/1016 740/741/1016 +f 730/728/1042 721/720/1042 740/741/1042 +f 719/730/1043 730/728/1043 740/741/1043 +f 714/711/1012 725/722/1012 741/742/1012 +f 725/722/1044 733/731/1044 741/742/1044 +f 720/727/1045 722/726/1045 742/743/1045 +f 726/739/1046 720/727/1046 742/743/1046 +f 728/734/1047 708/724/1047 742/743/1047 +f 722/726/1048 728/734/1048 742/743/1048 +f 738/738/1049 726/739/1049 742/743/1049 +f 708/724/1050 738/738/1050 742/743/1050 +f 726/739/1051 711/735/1051 743/744/1051 +f 720/727/1052 726/739/1052 743/744/1052 +f 711/735/1053 730/728/1053 743/744/1053 +f 730/728/1054 720/727/1054 743/744/1054 +f 725/722/1012 718/717/1012 744/745/1012 +f 719/730/1055 725/722/1055 744/745/1055 +f 718/717/1056 739/740/1056 744/745/1056 +f 739/740/1057 719/730/1057 744/745/1057 +f 727/723/1058 714/711/1058 745/746/1058 +f 733/731/1059 719/730/1059 745/746/1059 +f 719/730/1060 740/741/1060 745/746/1060 +f 740/741/1061 727/723/1061 745/746/1061 +f 714/711/1062 741/742/1062 745/746/1062 +f 741/742/1063 733/731/1063 745/746/1063 +f 717/716/1013 724/708/1013 746/710/1013 +f 731/709/1064 717/716/1064 746/710/1064 +o Bowl_hull_23 +v -0.013374 -0.042685 -0.018306 +v 0.002577 -0.083206 0.050235 +v -0.006045 -0.083206 0.050235 +v -0.012943 -0.077597 0.048935 +v 0.002577 -0.040959 -0.017013 +v 0.002144 -0.041389 -0.023904 +v -0.013374 -0.040098 -0.015293 +v 0.002577 -0.078893 0.049371 +v -0.013374 -0.081475 0.048078 +v -0.006045 -0.040529 -0.024768 +v -0.002598 -0.082771 0.048507 +v -0.012943 -0.042685 -0.010544 +v 0.002577 -0.040098 -0.025211 +v -0.013374 -0.078462 0.050235 +v 0.002577 -0.083206 0.049371 +v -0.013374 -0.040098 -0.021755 +v -0.006476 -0.078893 0.042037 +v -0.002167 -0.041389 -0.023904 +v -0.012512 -0.056911 0.005400 +v -0.012943 -0.082336 0.049371 +v 0.002577 -0.040098 -0.018742 +v 0.002577 -0.079754 0.050235 +v -0.010356 -0.040959 -0.022611 +v 0.002577 -0.067254 0.021337 +v -0.006476 -0.043976 -0.018742 +v -0.013374 -0.082336 0.050235 +v -0.011218 -0.082336 0.048935 +v -0.013374 -0.065528 0.020480 +v 0.002577 -0.040529 -0.025211 +v -0.008200 -0.045702 -0.015293 +v -0.005613 -0.046567 -0.014421 +v -0.012512 -0.040529 -0.014429 +vt 0.085748 0.000000 +vt 0.131460 0.000000 +vt 0.142913 0.009985 +vt 1.000000 1.000000 +vt 0.108653 0.019971 +vt 0.988547 0.899951 +vt 0.091523 0.060010 +vt 0.971417 0.959863 +vt 0.982772 0.869897 +vt 0.194401 0.060010 +vt 0.000000 0.000000 +vt 1.000000 1.000000 +vt 1.000000 0.889966 +vt 0.988547 1.000000 +vt 0.977095 0.989917 +vt 0.045810 0.000000 +vt 0.005873 0.009985 +vt 0.891347 0.899951 +vt 0.017326 0.029956 +vt 1.000000 0.919921 +vt 0.034456 0.019971 +vt 0.405736 0.390015 +vt 0.616973 0.629956 +vt 0.017326 0.029956 +vt 1.000000 0.979834 +vt 0.988547 0.979834 +vt 0.982772 0.979834 +vt 0.085748 0.089966 +vt 0.605619 0.589917 +vt 0.000000 0.009985 +vt 0.131460 0.130005 +vt 0.143011 0.150073 +vn 0.0817 0.9222 0.3779 +vn 1.0000 0.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0577 0.8610 0.5054 +vn 0.1096 0.8630 0.4932 +vn 0.0000 0.0000 1.0000 +vn 0.0528 0.8231 0.5654 +vn -0.2004 0.8449 0.4959 +vn -0.3609 0.8048 0.4712 +vn 0.0000 -1.0000 0.0000 +vn -0.0300 -0.9535 -0.2998 +vn -0.0000 1.0000 0.0000 +vn -0.0625 0.9554 -0.2886 +vn -0.0401 -0.8674 -0.4960 +vn 0.0573 0.7072 0.7046 +vn -0.3702 -0.7431 -0.5574 +vn -0.3611 -0.4568 -0.8130 +vn -0.2266 -0.8388 -0.4951 +vn 0.0096 -0.8691 -0.4945 +vn -0.0017 -0.8682 -0.4962 +vn 0.0000 -0.8681 -0.4963 +vn -0.1176 -0.9913 -0.0586 +vn -0.5966 -0.7453 -0.2976 +vn -0.0649 -0.9294 -0.3633 +vn -0.0680 -0.8732 -0.4827 +vn -0.0797 -0.9456 -0.3154 +vn -0.1252 -0.8593 -0.4959 +vn -0.2553 -0.8331 -0.4907 +vn -0.2235 -0.8439 -0.4877 +vn -0.0513 0.0000 -0.9987 +vn 0.0000 -0.8351 -0.5500 +vn -0.0323 -0.7768 -0.6289 +vn 0.2161 -0.8467 -0.4861 +vn -0.1660 -0.8491 -0.5014 +vn -0.1797 -0.8488 -0.4972 +vn -0.1430 -0.8546 -0.4992 +vn -0.1330 -0.8581 -0.4959 +vn -0.1677 -0.8518 -0.4963 +vn -0.1480 -0.8558 -0.4957 +vn -0.0659 -0.8655 -0.4966 +vn -0.0800 -0.8623 -0.5000 +vn -0.0877 -0.8619 -0.4994 +vn -0.0942 -0.8633 -0.4957 +vn -0.1052 -0.8620 -0.4959 +vn -0.0450 0.8755 0.4810 +vn 0.1089 0.8639 0.4917 +vn 0.1014 0.8905 0.4436 +usemtl None +s off +f 767/747/1065 753/748/1065 778/749/1065 +f 748/750/1066 751/751/1066 754/752/1066 +f 753/748/1067 747/753/1067 755/754/1067 +f 750/755/1068 754/752/1068 758/756/1068 +f 754/752/1069 751/751/1069 758/756/1069 +f 751/751/1066 748/750/1066 759/757/1066 +f 749/758/1070 748/750/1070 760/759/1070 +f 754/752/1071 750/755/1071 760/759/1071 +f 753/748/1067 755/754/1067 760/759/1067 +f 750/755/1072 758/756/1072 760/759/1072 +f 758/756/1073 753/748/1073 760/759/1073 +f 748/750/1074 749/758/1074 761/760/1074 +f 749/758/1075 757/761/1075 761/760/1075 +f 759/757/1066 748/750/1066 761/760/1066 +f 747/753/1067 753/748/1067 762/762/1067 +f 753/748/1076 759/757/1076 762/762/1076 +f 759/757/1077 756/763/1077 762/762/1077 +f 757/761/1078 763/764/1078 764/765/1078 +f 751/751/1066 759/757/1066 767/747/1066 +f 759/757/1076 753/748/1076 767/747/1076 +f 748/750/1066 754/752/1066 768/766/1066 +f 760/759/1070 748/750/1070 768/766/1070 +f 754/752/1079 760/759/1079 768/766/1079 +f 747/753/1080 762/762/1080 769/767/1080 +f 762/762/1081 756/763/1081 769/767/1081 +f 765/768/1082 747/753/1082 769/767/1082 +f 761/760/1083 757/761/1083 770/769/1083 +f 759/757/1066 761/760/1066 770/769/1066 +f 757/761/1084 764/765/1084 770/769/1084 +f 764/765/1085 752/770/1085 770/769/1085 +f 749/758/1070 760/759/1070 772/771/1070 +f 760/759/1067 755/754/1067 772/771/1067 +f 766/772/1086 749/758/1086 772/771/1086 +f 755/754/1087 766/772/1087 772/771/1087 +f 757/761/1088 749/758/1088 773/773/1088 +f 763/764/1089 757/761/1089 773/773/1089 +f 749/758/1090 766/772/1090 773/773/1090 +f 766/772/1091 771/774/1091 773/773/1091 +f 755/754/1067 747/753/1067 774/775/1067 +f 747/753/1092 765/768/1092 774/775/1092 +f 766/772/1093 755/754/1093 774/775/1093 +f 756/763/1094 759/757/1094 775/776/1094 +f 752/770/1095 764/765/1095 775/776/1095 +f 764/765/1096 756/763/1096 775/776/1096 +f 770/769/1097 752/770/1097 775/776/1097 +f 759/757/1066 770/769/1066 775/776/1066 +f 769/767/1098 756/763/1098 776/777/1098 +f 765/768/1099 769/767/1099 776/777/1099 +f 756/763/1100 771/774/1100 776/777/1100 +f 771/774/1101 766/772/1101 776/777/1101 +f 774/775/1102 765/768/1102 776/777/1102 +f 766/772/1103 774/775/1103 776/777/1103 +f 764/765/1104 763/764/1104 777/778/1104 +f 756/763/1105 764/765/1105 777/778/1105 +f 771/774/1106 756/763/1106 777/778/1106 +f 763/764/1107 773/773/1107 777/778/1107 +f 773/773/1108 771/774/1108 777/778/1108 +f 753/748/1109 758/756/1109 778/749/1109 +f 758/756/1110 751/751/1110 778/749/1110 +f 751/751/1111 767/747/1111 778/749/1111 +o Bowl_hull_24 +v -0.038377 0.028020 -0.013569 +v -0.009063 0.039229 -0.018312 +v -0.009063 0.039229 -0.018744 +v -0.039671 0.006898 -0.018312 +v -0.039671 0.039229 0.008847 +v -0.023292 0.037936 -0.018744 +v -0.040103 0.039659 0.002376 +v -0.040103 0.018973 -0.018744 +v -0.030186 0.032763 -0.018744 +v -0.020703 0.039662 -0.018312 +v -0.040103 0.006898 -0.018744 +v -0.040103 0.039659 0.008847 +v -0.009063 0.039662 -0.018312 +v -0.032774 0.039659 -0.006671 +v -0.040103 0.034918 -0.003660 +v -0.034928 0.027590 -0.018744 +v -0.040103 0.025435 -0.013569 +v -0.037945 0.039659 -0.000641 +v -0.032774 0.030175 -0.018744 +v -0.037945 0.023280 -0.018744 +v -0.027597 0.036211 -0.017018 +v -0.025443 0.039229 -0.014863 +vt 0.052663 0.541601 +vt 0.105325 0.402897 +vt 0.013215 0.472298 +vt 0.013215 1.000000 +vt 0.013215 1.000000 +vt 1.000000 0.013900 +vt 0.013215 0.013900 +vt 0.631461 0.000000 +vt 0.210552 0.319499 +vt 0.000000 0.625000 +vt 1.000000 0.000000 +vt 0.000098 0.000000 +vt 0.000098 0.000000 +vt 0.000000 1.000000 +vt 0.144773 0.000000 +vt 0.368442 0.166699 +vt 0.355325 0.055599 +vt 0.434221 0.000000 +vt 0.000098 0.069499 +vt 0.000098 0.236100 +vt 0.289546 0.236100 +vt 0.500000 0.069499 +vn -0.4880 0.7105 -0.5071 +vn 0.7262 -0.6875 0.0000 +vn 0.5620 -0.5320 0.6333 +vn 0.0000 0.0000 -1.0000 +vn -0.0253 0.2784 -0.9601 +vn 0.5854 -0.5620 -0.5844 +vn -1.0000 -0.0000 0.0000 +vn -0.5395 -0.5416 0.6447 +vn -0.0002 1.0000 0.0000 +vn -0.6081 -0.5114 0.6072 +vn 1.0000 0.0000 0.0000 +vn 0.6637 0.0000 0.7480 +vn 0.0000 0.7064 -0.7078 +vn 0.5493 0.5515 0.6278 +vn 0.0000 1.0000 0.0001 +vn -0.6770 0.5435 -0.4963 +vn -0.7344 0.4903 -0.4692 +vn -0.0007 1.0000 -0.0005 +vn -0.5771 0.6497 -0.4948 +vn -0.0015 1.0000 -0.0013 +vn -0.6537 0.5952 -0.4674 +vn -0.6284 0.6008 -0.4942 +vn -0.6661 0.5551 -0.4982 +vn -0.6136 0.6137 -0.4968 +vn -0.7045 0.4931 -0.5104 +vn -0.7804 0.3908 -0.4881 +vn -0.7201 0.4807 -0.5004 +vn -0.4923 0.6560 -0.5721 +vn -0.5542 0.6660 -0.4992 +vn -0.5054 0.7105 -0.4896 +vn -0.4256 0.7611 -0.4894 +vn -0.3275 0.8818 -0.3394 +usemtl None +s off +f 784/779/1112 799/780/1112 800/781/1112 +f 781/782/1113 780/783/1113 782/784/1113 +f 782/784/1114 780/783/1114 783/785/1114 +f 784/779/1115 781/782/1115 786/786/1115 +f 784/779/1115 786/786/1115 787/787/1115 +f 781/782/1116 784/779/1116 788/788/1116 +f 781/782/1117 782/784/1117 789/789/1117 +f 786/786/1115 781/782/1115 789/789/1115 +f 785/790/1118 786/786/1118 789/789/1118 +f 782/784/1119 783/785/1119 790/791/1119 +f 788/788/1120 785/790/1120 790/791/1120 +f 789/789/1121 782/784/1121 790/791/1121 +f 785/790/1118 789/789/1118 790/791/1118 +f 780/783/1122 781/782/1122 791/792/1122 +f 783/785/1123 780/783/1123 791/792/1123 +f 781/782/1124 788/788/1124 791/792/1124 +f 790/791/1125 783/785/1125 791/792/1125 +f 788/788/1126 790/791/1126 791/792/1126 +f 786/786/1118 785/790/1118 793/793/1118 +f 787/787/1115 786/786/1115 794/794/1115 +f 779/795/1127 793/793/1127 794/794/1127 +f 793/793/1128 779/795/1128 795/796/1128 +f 786/786/1118 793/793/1118 795/796/1118 +f 785/790/1129 788/788/1129 796/797/1129 +f 792/798/1130 787/787/1130 796/797/1130 +f 788/788/1131 792/798/1131 796/797/1131 +f 793/793/1132 785/790/1132 796/797/1132 +f 793/793/1133 796/797/1133 797/799/1133 +f 787/787/1115 794/794/1115 797/799/1115 +f 794/794/1134 793/793/1134 797/799/1134 +f 796/797/1135 787/787/1135 797/799/1135 +f 779/795/1136 794/794/1136 798/800/1136 +f 794/794/1115 786/786/1115 798/800/1115 +f 786/786/1137 795/796/1137 798/800/1137 +f 795/796/1138 779/795/1138 798/800/1138 +f 784/779/1139 787/787/1139 799/780/1139 +f 787/787/1140 792/798/1140 799/780/1140 +f 799/780/1141 792/798/1141 800/781/1141 +f 788/788/1142 784/779/1142 800/781/1142 +f 792/798/1143 788/788/1143 800/781/1143 +o Bowl_hull_25 +v 0.012492 0.077167 0.040309 +v 0.013355 0.040094 -0.015285 +v 0.013355 0.040959 -0.013565 +v -0.001301 0.040094 -0.018742 +v -0.001301 0.078462 0.048507 +v -0.001301 0.041394 -0.023904 +v -0.001301 0.082771 0.048507 +v 0.013355 0.078458 0.050235 +v 0.013355 0.040529 -0.021755 +v 0.006026 0.040529 -0.024775 +v 0.013355 0.082336 0.049799 +v 0.004301 0.083201 0.049371 +v -0.001301 0.083201 0.050235 +v 0.012923 0.076302 0.046778 +v 0.012923 0.053032 -0.001062 +v -0.001301 0.040094 -0.025211 +v 0.003439 0.041820 -0.023047 +v 0.009042 0.080619 0.045486 +v 0.012923 0.040959 -0.013565 +v -0.001301 0.079754 0.050235 +v -0.001301 0.042250 -0.014850 +v 0.013355 0.040094 -0.021755 +v 0.002577 0.067254 0.021337 +v 0.008611 0.043115 -0.019598 +v 0.013355 0.076302 0.039017 +v 0.013355 0.082336 0.050235 +v 0.010336 0.040959 -0.022619 +v 0.006456 0.043976 -0.018742 +vt 0.868442 0.139990 +vt 0.851312 0.160059 +vt 0.085748 0.909936 +vt 0.085748 1.000000 +vt 0.977095 0.109936 +vt 0.017326 0.969848 +vt 0.977095 0.009985 +vt 0.154366 0.979931 +vt 0.131558 1.000000 +vt 1.000000 0.110034 +vt 0.045810 0.989917 +vt 0.994225 0.020069 +vt 1.000000 0.000000 +vt 0.988547 0.000000 +vt 0.954190 0.160059 +vt 0.000000 1.000000 +vt 0.005775 0.989917 +vt 0.028681 0.959961 +vt 0.937060 0.059912 +vt 0.154366 0.979931 +vt 1.000000 0.079980 +vt 0.137334 0.949975 +vt 0.045810 1.000000 +vt 0.616973 0.369946 +vt 0.320086 0.699853 +vt 0.074393 0.929907 +vt 1.000000 0.020069 +vt 0.034358 0.979931 +vn 0.1200 0.8602 -0.4957 +vn -1.0000 0.0000 0.0000 +vn 1.0000 -0.0000 0.0000 +vn -0.0372 0.9697 -0.2415 +vn 0.2421 -0.8365 0.4917 +vn -0.0632 -0.8431 0.5340 +vn 0.0000 -1.0000 0.0000 +vn -0.0001 0.7091 -0.7051 +vn 0.0292 0.8212 -0.5700 +vn 0.0657 0.8660 -0.4957 +vn 0.1393 0.8642 -0.4834 +vn 0.1060 0.8828 -0.4576 +vn 0.0000 -0.8934 0.4492 +vn -0.1006 -0.8988 0.4266 +vn 0.0000 -0.8629 0.5054 +vn -0.0695 -0.8608 0.5042 +vn -0.0706 -0.7991 0.5971 +vn 0.0000 0.0000 1.0000 +vn -0.1223 -0.8681 0.4810 +vn -0.1227 -0.8616 0.4925 +vn 0.3810 0.0000 -0.9246 +vn 0.0750 -0.9451 -0.3179 +vn -0.0019 0.8682 -0.4961 +vn 0.0096 0.8689 -0.4949 +vn 0.0118 0.8677 -0.4970 +vn 0.0447 0.8671 -0.4960 +vn 0.1748 0.8507 -0.4958 +vn 0.1420 0.8638 -0.4834 +vn 0.5418 0.7243 -0.4264 +vn 0.0951 0.9955 0.0000 +vn 0.0550 0.9325 0.3569 +vn 0.2952 0.6324 -0.7162 +vn 0.2600 0.8288 -0.4954 +vn 0.1692 0.8453 -0.5069 +vn 0.1886 0.8470 -0.4970 +vn 0.0966 0.8612 -0.4990 +vn 0.0910 0.8634 -0.4962 +vn 0.1172 0.8606 -0.4957 +vn 0.1433 0.8549 -0.4987 +vn 0.1446 0.8560 -0.4963 +usemtl None +s off +f 801/801/1144 825/802/1144 828/803/1144 +f 804/804/1145 805/805/1145 806/806/1145 +f 806/806/1145 805/805/1145 807/807/1145 +f 803/808/1146 802/809/1146 808/810/1146 +f 808/810/1146 802/809/1146 809/811/1146 +f 808/810/1146 809/811/1146 811/812/1146 +f 807/807/1145 805/805/1145 813/813/1145 +f 812/814/1147 807/807/1147 813/813/1147 +f 803/808/1148 808/810/1148 814/815/1148 +f 808/810/1149 805/805/1149 814/815/1149 +f 802/809/1150 804/804/1150 816/816/1150 +f 804/804/1145 806/806/1145 816/816/1145 +f 806/806/1151 810/817/1151 816/816/1151 +f 810/817/1152 806/806/1152 817/818/1152 +f 817/818/1153 812/814/1153 818/819/1153 +f 811/812/1154 801/801/1154 818/819/1154 +f 812/814/1155 811/812/1155 818/819/1155 +f 802/809/1156 803/808/1156 819/820/1156 +f 804/804/1157 802/809/1157 819/820/1157 +f 803/808/1158 814/815/1158 819/820/1158 +f 814/815/1159 805/805/1159 819/820/1159 +f 805/805/1160 808/810/1160 820/821/1160 +f 813/813/1145 805/805/1145 820/821/1145 +f 808/810/1161 813/813/1161 820/821/1161 +f 805/805/1145 804/804/1145 821/822/1145 +f 804/804/1162 819/820/1162 821/822/1162 +f 819/820/1163 805/805/1163 821/822/1163 +f 809/811/1146 802/809/1146 822/823/1146 +f 810/817/1164 809/811/1164 822/823/1164 +f 802/809/1150 816/816/1150 822/823/1150 +f 816/816/1165 810/817/1165 822/823/1165 +f 806/806/1166 807/807/1166 823/824/1166 +f 807/807/1167 812/814/1167 823/824/1167 +f 817/818/1168 806/806/1168 823/824/1168 +f 812/814/1169 817/818/1169 823/824/1169 +f 815/825/1170 824/826/1170 825/802/1170 +f 801/801/1171 811/812/1171 825/802/1171 +f 811/812/1146 809/811/1146 825/802/1146 +f 809/811/1172 815/825/1172 825/802/1172 +f 808/810/1146 811/812/1146 826/827/1146 +f 811/812/1173 812/814/1173 826/827/1173 +f 812/814/1174 813/813/1174 826/827/1174 +f 813/813/1161 808/810/1161 826/827/1161 +f 809/811/1175 810/817/1175 827/828/1175 +f 815/825/1176 809/811/1176 827/828/1176 +f 810/817/1177 824/826/1177 827/828/1177 +f 824/826/1178 815/825/1178 827/828/1178 +f 810/817/1179 817/818/1179 828/803/1179 +f 817/818/1180 818/819/1180 828/803/1180 +f 818/819/1181 801/801/1181 828/803/1181 +f 824/826/1182 810/817/1182 828/803/1182 +f 825/802/1183 824/826/1183 828/803/1183 +o Bowl_hull_26 +v 0.013787 0.064667 0.019187 +v 0.025857 0.040094 -0.005807 +v 0.025857 0.040532 -0.004939 +v 0.025857 0.078461 0.048077 +v 0.013356 0.078032 0.049800 +v 0.013356 0.040528 -0.021331 +v 0.025857 0.040962 -0.011846 +v 0.013356 0.040528 -0.013996 +v 0.025857 0.075011 0.049800 +v 0.013356 0.081912 0.048939 +v 0.016803 0.040958 -0.019173 +v 0.024994 0.040094 -0.005807 +v 0.025857 0.059067 0.016175 +v 0.022838 0.080181 0.049366 +v 0.014217 0.045268 -0.013569 +v 0.024563 0.075440 0.050235 +v 0.015943 0.081912 0.050235 +v 0.022838 0.040528 -0.015292 +v 0.014217 0.040094 -0.021331 +v 0.025857 0.079325 0.050235 +v 0.018961 0.080181 0.047643 +v 0.025857 0.069403 0.032988 +v 0.025857 0.040094 -0.012273 +v 0.013356 0.040094 -0.014858 +v 0.013356 0.078461 0.050235 +v 0.013787 0.054323 0.001520 +v 0.022838 0.074577 0.039881 +v 0.015080 0.081478 0.048504 +v 0.025425 0.050016 0.001527 +v 0.013356 0.076738 0.047643 +v 0.014217 0.041387 -0.020035 +v 0.013356 0.048719 -0.007965 +v 0.019821 0.040962 -0.017009 +vt 0.319401 0.762725 +vt 0.084377 0.989624 +vt 0.060395 0.979248 +vt 0.229052 0.989526 +vt 0.216915 1.000000 +vt 0.969851 0.082518 +vt 0.132537 0.979248 +vt 0.993931 0.092796 +vt 0.000000 0.989624 +vt 0.102486 0.989624 +vt 0.993931 0.165035 +vt 0.981891 0.000000 +vt 0.216915 1.000000 +vt 0.524080 0.546300 +vt 1.000000 0.154757 +vt 0.030149 0.979346 +vt 0.000000 1.000000 +vt 1.000000 0.061864 +vt 0.987862 0.041406 +vt 1.000000 0.000000 +vt 0.759006 0.299139 +vt 0.126566 1.000000 +vt 0.090446 1.000000 +vt 1.000000 0.082518 +vt 0.566171 0.412392 +vt 0.963782 0.041406 +vt 0.319303 0.659749 +vt 0.855325 0.175411 +vt 0.108457 0.876272 +vt 0.975822 0.010376 +vt 0.963782 0.123727 +vt 0.018109 0.969068 +vt 0.186766 0.793755 +vn 0.3939 0.7733 -0.4968 +vn 1.0000 0.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0000 -0.8929 0.4502 +vn -0.1017 -0.8418 0.5302 +vn -0.1063 -0.8414 0.5299 +vn -0.2115 -0.8274 0.5202 +vn 0.3349 0.6650 -0.6676 +vn 0.0000 -1.0000 0.0000 +vn 0.5220 0.3641 -0.7713 +vn 0.3470 0.8707 -0.3485 +vn 0.2880 -0.0959 0.9528 +vn 0.2518 0.9649 0.0752 +vn 0.0000 0.0000 1.0000 +vn 0.3226 0.8064 -0.4957 +vn 0.6928 0.3186 -0.6470 +vn 0.3897 -0.7729 -0.5007 +vn -0.3302 -0.8431 0.4245 +vn -0.4490 -0.8915 -0.0598 +vn -0.1882 -0.6981 0.6908 +vn -0.4246 0.3183 0.8476 +vn 0.1878 0.8476 -0.4963 +vn 0.2203 0.8401 -0.4957 +vn 0.2635 0.8305 -0.4907 +vn 0.2822 0.8225 -0.4938 +vn 0.2283 0.8377 -0.4962 +vn 0.2234 0.8392 -0.4958 +vn 0.0914 0.8621 -0.4984 +vn 0.1911 0.9254 -0.3274 +vn 0.1568 0.9367 -0.3131 +vn 0.1745 0.8508 -0.4956 +vn 0.1955 0.8766 -0.4398 +vn 0.6270 0.6543 -0.4228 +vn 0.4522 0.7452 -0.4900 +vn -1.0000 0.0001 0.0000 +vn -0.3211 -0.8123 0.4870 +vn -0.3622 -0.8037 0.4721 +vn 0.3327 0.6688 -0.6648 +vn 0.3007 0.8144 -0.4963 +vn 0.2781 0.8227 -0.4958 +vn 0.2656 0.8266 -0.4961 +vn -0.2139 0.8438 -0.4922 +vn -0.1005 0.8586 -0.5027 +vn 0.1069 0.8539 -0.5093 +vn -0.0646 0.8509 -0.5214 +vn 0.0866 0.8542 -0.5127 +vn 0.3552 0.7919 -0.4967 +vn 0.4478 0.6390 -0.6255 +vn 0.3721 0.7847 -0.4958 +usemtl None +s off +f 857/829/1184 846/830/1184 861/831/1184 +f 831/832/1185 830/833/1185 832/834/1185 +f 832/834/1185 830/833/1185 835/835/1185 +f 833/836/1186 834/837/1186 836/838/1186 +f 831/832/1185 832/834/1185 837/839/1185 +f 834/837/1186 833/836/1186 838/840/1186 +f 830/833/1187 831/832/1187 840/841/1187 +f 832/834/1185 835/835/1185 841/842/1185 +f 831/832/1188 837/839/1188 844/843/1188 +f 840/841/1189 831/832/1189 844/843/1189 +f 833/836/1190 840/841/1190 844/843/1190 +f 834/837/1191 839/844/1191 847/845/1191 +f 830/833/1192 840/841/1192 847/845/1192 +f 839/844/1193 846/830/1193 847/845/1193 +f 837/839/1185 832/834/1185 848/846/1185 +f 832/834/1194 842/847/1194 848/846/1194 +f 844/843/1195 837/839/1195 848/846/1195 +f 842/847/1196 845/848/1196 848/846/1196 +f 845/848/1197 844/843/1197 848/846/1197 +f 832/834/1185 841/842/1185 850/849/1185 +f 841/842/1198 839/844/1198 850/849/1198 +f 835/835/1185 830/833/1185 851/850/1185 +f 846/830/1199 835/835/1199 851/850/1199 +f 830/833/1192 847/845/1192 851/850/1192 +f 847/845/1200 846/830/1200 851/850/1200 +f 836/838/1186 834/837/1186 852/851/1186 +f 840/841/1201 836/838/1201 852/851/1201 +f 834/837/1202 847/845/1202 852/851/1202 +f 847/845/1192 840/841/1192 852/851/1192 +f 838/840/1186 833/836/1186 853/852/1186 +f 833/836/1203 844/843/1203 853/852/1203 +f 844/843/1197 845/848/1197 853/852/1197 +f 845/848/1204 838/840/1204 853/852/1204 +f 829/853/1205 849/854/1205 854/855/1205 +f 849/854/1206 842/847/1206 854/855/1206 +f 842/847/1207 832/834/1207 855/856/1207 +f 832/834/1208 850/849/1208 855/856/1208 +f 843/857/1209 854/855/1209 855/856/1209 +f 854/855/1210 842/847/1210 855/856/1210 +f 829/853/1211 838/840/1211 856/858/1211 +f 845/848/1212 842/847/1212 856/858/1212 +f 838/840/1213 845/848/1213 856/858/1213 +f 849/854/1214 829/853/1214 856/858/1214 +f 842/847/1215 849/854/1215 856/858/1215 +f 841/842/1216 835/835/1216 857/829/1216 +f 835/835/1217 846/830/1217 857/829/1217 +f 833/836/1218 836/838/1218 858/859/1218 +f 840/841/1219 833/836/1219 858/859/1219 +f 836/838/1220 840/841/1220 858/859/1220 +f 839/844/1221 834/837/1221 859/860/1221 +f 850/849/1222 839/844/1222 859/860/1222 +f 855/856/1223 850/849/1223 859/860/1223 +f 843/857/1224 855/856/1224 859/860/1224 +f 838/840/1225 829/853/1225 860/861/1225 +f 834/837/1186 838/840/1186 860/861/1186 +f 829/853/1226 854/855/1226 860/861/1226 +f 854/855/1227 843/857/1227 860/861/1227 +f 859/860/1228 834/837/1228 860/861/1228 +f 843/857/1229 859/860/1229 860/861/1229 +f 839/844/1230 841/842/1230 861/831/1230 +f 846/830/1231 839/844/1231 861/831/1231 +f 841/842/1232 857/829/1232 861/831/1232 +o Bowl_hull_27 +v 0.027151 0.046562 -0.002360 +v 0.043964 0.040094 0.014886 +v 0.043531 0.040094 0.014886 +v 0.025857 0.078894 0.050235 +v 0.043964 0.070269 0.048503 +v 0.025857 0.075013 0.050235 +v 0.025857 0.040094 -0.005374 +v 0.043964 0.040531 0.007989 +v 0.043531 0.066387 0.050235 +v 0.026289 0.040960 -0.011415 +v 0.030600 0.077599 0.049372 +v 0.043531 0.053463 0.023934 +v 0.025857 0.062077 0.021345 +v 0.038360 0.073288 0.048071 +v 0.034049 0.040527 -0.004080 +v 0.043964 0.070698 0.050235 +v 0.025857 0.040094 -0.011846 +v 0.026289 0.055620 0.011009 +v 0.040945 0.058203 0.027811 +v 0.026720 0.078461 0.048509 +v 0.025857 0.040531 -0.004511 +v 0.042668 0.040094 0.014029 +v 0.043964 0.066387 0.050235 +v 0.043964 0.040094 0.007989 +v 0.042238 0.069407 0.045489 +v 0.028014 0.041389 -0.009257 +v 0.043964 0.047857 0.017043 +v 0.034480 0.075442 0.048509 +v 0.040084 0.073288 0.050235 +v 0.026289 0.062077 0.021345 +v 0.043964 0.062077 0.036434 +v 0.033188 0.043117 -0.001497 +v 0.026289 0.049581 0.001523 +v 0.025857 0.078028 0.047646 +v 0.040084 0.041389 0.004112 +v 0.025857 0.049581 0.001523 +vt 0.368148 0.599843 +vt 0.215348 0.755482 +vt 0.215348 0.755482 +vt 1.000000 0.100039 +vt 1.000000 0.000000 +vt 0.104248 1.000000 +vt 0.430599 1.000000 +vt 0.430599 1.000000 +vt 0.972103 0.222298 +vt 0.319499 0.988743 +vt 1.000000 0.322337 +vt 0.534652 0.433438 +vt 1.000000 0.211237 +vt 0.000000 1.000000 +vt 0.006950 0.977682 +vt 0.125098 0.988841 +vt 0.986100 0.033379 +vt 0.972201 0.011159 +vt 0.118148 0.988743 +vt 0.416797 1.000000 +vt 1.000000 0.322337 +vt 0.319499 1.000000 +vt 0.152800 0.833301 +vt 0.965153 0.144479 +vt 0.923551 0.244518 +vt 0.638802 0.533281 +vt 0.041699 0.966621 +vt 0.465348 0.799922 +vt 0.576351 0.655442 +vt 0.972201 0.088978 +vt 1.000000 0.144479 +vt 0.534652 0.433438 +vt 0.777702 0.433438 +vt 0.166699 0.922083 +vt 0.958301 0.022318 +vt 0.257048 0.966621 +vn 0.0000 0.8436 -0.5370 +vn -1.0000 0.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn 1.0000 -0.0000 0.0000 +vn 0.0000 -0.8024 0.5968 +vn -0.3646 -0.7471 0.5557 +vn 0.0000 0.0000 1.0000 +vn 0.6874 0.0185 -0.7261 +vn 0.2409 0.9630 -0.1211 +vn -0.4622 -0.7912 0.4005 +vn -0.4798 -0.7322 0.4834 +vn -0.5206 -0.7224 0.4550 +vn 0.7727 0.0000 -0.6348 +vn 0.3468 -0.8829 -0.3166 +vn 0.4269 0.7563 -0.4957 +vn 0.4459 0.7600 -0.4728 +vn 0.4752 0.7271 -0.4956 +vn 0.4428 0.7430 -0.5018 +vn 0.5772 0.5784 -0.5765 +vn 0.4568 0.7382 -0.4965 +vn 0.5726 0.6532 -0.4954 +vn 0.3780 0.7818 -0.4958 +vn 0.3118 0.7912 0.5261 +vn 0.4627 0.8061 -0.3689 +vn 0.5438 0.8146 -0.2019 +vn 0.4182 0.8641 -0.2799 +vn 0.4267 0.8380 -0.3402 +vn 0.0000 0.8481 -0.5298 +vn 0.2921 0.8169 -0.4974 +vn 0.3354 0.8013 -0.4954 +vn 0.3495 0.7947 -0.4964 +vn 0.5260 0.6917 -0.4949 +vn 0.4935 0.7196 -0.4885 +vn 0.4822 0.7236 -0.4939 +vn 0.7176 0.5617 -0.4119 +vn 0.5444 0.6761 -0.4965 +vn 0.5256 0.6918 -0.4952 +vn 0.5102 0.7023 -0.4965 +vn 0.5307 0.6804 -0.5054 +vn 0.3850 0.7680 -0.5118 +vn 0.4229 0.7584 -0.4959 +vn 0.3826 0.7794 -0.4962 +vn -0.1566 0.9366 -0.3133 +vn 0.0000 0.8550 -0.5186 +vn 0.0878 0.8524 -0.5155 +vn 0.6553 0.5296 -0.5386 +vn 0.6250 0.6069 -0.4910 +vn 0.5822 0.6438 -0.4967 +vn -0.7260 0.5609 -0.3980 +vn -0.1151 0.8403 -0.5297 +vn 0.0000 0.8322 -0.5545 +usemtl None +s off +f 879/862/1233 894/863/1233 897/864/1233 +f 867/865/1234 865/866/1234 868/867/1234 +f 863/868/1235 864/869/1235 868/867/1235 +f 866/870/1236 863/868/1236 869/871/1236 +f 864/869/1237 863/868/1237 870/872/1237 +f 867/865/1238 864/869/1238 870/872/1238 +f 865/866/1239 867/865/1239 870/872/1239 +f 868/867/1234 865/866/1234 874/873/1234 +f 863/868/1236 866/870/1236 877/874/1236 +f 865/866/1239 870/872/1239 877/874/1239 +f 863/868/1235 868/867/1235 878/875/1235 +f 868/867/1234 874/873/1234 878/875/1234 +f 871/876/1240 876/877/1240 878/875/1240 +f 865/866/1241 872/878/1241 881/879/1241 +f 867/865/1234 868/867/1234 882/880/1234 +f 882/880/1242 868/867/1242 883/881/1242 +f 864/869/1243 867/865/1243 883/881/1243 +f 868/867/1235 864/869/1235 883/881/1235 +f 867/865/1244 882/880/1244 883/881/1244 +f 870/872/1237 863/868/1237 884/882/1237 +f 863/868/1236 877/874/1236 884/882/1236 +f 877/874/1239 870/872/1239 884/882/1239 +f 869/871/1236 863/868/1236 885/883/1236 +f 876/877/1245 869/871/1245 885/883/1245 +f 863/868/1235 878/875/1235 885/883/1235 +f 878/875/1246 876/877/1246 885/883/1246 +f 862/884/1247 875/885/1247 886/886/1247 +f 875/885/1248 866/870/1248 886/886/1248 +f 886/886/1249 880/887/1249 887/888/1249 +f 871/876/1250 862/884/1250 887/888/1250 +f 876/877/1251 871/876/1251 887/888/1251 +f 862/884/1252 886/886/1252 887/888/1252 +f 866/870/1236 869/871/1236 888/889/1236 +f 876/877/1253 873/890/1253 888/889/1253 +f 875/885/1254 879/862/1254 889/891/1254 +f 872/878/1255 865/866/1255 890/892/1255 +f 866/870/1256 875/885/1256 890/892/1256 +f 877/874/1257 866/870/1257 890/892/1257 +f 865/866/1239 877/874/1239 890/892/1239 +f 889/891/1258 872/878/1258 890/892/1258 +f 875/885/1259 889/891/1259 890/892/1259 +f 879/862/1260 874/873/1260 891/893/1260 +f 881/879/1261 872/878/1261 891/893/1261 +f 872/878/1262 889/891/1262 891/893/1262 +f 889/891/1263 879/862/1263 891/893/1263 +f 873/890/1264 880/887/1264 892/894/1264 +f 886/886/1265 866/870/1265 892/894/1265 +f 880/887/1266 886/886/1266 892/894/1266 +f 866/870/1236 888/889/1236 892/894/1236 +f 888/889/1267 873/890/1267 892/894/1267 +f 873/890/1268 876/877/1268 893/895/1268 +f 880/887/1269 873/890/1269 893/895/1269 +f 887/888/1270 880/887/1270 893/895/1270 +f 876/877/1271 887/888/1271 893/895/1271 +f 862/884/1272 871/876/1272 894/863/1272 +f 875/885/1273 862/884/1273 894/863/1273 +f 879/862/1274 875/885/1274 894/863/1274 +f 874/873/1234 865/866/1234 895/896/1234 +f 865/866/1275 881/879/1275 895/896/1275 +f 891/893/1276 874/873/1276 895/896/1276 +f 881/879/1277 891/893/1277 895/896/1277 +f 869/871/1278 876/877/1278 896/897/1278 +f 888/889/1279 869/871/1279 896/897/1279 +f 876/877/1280 888/889/1280 896/897/1280 +f 878/875/1234 874/873/1234 897/864/1234 +f 871/876/1281 878/875/1281 897/864/1281 +f 874/873/1282 879/862/1282 897/864/1282 +f 894/863/1283 871/876/1283 897/864/1283 +o Bowl_hull_28 +v 0.050000 0.056043 0.034706 +v 0.072849 0.040094 0.050235 +v 0.072849 0.040528 0.050235 +v 0.044396 0.040094 0.008851 +v 0.043964 0.065097 0.048934 +v 0.044396 0.040094 0.016180 +v 0.068537 0.040094 0.050235 +v 0.044396 0.070703 0.049801 +v 0.063363 0.054323 0.049372 +v 0.059051 0.040528 0.028682 +v 0.044396 0.042251 0.010573 +v 0.053450 0.064234 0.050235 +v 0.043964 0.055608 0.027823 +v 0.069829 0.045700 0.049372 +v 0.043964 0.066392 0.050235 +v 0.051725 0.065529 0.049372 +v 0.043964 0.040525 0.016180 +v 0.058618 0.059060 0.048938 +v 0.053020 0.040528 0.020057 +v 0.044396 0.055608 0.027823 +v 0.072416 0.040957 0.048938 +v 0.043964 0.070703 0.050235 +v 0.066812 0.050011 0.049372 +v 0.043964 0.040525 0.008851 +v 0.044396 0.065960 0.042468 +v 0.064225 0.053460 0.050235 +v 0.045691 0.040525 0.010148 +v 0.065517 0.040094 0.038162 +v 0.044396 0.049151 0.019198 +v 0.053020 0.052169 0.033422 +v 0.047413 0.068114 0.048509 +v 0.054312 0.060786 0.045920 +vt 0.593735 0.605521 +vt 0.250024 0.704092 +vt 0.895742 0.324002 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 0.177092 1.000000 +vt 1.000000 0.985807 +vt 1.000000 1.000000 +vt 1.000000 0.211335 +vt 0.968576 0.183144 +vt 1.000000 0.140857 +vt 0.458443 0.493148 +vt 0.989525 0.000000 +vt 0.979148 0.169049 +vt 0.177092 0.985905 +vt 0.979148 0.535141 +vt 0.968673 0.380384 +vt 0.624767 0.478955 +vt 0.458443 0.493148 +vt 0.968673 0.971809 +vt 0.979148 0.816856 +vt 0.479197 0.985807 +vt 1.000000 0.000000 +vt 0.979148 0.675998 +vt 0.270778 0.985807 +vt 0.000000 0.985905 +vt 0.812335 0.154953 +vt 1.000000 0.563332 +vt 0.031326 0.985905 +vt 0.041605 0.929522 +vt 0.708272 1.000000 +vt 0.958297 0.084573 +vn 0.5978 0.6298 -0.4960 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn -0.6043 -0.5647 0.5621 +vn -1.0000 -0.0000 0.0000 +vn 0.5781 0.8134 0.0646 +vn -0.7062 -0.7080 -0.0000 +vn -0.6457 -0.6108 0.4582 +vn -0.6315 -0.6331 0.4476 +vn 0.7068 0.7074 -0.0056 +vn 0.6565 0.7156 -0.2388 +vn 0.5577 0.6655 -0.4961 +vn 0.9486 0.0000 -0.3165 +vn 0.8656 0.4839 -0.1289 +vn 0.7411 0.4498 -0.4985 +vn 0.4911 0.7202 0.4901 +vn 0.7118 0.4980 -0.4953 +vn 0.7091 0.5014 -0.4958 +vn 0.6785 0.5429 -0.4949 +vn 0.0000 0.8166 -0.5772 +vn -0.4780 0.7375 -0.4770 +vn -0.6831 0.6057 -0.4080 +vn 0.7071 0.7071 0.0005 +vn 0.7688 0.5127 0.3822 +vn 0.7716 0.6173 -0.1538 +vn 0.8084 0.5656 0.1630 +vn 0.6812 -0.5313 -0.5037 +vn 0.6706 0.5515 -0.4961 +vn 0.5143 0.5156 -0.6853 +vn 0.5038 0.5435 -0.6714 +vn 0.5665 -0.7158 -0.4082 +vn 0.7836 -0.2927 -0.5479 +vn 0.8064 -0.3315 -0.4897 +vn 0.8018 0.2669 -0.5347 +vn 0.5589 0.6638 -0.4969 +vn 0.0000 0.8005 -0.5993 +vn -0.5323 0.6610 -0.5288 +vn -0.5865 0.6340 -0.5040 +vn 0.6369 0.5927 -0.4930 +vn 0.6415 0.5859 -0.4951 +vn 0.6310 0.5959 -0.4968 +vn 0.6037 0.6225 -0.4980 +vn 0.5335 0.7823 -0.3216 +vn 0.5173 0.6969 -0.4968 +vn 0.4385 0.7546 -0.4881 +vn 0.4969 0.7087 -0.5009 +vn 0.5580 0.6653 -0.4960 +vn 0.5902 0.6601 -0.4647 +vn 0.5894 0.6375 -0.4963 +vn 0.5993 0.6288 -0.4955 +usemtl None +s off +f 927/898/1284 926/899/1284 929/900/1284 +f 901/901/1285 899/902/1285 903/903/1285 +f 899/902/1286 900/904/1286 904/905/1286 +f 903/903/1285 899/902/1285 904/905/1285 +f 904/905/1286 900/904/1286 909/906/1286 +f 902/907/1287 904/905/1287 912/908/1287 +f 904/905/1286 909/906/1286 912/908/1286 +f 910/909/1288 902/907/1288 912/908/1288 +f 905/910/1289 909/906/1289 913/911/1289 +f 901/901/1290 903/903/1290 914/912/1290 +f 904/905/1291 902/907/1291 914/912/1291 +f 903/903/1292 904/905/1292 914/912/1292 +f 902/907/1288 910/909/1288 914/912/1288 +f 909/906/1293 906/913/1293 915/914/1293 +f 913/911/1294 909/906/1294 915/914/1294 +f 913/911/1295 898/915/1295 917/916/1295 +f 900/904/1296 899/902/1296 918/917/1296 +f 911/918/1297 900/904/1297 918/917/1297 +f 907/919/1298 911/918/1298 918/917/1298 +f 909/906/1299 905/910/1299 919/920/1299 +f 912/908/1286 909/906/1286 919/920/1286 +f 910/909/1288 912/908/1288 919/920/1288 +f 911/918/1300 907/919/1300 920/921/1300 +f 907/919/1301 916/922/1301 920/921/1301 +f 916/922/1302 906/913/1302 920/921/1302 +f 901/901/1290 914/912/1290 921/923/1290 +f 914/912/1288 910/909/1288 921/923/1288 +f 917/916/1303 910/909/1303 922/924/1303 +f 919/920/1304 905/910/1304 922/924/1304 +f 910/909/1305 919/920/1305 922/924/1305 +f 909/906/1286 900/904/1286 923/925/1286 +f 906/913/1306 909/906/1306 923/925/1306 +f 900/904/1307 911/918/1307 923/925/1307 +f 920/921/1308 906/913/1308 923/925/1308 +f 911/918/1309 920/921/1309 923/925/1309 +f 916/922/1310 901/901/1310 924/926/1310 +f 906/913/1311 916/922/1311 924/926/1311 +f 901/901/1312 921/923/1312 924/926/1312 +f 921/923/1313 908/927/1313 924/926/1313 +f 899/902/1285 901/901/1285 925/928/1285 +f 901/901/1314 916/922/1314 925/928/1314 +f 916/922/1315 907/919/1315 925/928/1315 +f 918/917/1316 899/902/1316 925/928/1316 +f 907/919/1317 918/917/1317 925/928/1317 +f 917/916/1318 898/915/1318 926/899/1318 +f 910/909/1319 917/916/1319 926/899/1319 +f 908/927/1320 921/923/1320 926/899/1320 +f 921/923/1321 910/909/1321 926/899/1321 +f 915/914/1322 906/913/1322 927/898/1322 +f 906/913/1323 924/926/1323 927/898/1323 +f 924/926/1324 908/927/1324 927/898/1324 +f 908/927/1325 926/899/1325 927/898/1325 +f 905/910/1326 913/911/1326 928/929/1326 +f 913/911/1327 917/916/1327 928/929/1327 +f 922/924/1328 905/910/1328 928/929/1328 +f 917/916/1329 922/924/1329 928/929/1329 +f 898/915/1330 913/911/1330 929/900/1330 +f 913/911/1331 915/914/1331 929/900/1331 +f 926/899/1332 898/915/1332 929/900/1332 +f 915/914/1333 927/898/1333 929/900/1333 +o Bowl_hull_29 +v 0.020251 -0.046997 -0.007096 +v 0.006026 -0.083197 0.050235 +v 0.002577 -0.083197 0.050235 +v 0.021115 -0.075875 0.048935 +v 0.002577 -0.039667 -0.019173 +v 0.003440 -0.040532 -0.025204 +v 0.021115 -0.039667 -0.010542 +v 0.002577 -0.078888 0.049366 +v 0.021115 -0.080614 0.049366 +v 0.013354 -0.040097 -0.022612 +v 0.014216 -0.078893 0.043758 +v 0.021115 -0.039667 -0.017011 +v 0.020683 -0.040097 -0.009681 +v 0.004302 -0.083197 0.049366 +v 0.002577 -0.039667 -0.025642 +v 0.009476 -0.042684 -0.020027 +v 0.020251 -0.076732 0.050235 +v 0.009476 -0.082771 0.049366 +v 0.021115 -0.059067 0.013158 +v 0.005594 -0.040102 -0.025642 +v 0.002577 -0.083197 0.049366 +v 0.021115 -0.040528 -0.016588 +v 0.021115 -0.080614 0.050235 +v 0.003440 -0.079319 0.050235 +v 0.002577 -0.041824 -0.023050 +v 0.018095 -0.074580 0.037720 +v 0.020683 -0.067249 0.026512 +v 0.004302 -0.045706 -0.016157 +v 0.010770 -0.040097 -0.023904 +v 0.009044 -0.078888 0.042473 +v 0.010770 -0.039667 -0.023904 +v 0.016371 -0.081475 0.048935 +v 0.016803 -0.040958 -0.019165 +v 0.008182 -0.050445 -0.007104 +vt 0.897709 0.901018 +vt 0.000000 0.009986 +vt 0.244323 0.247601 +vt 0.085258 0.000000 +vt 1.000000 1.000000 +vt 0.988547 0.901018 +vt 0.199002 0.000000 +vt 0.982870 0.831799 +vt 0.988547 0.940670 +vt 0.113743 0.000000 +vt 0.210356 0.009889 +vt 1.000000 1.000000 +vt 0.988547 1.000000 +vt 0.000000 0.000000 +vt 1.000000 0.851478 +vt 0.988547 0.990210 +vt 0.511355 0.445663 +vt 0.005775 0.019875 +vt 0.988547 1.000000 +vt 0.039937 0.009889 +vt 0.119323 0.019777 +vt 0.244420 0.168396 +vt 1.000000 0.940670 +vt 1.000000 0.910907 +vt 0.034162 0.049540 +vt 0.687353 0.633640 +vt 0.835063 0.802036 +vt 0.125000 0.138731 +vt 0.074002 0.069317 +vt 0.022905 0.009889 +vt 0.914644 0.901116 +vt 0.022905 0.000000 +vt 0.982870 0.960446 +vt 0.085356 0.029665 +vn 0.1112 -0.8612 -0.4960 +vn -1.0000 -0.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.1829 0.8398 0.5112 +vn -0.1722 0.9130 0.3698 +vn -0.2331 0.8440 0.4830 +vn 0.0000 -1.0000 -0.0000 +vn 0.0000 -0.0000 1.0000 +vn -0.0617 0.8517 0.5203 +vn -0.1287 0.8465 0.5166 +vn 0.0810 -0.9837 -0.1608 +vn -0.0732 -0.5078 -0.8584 +vn 0.5578 -0.3663 -0.7448 +vn 0.4779 -0.7455 -0.4646 +vn 0.7653 0.1703 0.6208 +vn 0.1659 -0.9690 0.1832 +vn 0.1822 -0.9833 0.0000 +vn -0.6639 0.1479 0.7331 +vn -0.1281 0.8322 0.5395 +vn -0.4070 -0.7022 -0.5842 +vn 0.0000 -0.8683 -0.4961 +vn 0.2725 -0.8243 -0.4963 +vn 0.4242 -0.7782 -0.4631 +vn 0.2322 -0.8377 -0.4943 +vn 0.0707 -0.8630 -0.5003 +vn 0.0481 -0.8651 -0.4993 +vn 0.0308 -0.8675 -0.4964 +vn 0.1709 -0.8450 -0.5068 +vn 0.2009 -0.8445 -0.4964 +vn 0.2264 -0.8383 -0.4960 +vn 0.2484 -0.8316 -0.4967 +vn 0.1218 -0.8615 -0.4929 +vn 0.0714 -0.8671 -0.4929 +vn 0.0667 -0.8660 -0.4955 +vn 0.0990 -0.8626 -0.4962 +vn 0.4267 0.6386 -0.6404 +vn 0.1183 0.8215 -0.5578 +vn 0.4473 0.0000 -0.8944 +vn 0.3184 0.0000 -0.9480 +vn 0.1711 -0.8513 -0.4960 +vn 0.1820 -0.9824 -0.0410 +vn 0.1320 -0.8640 -0.4860 +vn 0.1985 -0.8482 -0.4910 +vn 0.1755 -0.8504 -0.4959 +vn 0.3178 -0.8085 -0.4953 +vn 0.2924 -0.8171 -0.4968 +vn 0.3759 -0.7813 -0.4983 +vn 0.4237 -0.6831 -0.5948 +vn 0.1607 -0.8532 -0.4963 +vn 0.1517 -0.8540 -0.4977 +vn 0.1224 -0.8599 -0.4955 +usemtl None +s off +f 959/930/1334 949/931/1334 963/932/1334 +f 934/933/1335 932/934/1335 937/935/1335 +f 936/936/1336 933/937/1336 938/938/1336 +f 934/933/1337 936/936/1337 941/939/1337 +f 936/936/1336 938/938/1336 941/939/1336 +f 933/937/1338 936/936/1338 942/940/1338 +f 936/936/1339 934/933/1339 942/940/1339 +f 934/933/1340 937/935/1340 942/940/1340 +f 931/941/1341 932/934/1341 943/942/1341 +f 932/934/1335 934/933/1335 944/943/1335 +f 934/933/1337 941/939/1337 944/943/1337 +f 932/934/1342 931/941/1342 946/944/1342 +f 933/937/1343 942/940/1343 946/944/1343 +f 942/940/1344 937/935/1344 946/944/1344 +f 931/941/1345 943/942/1345 947/945/1345 +f 941/939/1336 938/938/1336 948/946/1336 +f 935/947/1346 944/943/1346 949/931/1346 +f 943/942/1341 932/934/1341 950/948/1341 +f 932/934/1335 944/943/1335 950/948/1335 +f 939/949/1347 941/939/1347 951/950/1347 +f 948/946/1348 930/951/1348 951/950/1348 +f 941/939/1336 948/946/1336 951/950/1336 +f 938/938/1336 933/937/1336 952/952/1336 +f 946/944/1342 931/941/1342 952/952/1342 +f 933/937/1349 946/944/1349 952/952/1349 +f 931/941/1350 947/945/1350 952/952/1350 +f 947/945/1351 938/938/1351 952/952/1351 +f 937/935/1352 932/934/1352 953/953/1352 +f 932/934/1342 946/944/1342 953/953/1342 +f 946/944/1353 937/935/1353 953/953/1353 +f 944/943/1354 935/947/1354 954/954/1354 +f 943/942/1355 950/948/1355 954/954/1355 +f 950/948/1335 944/943/1335 954/954/1335 +f 939/949/1356 948/946/1356 956/955/1356 +f 948/946/1357 938/938/1357 956/955/1357 +f 938/938/1358 955/956/1358 956/955/1358 +f 935/947/1359 949/931/1359 957/957/1359 +f 954/954/1360 935/947/1360 957/957/1360 +f 943/942/1361 954/954/1361 957/957/1361 +f 945/958/1362 949/931/1362 958/959/1362 +f 955/956/1363 945/958/1363 958/959/1363 +f 956/955/1364 955/956/1364 958/959/1364 +f 939/949/1365 956/955/1365 958/959/1365 +f 940/960/1366 947/945/1366 959/930/1366 +f 947/945/1367 943/942/1367 959/930/1367 +f 943/942/1368 957/957/1368 959/930/1368 +f 957/957/1369 949/931/1369 959/930/1369 +f 941/939/1370 939/949/1370 960/961/1370 +f 944/943/1337 941/939/1337 960/961/1337 +f 949/931/1371 944/943/1371 960/961/1371 +f 939/949/1372 958/959/1372 960/961/1372 +f 958/959/1373 949/931/1373 960/961/1373 +f 940/960/1374 945/958/1374 961/962/1374 +f 938/938/1375 947/945/1375 961/962/1375 +f 947/945/1376 940/960/1376 961/962/1376 +f 955/956/1377 938/938/1377 961/962/1377 +f 945/958/1378 955/956/1378 961/962/1378 +f 930/951/1379 948/946/1379 962/963/1379 +f 948/946/1380 939/949/1380 962/963/1380 +f 951/950/1381 930/951/1381 962/963/1381 +f 939/949/1382 951/950/1382 962/963/1382 +f 945/958/1383 940/960/1383 963/932/1383 +f 949/931/1384 945/958/1384 963/932/1384 +f 940/960/1385 959/930/1385 963/932/1385 +o Bowl_hull_30 +v 0.036202 0.028019 -0.016586 +v 0.006457 0.040094 -0.018744 +v 0.006457 0.040094 -0.018309 +v 0.039221 0.009053 -0.018312 +v 0.039221 0.039662 0.008847 +v 0.020257 0.039659 -0.018744 +v 0.039653 0.040094 0.001944 +v 0.039653 0.020265 -0.018744 +v 0.030164 0.032762 -0.018744 +v 0.006457 0.039659 -0.018309 +v 0.039653 0.009053 -0.018744 +v 0.024991 0.040094 -0.013999 +v 0.039653 0.040094 0.008847 +v 0.039653 0.032762 -0.006671 +v 0.031458 0.040094 -0.007533 +v 0.033183 0.029745 -0.018744 +v 0.025852 0.036211 -0.018744 +v 0.018964 0.040094 -0.018744 +v 0.039221 0.025002 -0.015295 +v 0.006457 0.039659 -0.018744 +v 0.036202 0.025865 -0.018744 +vt 0.986981 0.486198 +vt 1.000000 0.638802 +vt 0.896045 0.458399 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 0.415720 0.013998 +vt 0.714174 0.236198 +vt 0.000000 0.013998 +vt 0.986981 1.000000 +vt 0.986981 0.013900 +vt 1.000000 1.000000 +vt 0.558340 0.000000 +vt 1.000000 0.000000 +vt 1.000000 0.236198 +vt 0.753132 0.000000 +vt 0.805110 0.333399 +vt 0.896045 0.388998 +vt 0.584280 0.125098 +vt 0.376762 0.000000 +vt 0.000000 0.013998 +vn 0.7255 0.4471 -0.5232 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.5269 -0.5641 0.6357 +vn -0.6381 0.0000 0.7699 +vn 1.0000 0.0000 0.0000 +vn 0.5523 -0.5533 0.6235 +vn -0.5347 0.5356 0.6536 +vn 0.5986 -0.5322 0.5987 +vn 0.5716 0.6550 -0.4943 +vn 0.6129 0.6132 -0.4984 +vn 0.6703 0.5511 -0.4969 +vn 0.6495 0.5791 -0.4928 +vn 0.4496 0.7295 -0.5154 +vn 0.5396 0.6747 -0.5035 +vn 0.4948 0.7144 -0.4948 +vn 0.2952 0.8788 -0.3750 +vn 0.7124 0.5036 -0.4888 +vn 0.8824 0.3269 -0.3384 +vn -0.6826 -0.7308 0.0000 +vn -0.5611 -0.6086 -0.5611 +vn 0.6729 0.5235 -0.5226 +vn 0.7104 0.4981 -0.4972 +usemtl None +s off +f 982/964/1386 971/965/1386 984/966/1386 +f 965/967/1387 966/968/1387 970/969/1387 +f 965/967/1388 969/970/1388 971/965/1388 +f 971/965/1388 969/970/1388 972/971/1388 +f 966/968/1389 965/967/1389 973/972/1389 +f 967/973/1390 968/974/1390 973/972/1390 +f 968/974/1391 966/968/1391 973/972/1391 +f 965/967/1388 971/965/1388 974/975/1388 +f 971/965/1392 970/969/1392 974/975/1392 +f 965/967/1387 970/969/1387 975/976/1387 +f 968/974/1393 967/973/1393 976/977/1393 +f 966/968/1394 968/974/1394 976/977/1394 +f 970/969/1387 966/968/1387 976/977/1387 +f 967/973/1395 974/975/1395 976/977/1395 +f 974/975/1392 970/969/1392 976/977/1392 +f 970/969/1392 971/965/1392 977/978/1392 +f 970/969/1396 972/971/1396 978/979/1396 +f 975/976/1387 970/969/1387 978/979/1387 +f 972/971/1397 970/969/1397 979/980/1397 +f 971/965/1388 972/971/1388 979/980/1388 +f 977/978/1398 964/981/1398 979/980/1398 +f 970/969/1399 977/978/1399 979/980/1399 +f 972/971/1388 969/970/1388 980/982/1388 +f 969/970/1400 975/976/1400 980/982/1400 +f 978/979/1401 972/971/1401 980/982/1401 +f 975/976/1402 978/979/1402 980/982/1402 +f 969/970/1388 965/967/1388 981/983/1388 +f 965/967/1387 975/976/1387 981/983/1387 +f 975/976/1403 969/970/1403 981/983/1403 +f 964/981/1404 977/978/1404 982/964/1404 +f 977/978/1405 971/965/1405 982/964/1405 +f 973/972/1389 965/967/1389 983/984/1389 +f 967/973/1406 973/972/1406 983/984/1406 +f 974/975/1407 967/973/1407 983/984/1407 +f 965/967/1388 974/975/1388 983/984/1388 +f 979/980/1408 964/981/1408 984/966/1408 +f 971/965/1388 979/980/1388 984/966/1388 +f 964/981/1409 982/964/1409 984/966/1409 +o Bowl_hull_31 +v 0.048278 0.040094 0.013159 +v 0.039653 0.019401 -0.018744 +v 0.039653 0.018969 -0.018744 +v 0.081036 0.018969 0.049370 +v 0.040086 0.039662 0.010141 +v 0.073278 0.040094 0.049796 +v 0.077159 0.018969 0.050228 +v 0.040086 0.018969 -0.010979 +v 0.068104 0.040094 0.049364 +v 0.077159 0.027594 0.046784 +v 0.040086 0.040094 0.002815 +v 0.040086 0.019401 -0.018744 +v 0.041379 0.028886 -0.008393 +v 0.076725 0.032761 0.049370 +v 0.068104 0.040094 0.041606 +v 0.055606 0.019831 0.006698 +v 0.039653 0.040094 0.009284 +v 0.068967 0.039232 0.050235 +v 0.080177 0.023280 0.050228 +v 0.073711 0.037507 0.048074 +v 0.076296 0.018969 0.048938 +v 0.058191 0.039662 0.026515 +v 0.040086 0.025005 -0.013997 +v 0.080177 0.021990 0.048938 +v 0.039653 0.037507 -0.000635 +v 0.040086 0.031469 -0.007529 +v 0.039653 0.018969 -0.011843 +v 0.068104 0.039662 0.049364 +v 0.073278 0.040094 0.050228 +v 0.069397 0.018969 0.029540 +v 0.040516 0.022850 -0.015294 +v 0.052588 0.021556 0.002815 +v 0.040086 0.037507 -0.000635 +v 0.067242 0.019831 0.026089 +v 0.053018 0.040094 0.019621 +v 0.051296 0.018969 -0.000635 +v 0.081036 0.018969 0.050228 +v 0.068967 0.034918 0.038587 +vt 0.050020 0.020852 +vt 0.874902 0.687518 +vt 0.831147 0.708370 +vt 0.000000 0.000000 +vt 0.987471 1.000000 +vt 0.999902 0.906314 +vt 0.112569 0.010475 +vt 0.993637 0.812531 +vt 0.462510 0.208419 +vt 0.987373 0.687518 +vt 0.312549 0.010475 +vt 0.000000 0.000000 +vt 0.000000 0.010475 +vt 0.406323 0.000000 +vt 0.418755 0.010475 +vt 0.987471 0.895840 +vt 0.968677 0.823005 +vt 0.981206 0.885463 +vt 0.656128 0.447969 +vt 0.068814 0.010475 +vt 0.150059 0.041703 +vt 0.949980 0.906314 +vt 0.981206 0.979246 +vt 0.999902 0.979246 +vt 0.262529 0.000000 +vt 0.162588 0.010475 +vt 0.100039 0.000000 +vt 0.987373 0.687518 +vt 1.000000 0.708370 +vt 0.999902 0.812531 +vt 0.699980 0.718747 +vt 0.312549 0.312580 +vt 0.368833 0.385511 +vt 0.262529 0.010475 +vt 0.649961 0.666667 +vt 0.556186 0.322956 +vt 0.262529 0.281351 +vt 0.999902 1.000000 +vn 0.7623 0.4162 -0.4957 +vn -0.0000 -1.0000 0.0000 +vn -0.0000 1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.7742 0.3139 0.5496 +vn 0.8173 0.4079 -0.4071 +vn 0.7571 0.4452 -0.4782 +vn -0.7685 -0.3807 0.5142 +vn -0.7569 -0.4668 0.4574 +vn 0.7346 0.4631 -0.4958 +vn 0.0000 0.6463 -0.7630 +vn 0.7265 0.4750 -0.4965 +vn 0.8511 0.2903 -0.4374 +vn 0.9433 0.2346 -0.2347 +vn 0.9042 0.3019 -0.3020 +vn -0.9665 0.2483 -0.0648 +vn -0.8137 0.4111 -0.4110 +vn -0.8115 0.4133 -0.4131 +vn 0.6853 0.5152 -0.5148 +vn -0.8128 -0.4161 0.4077 +vn -0.9032 -0.3036 0.3036 +vn -0.7723 -0.3149 0.5517 +vn -0.8137 0.0000 0.5813 +vn -0.7476 -0.3024 0.5913 +vn -0.7104 0.0000 0.7038 +vn 0.9050 0.4255 0.0000 +vn -0.1267 0.6393 0.7584 +vn 0.8362 0.3431 0.4279 +vn 0.0014 0.0006 1.0000 +vn 0.7442 0.4470 -0.4963 +vn 0.6847 0.4711 -0.5561 +vn 0.8091 0.3159 -0.4955 +vn 0.7957 0.3473 -0.4962 +vn 0.8127 0.3055 -0.4961 +vn 0.8134 0.2952 -0.5012 +vn 0.6038 0.6378 -0.4782 +vn 0.0000 0.8001 -0.5999 +vn 0.0000 0.7523 -0.6589 +vn 0.6572 0.5670 -0.4966 +vn 0.8266 0.2662 -0.4959 +vn 0.8303 0.2572 -0.4944 +vn 0.8505 0.1706 -0.4976 +vn 0.8552 0.1291 -0.5019 +vn 0.7034 0.5092 -0.4959 +vn 0.6300 0.6452 -0.4323 +vn 0.6752 0.5467 -0.4953 +vn 0.6984 0.5156 -0.4964 +vn 0.6429 -0.6448 -0.4134 +vn 0.8376 0.1846 -0.5141 +vn 0.8541 0.0883 -0.5125 +vn 0.8545 0.0848 -0.5126 +vn 0.0000 -0.0003 1.0000 +vn 0.9807 0.1954 0.0000 +vn 0.0008 0.0002 1.0000 +vn 0.7895 0.3619 -0.4957 +vn 0.7886 0.3659 -0.4942 +vn 0.7629 0.4158 -0.4950 +vn 0.7701 0.4007 -0.4964 +usemtl None +s off +f 1015/985/1410 999/986/1410 1022/987/1410 +f 987/988/1411 988/989/1411 991/990/1411 +f 987/988/1411 991/990/1411 992/991/1411 +f 990/992/1412 985/993/1412 993/994/1412 +f 993/994/1412 985/993/1412 995/995/1412 +f 987/988/1413 986/996/1413 996/997/1413 +f 985/993/1412 990/992/1412 999/986/1412 +f 986/996/1414 987/988/1414 1001/998/1414 +f 989/999/1415 993/994/1415 1001/998/1415 +f 993/994/1412 995/995/1412 1001/998/1412 +f 990/992/1416 998/1000/1416 1004/1001/1416 +f 999/986/1417 990/992/1417 1004/1001/1417 +f 991/990/1418 989/999/1418 1005/1002/1418 +f 989/999/1419 992/991/1419 1005/1002/1419 +f 992/991/1411 991/990/1411 1005/1002/1411 +f 1006/1003/1420 999/986/1420 1007/1004/1420 +f 996/997/1421 986/996/1421 1007/1004/1421 +f 997/1005/1422 1006/1003/1422 1007/1004/1422 +f 994/1006/1423 998/1000/1423 1008/1007/1423 +f 1003/1008/1424 988/989/1424 1008/1007/1424 +f 998/1000/1425 1003/1008/1425 1008/1007/1425 +f 986/996/1414 1001/998/1414 1009/1009/1414 +f 1001/998/1426 995/995/1426 1009/1009/1426 +f 1007/1004/1427 986/996/1427 1009/1009/1427 +f 1007/1004/1428 1009/1009/1428 1010/1010/1428 +f 997/1005/1429 1007/1004/1429 1010/1010/1429 +f 987/988/1411 992/991/1411 1011/1011/1411 +f 992/991/1430 989/999/1430 1011/1011/1430 +f 1001/998/1414 987/988/1414 1011/1011/1414 +f 989/999/1431 1001/998/1431 1011/1011/1431 +f 989/999/1432 991/990/1432 1012/1012/1432 +f 993/994/1433 989/999/1433 1012/1012/1433 +f 991/990/1434 1002/1013/1434 1012/1012/1434 +f 1002/1013/1435 993/994/1435 1012/1012/1435 +f 990/992/1412 993/994/1412 1013/1014/1412 +f 998/1000/1436 990/992/1436 1013/1014/1436 +f 993/994/1437 1002/1013/1437 1013/1014/1437 +f 1003/1008/1438 998/1000/1438 1013/1014/1438 +f 1002/1013/1439 1003/1008/1439 1013/1014/1439 +f 988/989/1411 987/988/1411 1014/1015/1411 +f 1007/1004/1440 999/986/1440 1015/985/1440 +f 996/997/1441 1007/1004/1441 1015/985/1441 +f 998/1000/1442 994/1006/1442 1016/1016/1442 +f 996/997/1443 998/1000/1443 1016/1016/1443 +f 994/1006/1444 1000/1017/1444 1016/1016/1444 +f 1000/1017/1445 996/997/1445 1016/1016/1445 +f 995/995/1446 985/993/1446 1017/1018/1446 +f 1009/1009/1447 995/995/1447 1017/1018/1447 +f 1010/1010/1448 1009/1009/1448 1017/1018/1448 +f 985/993/1449 1010/1010/1449 1017/1018/1449 +f 1000/1017/1450 994/1006/1450 1018/1019/1450 +f 994/1006/1451 1008/1007/1451 1018/1019/1451 +f 1008/1007/1452 988/989/1452 1018/1019/1452 +f 988/989/1453 1014/1015/1453 1018/1019/1453 +f 985/993/1412 999/986/1412 1019/1020/1412 +f 1006/1003/1454 997/1005/1454 1019/1020/1454 +f 999/986/1455 1006/1003/1455 1019/1020/1455 +f 1010/1010/1456 985/993/1456 1019/1020/1456 +f 997/1005/1457 1010/1010/1457 1019/1020/1457 +f 987/988/1458 996/997/1458 1020/1021/1458 +f 996/997/1459 1000/1017/1459 1020/1021/1459 +f 1014/1015/1411 987/988/1411 1020/1021/1411 +f 1000/1017/1460 1018/1019/1460 1020/1021/1460 +f 1018/1019/1461 1014/1015/1461 1020/1021/1461 +f 991/990/1411 988/989/1411 1021/1022/1411 +f 1002/1013/1462 991/990/1462 1021/1022/1462 +f 988/989/1463 1003/1008/1463 1021/1022/1463 +f 1003/1008/1464 1002/1013/1464 1021/1022/1464 +f 998/1000/1465 996/997/1465 1022/987/1465 +f 1004/1001/1466 998/1000/1466 1022/987/1466 +f 999/986/1467 1004/1001/1467 1022/987/1467 +f 996/997/1468 1015/985/1468 1022/987/1468 +o Bowl_hull_32 +v 0.043967 0.017242 -0.013996 +v 0.039654 0.005606 -0.025642 +v 0.039654 0.000433 -0.025642 +v 0.083196 0.004314 0.049366 +v 0.040084 0.018535 -0.011411 +v 0.078452 0.000433 0.048504 +v 0.081039 0.018969 0.049366 +v 0.077160 0.018969 0.050235 +v 0.040519 0.000433 -0.017873 +v 0.083196 0.000433 0.049366 +v 0.040084 0.018969 -0.018735 +v 0.040084 0.005606 -0.025642 +v 0.082330 0.012931 0.049366 +v 0.041380 0.000433 -0.023911 +v 0.041380 0.010775 -0.021757 +v 0.039654 0.018969 -0.012273 +v 0.065951 0.018969 0.023504 +v 0.079743 0.000433 0.050235 +v 0.082330 0.013794 0.050235 +v 0.076295 0.017242 0.040312 +v 0.039654 0.000433 -0.019604 +v 0.081900 0.008625 0.047643 +v 0.041811 0.003452 -0.023050 +v 0.077160 0.018535 0.050235 +v 0.040519 0.007761 -0.024342 +v 0.039654 0.018104 -0.012273 +v 0.040084 0.013363 -0.022619 +v 0.039654 0.018104 -0.019604 +v 0.083196 0.000433 0.050235 +v 0.051724 0.018969 -0.000204 +v 0.077591 0.003020 0.039450 +v 0.067673 0.011207 0.023504 +v 0.081039 0.018969 0.050235 +v 0.043537 0.006038 -0.019604 +v 0.081039 0.018535 0.048935 +v 0.082761 0.000433 0.048504 +vt 0.022807 0.039644 +vt 0.857870 0.871280 +vt 0.977193 0.990016 +vt 0.000000 0.000000 +vt 0.977193 0.891053 +vt 0.102388 0.019871 +vt 0.988547 1.000000 +vt 1.000000 0.861394 +vt 0.988547 0.950470 +vt 0.091034 0.009886 +vt 0.000000 0.000000 +vt 0.000000 0.009886 +vt 0.176194 0.000000 +vt 0.187549 0.009886 +vt 0.647709 0.603954 +vt 1.000000 0.920713 +vt 0.988547 0.980129 +vt 1.000000 0.980129 +vt 0.988547 1.000000 +vt 0.051194 0.039644 +vt 0.869225 0.841523 +vt 0.079581 0.000000 +vt 0.965838 0.970243 +vt 0.034162 0.049530 +vt 1.000000 0.861394 +vt 0.017130 0.019871 +vt 0.176194 0.000000 +vt 0.153485 0.099060 +vt 0.039839 0.009886 +vt 0.079581 0.000000 +vt 1.000000 1.000000 +vt 0.335258 0.277212 +vt 0.647709 0.643500 +vt 1.000000 0.950470 +vt 0.079581 0.089174 +vt 0.982870 0.950470 +vn 0.8682 -0.0013 -0.4961 +vn 0.0000 -1.0000 -0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.7068 -0.0588 -0.7050 +vn -1.0000 0.0000 0.0000 +vn -0.8452 0.1685 0.5072 +vn 0.9574 0.2048 -0.2035 +vn 0.9901 0.0994 -0.0988 +vn -0.0000 0.0000 1.0000 +vn 0.8414 0.2151 -0.4957 +vn 0.8906 0.0894 -0.4459 +vn 0.8441 0.0324 -0.5352 +vn 0.8662 0.0622 -0.4958 +vn -0.8518 -0.1097 0.5123 +vn -0.8569 0.0000 0.5154 +vn -0.7963 -0.1136 0.5942 +vn 0.8485 0.1833 -0.4964 +vn -0.8526 -0.1493 0.5008 +vn -0.8514 -0.1959 0.4866 +vn -0.8946 -0.0000 0.4470 +vn -0.8794 -0.1824 0.4397 +vn 0.7825 0.3546 -0.5119 +vn 0.0000 0.3631 -0.9317 +vn 0.8310 0.2508 -0.4965 +vn 0.7019 0.2587 -0.6637 +vn 0.8124 0.2281 -0.5366 +vn -0.8695 0.4906 -0.0579 +vn -0.8348 0.2395 -0.4958 +vn 0.4574 0.5064 -0.7310 +vn 1.0000 0.0000 0.0000 +vn 0.9588 0.0621 0.2773 +vn 0.7739 0.4061 -0.4861 +vn 0.8203 0.2833 -0.4968 +vn 0.8263 0.2670 -0.4959 +vn 0.8671 0.0457 -0.4961 +vn 0.8678 0.0180 -0.4967 +vn 0.8546 0.1572 -0.4949 +vn 0.8613 0.1122 -0.4956 +vn 0.8531 0.1621 -0.4959 +vn 0.9702 0.2421 0.0000 +vn 0.8618 0.0900 -0.4992 +vn 0.8641 0.0845 -0.4962 +vn 0.8570 0.1281 -0.4991 +vn 0.8613 0.1119 -0.4957 +vn 0.8573 0.1363 -0.4964 +vn 0.9569 0.2047 -0.2060 +vn 0.7724 0.4476 -0.4506 +vn 0.8548 0.1590 -0.4941 +vn 0.8411 0.2173 -0.4953 +vn 0.8928 0.0000 -0.4505 +vn 0.8698 0.0121 -0.4932 +usemtl None +s off +f 1036/1023/1469 1053/1024/1469 1058/1025/1469 +f 1025/1026/1470 1028/1027/1470 1031/1028/1470 +f 1028/1027/1470 1025/1026/1470 1032/1029/1470 +f 1030/1030/1471 1029/1031/1471 1033/1032/1471 +f 1025/1026/1472 1024/1033/1472 1034/1034/1472 +f 1032/1029/1470 1025/1026/1470 1036/1023/1470 +f 1025/1026/1473 1034/1034/1473 1036/1023/1473 +f 1024/1033/1474 1025/1026/1474 1038/1035/1474 +f 1027/1036/1475 1030/1030/1475 1038/1035/1475 +f 1030/1030/1471 1033/1032/1471 1038/1035/1471 +f 1033/1032/1471 1029/1031/1471 1039/1037/1471 +f 1028/1027/1470 1032/1029/1470 1040/1038/1470 +f 1035/1039/1476 1029/1031/1476 1041/1040/1476 +f 1026/1041/1477 1035/1039/1477 1041/1040/1477 +f 1030/1030/1478 1040/1038/1478 1041/1040/1478 +f 1037/1042/1479 1039/1037/1479 1042/1043/1479 +f 1025/1026/1470 1031/1028/1470 1043/1044/1470 +f 1038/1035/1474 1025/1026/1474 1043/1044/1474 +f 1035/1039/1480 1026/1041/1480 1044/1045/1480 +f 1036/1023/1481 1034/1034/1481 1045/1046/1481 +f 1044/1045/1482 1026/1041/1482 1045/1046/1482 +f 1027/1036/1483 1028/1027/1483 1046/1047/1483 +f 1030/1030/1484 1027/1036/1484 1046/1047/1484 +f 1028/1027/1485 1040/1038/1485 1046/1047/1485 +f 1040/1038/1478 1030/1030/1478 1046/1047/1478 +f 1037/1042/1486 1042/1043/1486 1047/1048/1486 +f 1028/1027/1487 1027/1036/1487 1048/1049/1487 +f 1031/1028/1488 1028/1027/1488 1048/1049/1488 +f 1027/1036/1489 1038/1035/1489 1048/1049/1489 +f 1043/1044/1490 1031/1028/1490 1048/1049/1490 +f 1038/1035/1474 1043/1044/1474 1048/1049/1474 +f 1033/1032/1491 1023/1050/1491 1049/1051/1491 +f 1034/1034/1492 1024/1033/1492 1049/1051/1492 +f 1039/1037/1493 1037/1042/1493 1049/1051/1493 +f 1047/1048/1494 1034/1034/1494 1049/1051/1494 +f 1037/1042/1495 1047/1048/1495 1049/1051/1495 +f 1024/1033/1474 1038/1035/1474 1050/1052/1474 +f 1038/1035/1496 1033/1032/1496 1050/1052/1496 +f 1049/1051/1497 1024/1033/1497 1050/1052/1497 +f 1033/1032/1498 1049/1051/1498 1050/1052/1498 +f 1032/1029/1499 1026/1041/1499 1051/1053/1499 +f 1040/1038/1470 1032/1029/1470 1051/1053/1470 +f 1026/1041/1500 1041/1040/1500 1051/1053/1500 +f 1041/1040/1478 1040/1038/1478 1051/1053/1478 +f 1023/1050/1501 1033/1032/1501 1052/1054/1501 +f 1033/1032/1471 1039/1037/1471 1052/1054/1471 +f 1049/1051/1502 1023/1050/1502 1052/1054/1502 +f 1039/1037/1503 1049/1051/1503 1052/1054/1503 +f 1045/1046/1504 1026/1041/1504 1053/1024/1504 +f 1036/1023/1505 1045/1046/1505 1053/1024/1505 +f 1042/1043/1506 1035/1039/1506 1054/1055/1506 +f 1035/1039/1507 1044/1045/1507 1054/1055/1507 +f 1047/1048/1508 1042/1043/1508 1054/1055/1508 +f 1029/1031/1471 1030/1030/1471 1055/1056/1471 +f 1041/1040/1509 1029/1031/1509 1055/1056/1509 +f 1030/1030/1478 1041/1040/1478 1055/1056/1478 +f 1045/1046/1510 1034/1034/1510 1056/1057/1510 +f 1044/1045/1511 1045/1046/1511 1056/1057/1511 +f 1034/1034/1512 1047/1048/1512 1056/1057/1512 +f 1054/1055/1513 1044/1045/1513 1056/1057/1513 +f 1047/1048/1514 1054/1055/1514 1056/1057/1514 +f 1029/1031/1515 1035/1039/1515 1057/1058/1515 +f 1039/1037/1516 1029/1031/1516 1057/1058/1516 +f 1035/1039/1517 1042/1043/1517 1057/1058/1517 +f 1042/1043/1518 1039/1037/1518 1057/1058/1518 +f 1026/1041/1519 1032/1029/1519 1058/1025/1519 +f 1032/1029/1470 1036/1023/1470 1058/1025/1470 +f 1053/1024/1520 1026/1041/1520 1058/1025/1520 +o Bowl_hull_33 +v -0.050883 -0.019831 -0.001059 +v -0.083211 0.000431 0.049363 +v -0.083211 -0.003452 0.049363 +v -0.076746 -0.019399 0.049794 +v -0.039678 0.000431 -0.019604 +v -0.040539 -0.003881 -0.025204 +v -0.039678 -0.019831 -0.011412 +v -0.078472 0.000431 0.048502 +v -0.080194 -0.019831 0.048071 +v -0.040108 -0.012501 -0.023050 +v -0.041400 0.000431 -0.023911 +v -0.081920 -0.015519 0.049363 +v -0.039678 -0.019831 -0.018311 +v -0.039678 -0.019399 -0.011412 +v -0.077176 -0.019831 0.050232 +v -0.082781 -0.009486 0.049363 +v -0.042691 -0.008193 -0.020465 +v -0.040539 0.000431 -0.017873 +v -0.079763 0.000431 0.050232 +v -0.039678 0.000431 -0.025642 +v -0.081059 -0.019831 0.050232 +v -0.083211 0.000431 0.050232 +v -0.075024 -0.019399 0.039017 +v -0.040969 -0.019831 -0.017019 +v -0.040108 -0.005606 -0.025642 +v -0.063384 -0.019831 0.019626 +v -0.064245 -0.003881 0.016172 +v -0.042691 -0.009486 -0.020035 +v -0.076315 -0.009914 0.038156 +v -0.039678 -0.009486 -0.024342 +v -0.082781 -0.001727 0.048502 +v -0.048300 -0.002159 -0.011843 +v -0.082781 -0.006900 0.048932 +v -0.040969 -0.014655 -0.020465 +v -0.082781 -0.010347 0.050232 +v -0.040969 -0.019399 -0.009258 +v -0.041400 -0.011640 -0.021327 +vt 0.073904 0.930781 +vt 0.000000 0.990112 +vt 0.056872 0.960446 +vt 0.079581 1.000000 +vt 0.988547 0.000000 +vt 0.977193 0.108870 +vt 0.324002 0.742608 +vt 0.187549 1.000000 +vt 0.971515 0.069317 +vt 0.022807 0.960446 +vt 0.096613 1.000000 +vt 0.187549 1.000000 +vt 0.994225 0.148522 +vt 1.000000 0.138633 +vt 0.102388 0.980223 +vt 1.000000 0.079205 +vt 0.000000 1.000000 +vt 0.005775 0.980223 +vt 0.988547 0.029665 +vt 1.000000 0.049442 +vt 1.000000 0.000000 +vt 0.988547 0.000000 +vt 0.852193 0.188075 +vt 0.113645 0.970335 +vt 0.034162 0.990112 +vt 0.068226 0.930781 +vt 0.596613 0.455453 +vt 0.988547 0.009888 +vt 0.840838 0.158410 +vt 0.017130 1.000000 +vt 0.977193 0.009888 +vt 0.551096 0.435677 +vt 0.181872 0.801939 +vt 0.982870 0.009888 +vt 0.068226 0.970335 +vt 1.000000 0.009888 +vt 0.215936 0.970335 +vn -0.8348 -0.1907 -0.5165 +vn 0.0000 1.0000 0.0000 +vn -0.0000 -1.0000 -0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.8128 -0.3081 0.4944 +vn 0.8805 0.1810 0.4381 +vn 0.8515 0.1955 0.4866 +vn 0.7967 0.1081 0.5946 +vn 0.6674 0.0852 0.7398 +vn -0.7071 0.0697 -0.7036 +vn -0.8984 -0.2519 -0.3597 +vn 0.0000 -0.0000 1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.8483 -0.1917 -0.4936 +vn -0.6331 -0.4461 -0.6326 +vn -0.8575 -0.1365 -0.4961 +vn -0.6201 0.0442 -0.7833 +vn -0.8103 -0.3378 -0.4789 +vn -0.8523 -0.1653 -0.4962 +vn -0.8483 -0.1860 -0.4957 +vn -0.8457 -0.1686 -0.5062 +vn -0.8616 -0.1230 -0.4924 +vn -0.8580 -0.1337 -0.4960 +vn -0.8636 -0.0895 -0.4962 +vn 0.6824 -0.3681 -0.6315 +vn -0.3265 -0.3326 -0.8847 +vn 0.8767 -0.0625 -0.4770 +vn -0.8945 0.0000 -0.4470 +vn -0.8683 0.0246 -0.4955 +vn -0.8680 -0.0309 -0.4956 +vn -0.8680 -0.0284 -0.4958 +vn -0.8658 -0.0230 -0.4999 +vn -0.8664 -0.0534 -0.4964 +vn -0.8682 0.0014 -0.4961 +vn -0.9172 -0.0654 -0.3929 +vn -0.8676 -0.0465 -0.4952 +vn -0.8657 -0.0671 -0.4960 +vn -0.8646 -0.0825 -0.4956 +vn -0.8645 -0.0814 -0.4959 +vn -0.8015 -0.3314 -0.4978 +vn -0.7437 -0.3704 -0.5565 +vn -0.8197 -0.2874 -0.4954 +vn -0.8266 -0.2652 -0.4964 +vn -0.9804 -0.1399 -0.1386 +vn -0.9950 -0.0710 -0.0703 +vn -0.9801 -0.1779 0.0881 +vn -0.9837 -0.0393 0.1756 +vn 0.8550 -0.0266 0.5180 +vn 0.8503 0.1076 0.5152 +vn 0.8576 0.0000 0.5142 +vn 0.8511 0.1232 0.5103 +vn -0.8292 -0.1967 -0.5232 +vn -0.8306 -0.2525 -0.4964 +vn -0.8350 -0.2382 -0.4959 +vn -0.8429 -0.2076 -0.4964 +usemtl None +s off +f 1086/1059/1521 1083/1060/1521 1095/1061/1521 +f 1063/1062/1522 1060/1063/1522 1066/1064/1522 +f 1059/1065/1523 1065/1066/1523 1067/1067/1523 +f 1060/1063/1522 1063/1062/1522 1069/1068/1522 +f 1065/1066/1523 1059/1065/1523 1071/1069/1523 +f 1063/1062/1524 1065/1066/1524 1071/1069/1524 +f 1065/1066/1524 1063/1062/1524 1072/1070/1524 +f 1065/1066/1525 1062/1071/1525 1073/1072/1525 +f 1067/1067/1523 1065/1066/1523 1073/1072/1523 +f 1063/1062/1522 1066/1064/1522 1076/1073/1522 +f 1072/1070/1526 1063/1062/1526 1076/1073/1526 +f 1066/1064/1527 1072/1070/1527 1076/1073/1527 +f 1066/1064/1522 1060/1063/1522 1077/1074/1522 +f 1062/1071/1528 1066/1064/1528 1077/1074/1528 +f 1073/1072/1529 1062/1071/1529 1077/1074/1529 +f 1069/1068/1522 1063/1062/1522 1078/1075/1522 +f 1064/1076/1530 1069/1068/1530 1078/1075/1530 +f 1063/1062/1524 1071/1069/1524 1078/1075/1524 +f 1070/1077/1531 1067/1067/1531 1079/1078/1531 +f 1067/1067/1523 1073/1072/1523 1079/1078/1523 +f 1073/1072/1532 1077/1074/1532 1079/1078/1532 +f 1079/1078/1532 1077/1074/1532 1080/1079/1532 +f 1060/1063/1533 1061/1080/1533 1080/1079/1533 +f 1077/1074/1522 1060/1063/1522 1080/1079/1522 +f 1067/1067/1534 1070/1077/1534 1081/1081/1534 +f 1071/1069/1523 1059/1065/1523 1082/1082/1523 +f 1068/1083/1535 1071/1069/1535 1082/1082/1535 +f 1075/1084/1536 1070/1077/1536 1083/1060/1536 +f 1064/1076/1537 1078/1075/1537 1083/1060/1537 +f 1059/1065/1523 1067/1067/1523 1084/1085/1523 +f 1067/1067/1538 1081/1081/1538 1084/1085/1538 +f 1070/1077/1539 1075/1084/1539 1086/1059/1539 +f 1081/1081/1540 1070/1077/1540 1086/1059/1540 +f 1075/1084/1541 1083/1060/1541 1086/1059/1541 +f 1070/1077/1542 1074/1086/1542 1087/1087/1542 +f 1083/1060/1543 1070/1077/1543 1087/1087/1543 +f 1064/1076/1544 1083/1060/1544 1087/1087/1544 +f 1071/1069/1545 1068/1083/1545 1088/1088/1545 +f 1078/1075/1524 1071/1069/1524 1088/1088/1524 +f 1068/1083/1546 1083/1060/1546 1088/1088/1546 +f 1083/1060/1547 1078/1075/1547 1088/1088/1547 +f 1061/1080/1548 1060/1063/1548 1089/1089/1548 +f 1060/1063/1549 1069/1068/1549 1089/1089/1549 +f 1085/1090/1550 1061/1080/1550 1089/1089/1550 +f 1085/1090/1551 1089/1089/1551 1090/1091/1551 +f 1069/1068/1552 1064/1076/1552 1090/1091/1552 +f 1064/1076/1553 1085/1090/1553 1090/1091/1553 +f 1089/1089/1554 1069/1068/1554 1090/1091/1554 +f 1074/1086/1555 1061/1080/1555 1091/1092/1555 +f 1061/1080/1556 1085/1090/1556 1091/1092/1556 +f 1085/1090/1557 1064/1076/1557 1091/1092/1557 +f 1087/1087/1558 1074/1086/1558 1091/1092/1558 +f 1064/1076/1559 1087/1087/1559 1091/1092/1559 +f 1082/1082/1560 1059/1065/1560 1092/1093/1560 +f 1068/1083/1561 1082/1082/1561 1092/1093/1561 +f 1059/1065/1562 1084/1085/1562 1092/1093/1562 +f 1084/1085/1563 1068/1083/1563 1092/1093/1563 +f 1074/1086/1564 1070/1077/1564 1093/1094/1564 +f 1061/1080/1565 1074/1086/1565 1093/1094/1565 +f 1070/1077/1566 1079/1078/1566 1093/1094/1566 +f 1079/1078/1532 1080/1079/1532 1093/1094/1532 +f 1080/1079/1567 1061/1080/1567 1093/1094/1567 +f 1062/1071/1568 1065/1066/1568 1094/1095/1568 +f 1066/1064/1569 1062/1071/1569 1094/1095/1569 +f 1065/1066/1570 1072/1070/1570 1094/1095/1570 +f 1072/1070/1571 1066/1064/1571 1094/1095/1571 +f 1083/1060/1572 1068/1083/1572 1095/1061/1572 +f 1068/1083/1573 1084/1085/1573 1095/1061/1573 +f 1084/1085/1574 1081/1081/1574 1095/1061/1574 +f 1081/1081/1575 1086/1059/1575 1095/1061/1575 +o Bowl_hull_34 +v -0.046143 -0.039229 0.009282 +v -0.080629 -0.019833 0.048934 +v -0.080629 -0.020266 0.048934 +v -0.040106 -0.020266 -0.017882 +v -0.040106 -0.039660 0.010142 +v -0.072867 -0.040092 0.048934 +v -0.076748 -0.020266 0.050235 +v -0.039673 -0.019833 -0.010981 +v -0.068125 -0.039660 0.049368 +v -0.039673 -0.040092 0.002814 +v -0.077610 -0.030608 0.049368 +v -0.040106 -0.025438 -0.013568 +v -0.068987 -0.040092 0.050235 +v -0.056491 -0.020266 0.008422 +v -0.059938 -0.040092 0.029538 +v -0.075882 -0.019833 0.048508 +v -0.039673 -0.019833 -0.017882 +v -0.078039 -0.029749 0.050235 +v -0.070282 -0.032762 0.039020 +v -0.039673 -0.040092 0.009282 +v -0.040106 -0.031039 -0.007960 +v -0.042263 -0.021128 -0.014001 +v -0.076748 -0.025008 0.044627 +v -0.073296 -0.040092 0.050235 +v -0.080629 -0.019833 0.050235 +v -0.040968 -0.040092 0.003675 +v -0.050453 -0.020266 -0.001493 +v -0.071144 -0.039229 0.045487 +v -0.055196 -0.039660 0.022211 +v -0.050453 -0.019833 -0.001493 +v -0.060796 -0.038367 0.029105 +v -0.041830 -0.025008 -0.011408 +v -0.074158 -0.034918 0.046781 +v -0.068125 -0.020266 0.027811 +v -0.039673 -0.031039 -0.007960 +v -0.040106 -0.034918 -0.003646 +v -0.049591 -0.040092 0.014883 +vt 0.208986 0.989428 +vt 0.398786 0.842013 +vt 0.481010 0.757831 +vt 0.411413 0.989428 +vt 1.000000 0.094753 +vt 0.987275 0.305305 +vt 1.000000 0.284260 +vt 0.980912 0.189507 +vt 0.303837 1.000000 +vt 0.696163 0.505188 +vt 0.974648 0.115897 +vt 0.101312 1.000000 +vt 0.980912 0.000000 +vt 0.000000 1.000000 +vt 0.063332 0.989428 +vt 0.000000 0.989428 +vt 0.980912 0.000000 +vt 0.987275 0.073708 +vt 1.000000 0.063234 +vt 0.398786 1.000000 +vt 0.917678 0.094753 +vt 0.386159 0.589370 +vt 1.000000 0.179033 +vt 1.000000 0.000000 +vt 0.316464 0.968383 +vt 0.240603 0.736785 +vt 0.835356 0.252643 +vt 0.056969 0.936766 +vt 0.930305 0.231597 +vt 0.145654 0.989428 +vt 0.588587 0.620987 +vt 0.240603 0.736785 +vt 0.689800 0.484240 +vt 0.095047 0.947337 +vt 0.949295 0.157987 +vt 0.670811 0.305305 +vt 0.145654 1.000000 +vn -0.6685 -0.5535 -0.4968 +vn 0.7714 0.3184 0.5510 +vn 0.6240 0.2443 0.7423 +vn 0.0000 -1.0000 0.0000 +vn 0.7607 0.4275 0.4885 +vn 0.0000 1.0000 0.0000 +vn 0.7531 0.4719 0.4584 +vn 1.0000 0.0000 0.0000 +vn 0.5388 -0.5396 -0.6469 +vn -0.9411 -0.2825 -0.1859 +vn 0.0000 -0.0000 1.0000 +vn 0.9037 0.3028 0.3027 +vn 0.7701 -0.3231 0.5501 +vn 0.7404 -0.4135 0.5300 +vn -0.8433 -0.2657 -0.4672 +vn -0.8172 -0.2939 -0.4957 +vn -0.8626 -0.4183 -0.2846 +vn -0.9084 -0.4165 -0.0369 +vn -1.0000 0.0000 0.0000 +vn 0.1059 0.9508 0.2912 +vn -0.9641 -0.2518 0.0837 +vn -0.8146 -0.3005 -0.4961 +vn -0.7997 -0.3386 -0.4958 +vn -0.8127 -0.2762 -0.5131 +vn -0.7950 -0.3483 -0.4966 +vn -0.7280 -0.4843 -0.4853 +vn -0.7102 -0.4981 -0.4975 +vn -0.6408 0.6417 -0.4215 +vn -0.8541 0.0000 -0.5201 +vn -0.8456 0.0000 -0.5339 +vn -0.7281 -0.4840 -0.4854 +vn -0.7221 -0.4821 -0.4962 +vn -0.7217 -0.4833 -0.4956 +vn -0.7466 -0.4261 -0.5109 +vn -0.7480 -0.4246 -0.5101 +vn -0.7614 -0.4169 -0.4965 +vn -0.7480 -0.4412 -0.4957 +vn -0.7367 -0.4593 -0.4963 +vn -0.8110 -0.3855 -0.4400 +vn -0.7988 -0.3431 -0.4943 +vn -0.7780 -0.3859 -0.4958 +vn -0.7773 -0.3971 -0.4881 +vn -0.7746 -0.3929 -0.4956 +vn -0.8605 0.0000 -0.5094 +vn -0.8365 -0.2348 -0.4952 +vn -0.8288 -0.2563 -0.4973 +vn -0.8284 0.2606 -0.4957 +vn -0.8446 0.1729 -0.5068 +vn 0.7463 -0.4412 -0.4983 +vn 0.0000 -0.7075 -0.7067 +vn 0.0000 -0.7436 -0.6686 +vn -0.6347 -0.5939 -0.4944 +vn -0.3747 -0.7358 -0.5641 +vn 0.4103 -0.6982 -0.5866 +vn -0.6215 -0.6206 -0.4782 +vn -0.6335 -0.6314 -0.4472 +vn -0.6889 -0.5289 -0.4957 +vn -0.6692 -0.5526 -0.4969 +usemtl None +s off +f 1131/1096/1576 1096/1097/1576 1132/1098/1576 +f 1100/1099/1577 1102/1100/1577 1104/1101/1577 +f 1104/1101/1578 1102/1100/1578 1108/1102/1578 +f 1101/1103/1579 1105/1104/1579 1108/1102/1579 +f 1105/1104/1579 1101/1103/1579 1110/1105/1579 +f 1102/1100/1580 1100/1099/1580 1111/1106/1580 +f 1103/1107/1581 1097/1108/1581 1111/1106/1581 +f 1100/1099/1582 1103/1107/1582 1111/1106/1582 +f 1097/1108/1581 1103/1107/1581 1112/1109/1581 +f 1103/1107/1583 1105/1104/1583 1112/1109/1583 +f 1107/1110/1584 1099/1111/1584 1112/1109/1584 +f 1098/1112/1585 1106/1113/1585 1113/1114/1585 +f 1108/1102/1586 1102/1100/1586 1113/1114/1586 +f 1103/1107/1587 1100/1099/1587 1115/1115/1587 +f 1100/1099/1588 1104/1101/1588 1115/1115/1588 +f 1105/1104/1583 1103/1107/1583 1115/1115/1583 +f 1104/1101/1589 1108/1102/1589 1115/1115/1589 +f 1108/1102/1579 1105/1104/1579 1115/1115/1579 +f 1106/1113/1590 1098/1112/1590 1118/1116/1590 +f 1109/1117/1591 1106/1113/1591 1118/1116/1591 +f 1106/1113/1592 1101/1103/1592 1119/1118/1592 +f 1101/1103/1579 1108/1102/1579 1119/1118/1579 +f 1113/1114/1593 1106/1113/1593 1119/1118/1593 +f 1108/1102/1586 1113/1114/1586 1119/1118/1586 +f 1097/1108/1594 1098/1112/1594 1120/1119/1594 +f 1111/1106/1581 1097/1108/1581 1120/1119/1581 +f 1102/1100/1595 1111/1106/1595 1120/1119/1595 +f 1098/1112/1596 1113/1114/1596 1120/1119/1596 +f 1113/1114/1586 1102/1100/1586 1120/1119/1586 +f 1105/1104/1579 1110/1105/1579 1121/1120/1579 +f 1106/1113/1597 1109/1117/1597 1122/1121/1597 +f 1114/1122/1598 1106/1113/1598 1122/1121/1598 +f 1099/1111/1599 1117/1123/1599 1122/1121/1599 +f 1117/1123/1600 1114/1122/1600 1122/1121/1600 +f 1110/1105/1601 1101/1103/1601 1123/1124/1601 +f 1107/1110/1602 1116/1125/1602 1124/1126/1602 +f 1097/1108/1581 1112/1109/1581 1125/1127/1581 +f 1112/1109/1603 1099/1111/1603 1125/1127/1603 +f 1122/1121/1604 1109/1117/1604 1125/1127/1604 +f 1099/1111/1605 1122/1121/1605 1125/1127/1605 +f 1110/1105/1606 1123/1124/1606 1126/1128/1606 +f 1107/1110/1607 1124/1126/1607 1126/1128/1607 +f 1124/1126/1608 1110/1105/1608 1126/1128/1608 +f 1099/1111/1609 1107/1110/1609 1127/1129/1609 +f 1117/1123/1610 1099/1111/1610 1127/1129/1610 +f 1123/1124/1611 1117/1123/1611 1127/1129/1611 +f 1126/1128/1612 1123/1124/1612 1127/1129/1612 +f 1107/1110/1613 1126/1128/1613 1127/1129/1613 +f 1101/1103/1614 1106/1113/1614 1128/1130/1614 +f 1106/1113/1615 1114/1122/1615 1128/1130/1615 +f 1114/1122/1616 1117/1123/1616 1128/1130/1616 +f 1123/1124/1617 1101/1103/1617 1128/1130/1617 +f 1117/1123/1618 1123/1124/1618 1128/1130/1618 +f 1098/1112/1619 1097/1108/1619 1129/1131/1619 +f 1118/1116/1620 1098/1112/1620 1129/1131/1620 +f 1109/1117/1621 1118/1116/1621 1129/1131/1621 +f 1097/1108/1622 1125/1127/1622 1129/1131/1622 +f 1125/1127/1623 1109/1117/1623 1129/1131/1623 +f 1112/1109/1583 1105/1104/1583 1130/1132/1583 +f 1107/1110/1624 1112/1109/1624 1130/1132/1624 +f 1116/1125/1625 1107/1110/1625 1130/1132/1625 +f 1116/1125/1626 1130/1132/1626 1131/1096/1626 +f 1121/1120/1627 1096/1097/1627 1131/1096/1627 +f 1105/1104/1628 1121/1120/1628 1131/1096/1628 +f 1130/1132/1629 1105/1104/1629 1131/1096/1629 +f 1096/1097/1630 1121/1120/1630 1132/1098/1630 +f 1121/1120/1579 1110/1105/1579 1132/1098/1579 +f 1110/1105/1631 1124/1126/1631 1132/1098/1631 +f 1124/1126/1632 1116/1125/1632 1132/1098/1632 +f 1116/1125/1633 1131/1096/1633 1132/1098/1633 +o Bowl_hull_35 +v 0.037064 -0.024576 -0.018744 +v 0.040084 -0.039663 0.008847 +v 0.040084 -0.039663 0.002376 +v 0.009043 -0.039663 -0.018744 +v 0.039652 -0.006898 -0.018312 +v 0.020255 -0.039663 -0.018744 +v 0.040084 -0.019406 -0.018744 +v 0.009043 -0.039230 -0.018309 +v 0.039652 -0.039227 0.008847 +v 0.030163 -0.032764 -0.018744 +v 0.040084 -0.006898 -0.018744 +v 0.029732 -0.039230 -0.010552 +v 0.040084 -0.031468 -0.007533 +v 0.033184 -0.029743 -0.018744 +v 0.037924 -0.039663 -0.000641 +v 0.025855 -0.036209 -0.018744 +v 0.040084 -0.037504 -0.000641 +v 0.040084 -0.025003 -0.014001 +v 0.032752 -0.039663 -0.006669 +v 0.039652 -0.006898 -0.018744 +vt 0.000000 0.986100 +vt 0.000000 1.000000 +vt 0.000000 0.986100 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 1.000000 0.361198 +vt 0.539546 0.902702 +vt 0.381754 1.000000 +vt 0.986785 0.000000 +vt 0.986688 0.986100 +vt 0.789448 0.680403 +vt 0.749902 1.000000 +vt 0.697240 0.777702 +vt 1.000000 0.930403 +vt 0.894577 0.541601 +vt 0.986785 0.666503 +vt 0.934123 1.000000 +vt 0.552565 1.000000 +vt 1.000000 0.763802 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn -0.5313 -0.6003 0.5978 +vn -0.5620 0.5321 0.6333 +vn 0.5452 0.5393 0.6419 +vn -0.5548 -0.5488 0.6254 +vn 0.6082 0.5113 0.6072 +vn 0.6903 -0.5184 -0.5047 +vn 0.4576 -0.7418 -0.4902 +vn 0.5393 -0.6746 -0.5041 +vn 0.6137 -0.6135 -0.4969 +vn 0.6616 -0.5641 -0.4940 +vn 0.6306 -0.6312 -0.4516 +vn 0.6134 -0.6139 -0.4969 +vn 0.7420 -0.4334 -0.5115 +vn 0.7107 -0.4975 -0.4973 +vn 0.3677 -0.8485 -0.3805 +vn 0.5475 -0.6706 -0.5005 +vn 0.5769 -0.6498 -0.4949 +vn -0.6043 0.5646 -0.5622 +vn -0.7262 0.6875 0.0000 +usemtl None +s off +f 1137/1133/1634 1143/1134/1634 1152/1135/1634 +f 1135/1136/1635 1134/1137/1635 1136/1138/1635 +f 1135/1136/1635 1136/1138/1635 1138/1139/1635 +f 1136/1138/1636 1133/1140/1636 1138/1139/1636 +f 1134/1137/1637 1135/1136/1637 1139/1141/1637 +f 1133/1140/1636 1136/1138/1636 1139/1141/1636 +f 1136/1138/1638 1134/1137/1638 1140/1142/1638 +f 1137/1133/1639 1140/1142/1639 1141/1143/1639 +f 1134/1137/1640 1137/1133/1640 1141/1143/1640 +f 1140/1142/1641 1134/1137/1641 1141/1143/1641 +f 1138/1139/1636 1133/1140/1636 1142/1144/1636 +f 1137/1133/1642 1134/1137/1642 1143/1134/1642 +f 1134/1137/1637 1139/1141/1637 1143/1134/1637 +f 1139/1141/1636 1136/1138/1636 1143/1134/1636 +f 1139/1141/1637 1135/1136/1637 1145/1145/1637 +f 1142/1144/1636 1133/1140/1636 1146/1146/1636 +f 1133/1140/1643 1145/1145/1643 1146/1146/1643 +f 1135/1136/1635 1138/1139/1635 1147/1147/1635 +f 1138/1139/1636 1142/1144/1636 1148/1148/1636 +f 1144/1149/1644 1138/1139/1644 1148/1148/1644 +f 1142/1144/1645 1144/1149/1645 1148/1148/1645 +f 1145/1145/1637 1135/1136/1637 1149/1150/1637 +f 1142/1144/1646 1146/1146/1646 1149/1150/1646 +f 1146/1146/1647 1145/1145/1647 1149/1150/1647 +f 1135/1136/1648 1147/1147/1648 1149/1150/1648 +f 1147/1147/1649 1142/1144/1649 1149/1150/1649 +f 1133/1140/1650 1139/1141/1650 1150/1151/1650 +f 1145/1145/1651 1133/1140/1651 1150/1151/1651 +f 1139/1141/1637 1145/1145/1637 1150/1151/1637 +f 1138/1139/1652 1144/1149/1652 1151/1152/1652 +f 1144/1149/1653 1142/1144/1653 1151/1152/1653 +f 1147/1147/1635 1138/1139/1635 1151/1152/1635 +f 1142/1144/1654 1147/1147/1654 1151/1152/1654 +f 1136/1138/1655 1140/1142/1655 1152/1135/1655 +f 1140/1142/1656 1137/1133/1656 1152/1135/1656 +f 1143/1134/1636 1136/1138/1636 1152/1135/1636 +o Bowl_hull_36 +v -0.039241 -0.029742 -0.010548 +v -0.039673 -0.007763 -0.019172 +v -0.039673 -0.007763 -0.018739 +v -0.005183 -0.039660 -0.019175 +v -0.039241 -0.039657 0.008847 +v -0.022857 -0.037936 -0.019175 +v -0.039673 -0.040094 0.002379 +v -0.039673 -0.019403 -0.019172 +v -0.018549 -0.040091 -0.019175 +v -0.032772 -0.030176 -0.018739 +v -0.005183 -0.039660 -0.018742 +v -0.039241 -0.007763 -0.018739 +v -0.039673 -0.040094 0.008847 +v -0.031050 -0.040094 -0.007962 +v -0.005183 -0.040091 -0.018742 +v -0.029325 -0.033192 -0.019172 +v -0.039673 -0.037932 -0.000638 +v -0.036222 -0.025432 -0.019172 +v -0.037515 -0.040094 -0.000638 +v -0.039673 -0.023283 -0.016152 +v -0.025014 -0.040091 -0.013999 +v -0.027600 -0.036211 -0.017016 +vt 0.487569 0.933242 +vt 0.425020 0.999902 +vt 0.350039 0.879894 +vt 0.000000 0.000000 +vt 1.000000 0.986590 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 0.000000 0.360023 +vt 0.612471 0.999902 +vt 0.012529 0.000000 +vt 0.012529 0.986492 +vt 1.000000 0.986590 +vt 0.000000 1.000000 +vt 0.250000 1.000000 +vt 1.000000 0.999902 +vt 0.000000 0.933144 +vt 0.012529 0.679816 +vt 0.200078 0.693226 +vt 0.100039 0.546496 +vt 0.300020 0.786511 +vt 0.062549 1.000000 +vt 0.000000 0.480031 +vn -0.4879 -0.7148 -0.5010 +vn 0.0000 0.0001 -1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.0002 0.0000 -1.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 1.0000 0.0000 +vn 0.5622 0.6080 -0.5606 +vn 0.0000 0.6542 0.7563 +vn 0.6836 0.7299 0.0000 +vn 0.5225 0.5578 0.6449 +vn -0.5485 0.5427 0.6361 +vn 0.0000 -1.0000 0.0000 +vn 0.0002 -1.0000 0.0001 +vn 0.0228 -0.7094 -0.7045 +vn 1.0000 0.0000 0.0000 +vn 0.6295 0.0000 0.7770 +vn 0.5314 -0.5258 0.6642 +vn 0.0000 -1.0000 -0.0003 +vn -0.6630 -0.5626 -0.4938 +vn -0.0004 -0.0003 -1.0000 +vn -0.6754 -0.5374 -0.5050 +vn -0.0012 -0.0011 -1.0000 +vn -0.4510 -0.4009 -0.7974 +vn -0.6055 -0.6203 -0.4986 +vn -0.5607 -0.6638 -0.4950 +vn -0.6315 -0.6303 -0.4515 +vn -0.6142 -0.6130 -0.4969 +vn -0.8912 -0.3298 -0.3114 +vn -0.7316 -0.4187 -0.5379 +vn -0.7281 -0.4764 -0.4929 +vn -0.3906 -0.7807 -0.4878 +vn -0.0021 -1.0000 -0.0026 +vn -0.4946 -0.7145 -0.4949 +vn -0.4947 -0.6742 -0.5483 +vn -0.5511 -0.6700 -0.4973 +usemtl None +s off +f 1158/1153/1657 1173/1154/1657 1174/1155/1657 +f 1154/1156/1658 1156/1157/1658 1158/1153/1658 +f 1155/1158/1659 1154/1156/1659 1159/1159/1659 +f 1154/1156/1660 1158/1153/1660 1160/1160/1660 +f 1159/1159/1659 1154/1156/1659 1160/1160/1659 +f 1158/1153/1661 1156/1157/1661 1161/1161/1661 +f 1154/1156/1662 1155/1158/1662 1164/1162/1662 +f 1156/1157/1663 1154/1156/1663 1164/1162/1663 +f 1155/1158/1664 1157/1163/1664 1164/1162/1664 +f 1163/1164/1665 1156/1157/1665 1164/1162/1665 +f 1157/1163/1666 1163/1164/1666 1164/1162/1666 +f 1157/1163/1667 1155/1158/1667 1165/1165/1667 +f 1155/1158/1659 1159/1159/1659 1165/1165/1659 +f 1165/1165/1668 1159/1159/1668 1166/1166/1668 +f 1165/1165/1669 1166/1166/1669 1167/1167/1669 +f 1161/1161/1670 1156/1157/1670 1167/1167/1670 +f 1156/1157/1671 1163/1164/1671 1167/1167/1671 +f 1163/1164/1672 1157/1163/1672 1167/1167/1672 +f 1157/1163/1673 1165/1165/1673 1167/1167/1673 +f 1166/1166/1674 1161/1161/1674 1167/1167/1674 +f 1159/1159/1659 1160/1160/1659 1169/1168/1659 +f 1153/1169/1675 1162/1170/1675 1169/1168/1675 +f 1160/1160/1676 1158/1153/1676 1170/1171/1676 +f 1162/1170/1677 1153/1169/1677 1170/1171/1677 +f 1158/1153/1678 1168/1172/1678 1170/1171/1678 +f 1168/1172/1679 1162/1170/1679 1170/1171/1679 +f 1166/1166/1668 1159/1159/1668 1171/1173/1668 +f 1162/1170/1680 1168/1172/1680 1171/1173/1680 +f 1168/1172/1681 1166/1166/1681 1171/1173/1681 +f 1159/1159/1682 1169/1168/1682 1171/1173/1682 +f 1169/1168/1683 1162/1170/1683 1171/1173/1683 +f 1153/1169/1684 1169/1168/1684 1172/1174/1684 +f 1169/1168/1659 1160/1160/1659 1172/1174/1659 +f 1160/1160/1685 1170/1171/1685 1172/1174/1685 +f 1170/1171/1686 1153/1169/1686 1172/1174/1686 +f 1158/1153/1687 1161/1161/1687 1173/1154/1687 +f 1161/1161/1688 1166/1166/1688 1173/1154/1688 +f 1173/1154/1689 1166/1166/1689 1174/1155/1689 +f 1168/1172/1690 1158/1153/1690 1174/1155/1690 +f 1166/1166/1691 1168/1172/1691 1174/1155/1691 +o Bowl_hull_37 +v -0.055196 -0.045701 0.028676 +v -0.042259 -0.071565 0.050235 +v -0.042259 -0.067253 0.050235 +v -0.072867 -0.040094 0.050230 +v -0.042259 -0.040094 0.013162 +v -0.068124 -0.040094 0.049800 +v -0.042691 -0.040525 0.006692 +v -0.054330 -0.063371 0.049365 +v -0.065107 -0.052167 0.049369 +v -0.042691 -0.059061 0.030829 +v -0.064676 -0.040528 0.036864 +v -0.045711 -0.069837 0.049369 +v -0.042691 -0.045701 0.012731 +v -0.061227 -0.056905 0.049800 +v -0.042259 -0.040094 0.006692 +v -0.042691 -0.040094 0.014023 +v -0.071141 -0.043547 0.049369 +v -0.051745 -0.040528 0.018336 +v -0.042259 -0.066821 0.049800 +v -0.059936 -0.055614 0.046352 +v -0.043554 -0.041388 0.008418 +v -0.053471 -0.064234 0.050235 +v -0.065970 -0.047857 0.045921 +v -0.068556 -0.040094 0.050230 +v -0.042259 -0.071565 0.049369 +v -0.053902 -0.056474 0.039882 +v -0.067261 -0.049582 0.050230 +v -0.072867 -0.040094 0.049369 +v -0.050022 -0.066821 0.049365 +v -0.043554 -0.052170 0.022219 +v -0.042259 -0.053464 0.023076 +v -0.051745 -0.040097 0.018336 +v -0.043122 -0.071131 0.048935 +v -0.059073 -0.040960 0.029107 +v -0.061227 -0.050013 0.041608 +v -0.056919 -0.060355 0.048508 +vt 0.910826 0.493148 +vt 0.762236 0.520458 +vt 0.960356 0.643794 +vt 1.000000 0.862960 +vt 1.000000 1.000000 +vt 0.148590 0.000000 +vt 0.999902 0.000000 +vt 0.990016 0.000000 +vt 0.000000 0.000000 +vt 0.138704 0.178152 +vt 0.000000 0.013704 +vt 0.168363 0.000000 +vt 0.990016 0.849256 +vt 0.990016 0.534162 +vt 0.980129 0.383614 +vt 0.039644 0.041112 +vt 0.504894 0.178152 +vt 0.267424 0.013802 +vt 1.000000 0.767032 +vt 0.980129 0.945086 +vt 0.980031 0.739624 +vt 0.980129 0.109730 +vt 0.900940 0.246672 +vt 0.692933 0.013802 +vt 0.999902 0.000000 +vt 0.980129 1.000000 +vt 0.999902 0.301488 +vt 0.980129 0.000000 +vt 0.554327 0.602682 +vt 0.980031 0.849256 +vt 0.356597 0.383712 +vt 0.376272 0.424824 +vt 0.267424 0.000098 +vt 0.970145 0.986198 +vt 0.514781 0.027506 +vt 0.801879 0.315192 +vn -0.6155 -0.6156 -0.4922 +vn 1.0000 0.0000 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.6046 -0.6048 -0.5183 +vn 0.5915 0.5724 0.5679 +vn 0.7618 0.5233 0.3818 +vn 0.6399 0.6193 0.4549 +vn -0.6628 -0.5852 -0.4673 +vn -0.4770 -0.6674 -0.5719 +vn -0.6637 -0.5565 -0.4999 +vn -0.7228 -0.4019 -0.5621 +vn -0.6513 -0.5738 -0.4965 +vn -0.0000 0.0000 1.0000 +vn -0.4873 -0.7451 0.4555 +vn -0.6848 -0.7274 -0.0444 +vn -0.7293 -0.5105 -0.4556 +vn -0.7271 -0.4791 -0.4916 +vn 0.5830 0.5646 0.5843 +vn 0.0001 0.0002 1.0000 +vn 0.0000 0.0002 1.0000 +vn -0.4477 -0.8942 0.0000 +vn -0.5805 -0.6458 -0.4959 +vn -0.6087 -0.6186 -0.4968 +vn -0.6184 -0.6097 -0.4957 +vn -0.7722 -0.6348 -0.0265 +vn -0.8213 -0.4852 0.3000 +vn -0.7784 -0.5449 -0.3117 +vn -0.0008 -0.0005 1.0000 +vn -0.4144 -0.3898 0.8224 +vn -0.8945 -0.4470 0.0000 +vn -0.7770 -0.3883 -0.4955 +vn -0.4977 -0.7122 -0.4950 +vn -0.5657 -0.8084 0.1624 +vn -0.6176 -0.7712 -0.1543 +vn -0.5733 -0.6517 -0.4965 +vn -0.4464 -0.7199 -0.5315 +vn -0.5430 -0.6781 -0.4954 +vn -0.5294 -0.6874 -0.4972 +vn -0.2292 -0.7831 -0.5781 +vn 0.7729 -0.4916 -0.4012 +vn 0.4446 -0.7378 -0.5079 +vn -0.6127 0.6129 -0.4989 +vn -0.7894 0.0000 -0.6138 +vn -0.8200 0.0000 -0.5723 +vn -0.0027 1.0000 -0.0019 +vn -0.7053 0.5216 -0.4801 +vn -0.4527 -0.7369 -0.5020 +vn -0.4477 -0.8942 -0.0048 +vn -0.1362 -0.8228 -0.5518 +vn -0.7719 -0.3377 -0.5387 +vn -0.7221 -0.4837 -0.4946 +vn -0.7007 -0.5115 -0.4973 +vn -0.6792 -0.5402 -0.4969 +vn -0.6546 -0.5708 -0.4957 +vn -0.6631 -0.5669 -0.4888 +vn -0.6893 -0.5317 -0.4921 +vn -0.6905 -0.5266 -0.4960 +vn -0.6447 -0.6620 -0.3823 +vn -0.6336 -0.6161 -0.4679 +vn -0.5855 -0.6428 -0.4940 +usemtl None +s off +f 1194/1175/1692 1200/1176/1692 1210/1177/1692 +f 1177/1178/1693 1176/1179/1693 1179/1180/1693 +f 1179/1180/1694 1178/1181/1694 1180/1182/1694 +f 1178/1181/1694 1179/1180/1694 1189/1183/1694 +f 1179/1180/1693 1176/1179/1693 1189/1183/1693 +f 1187/1184/1695 1181/1185/1695 1189/1183/1695 +f 1179/1180/1694 1180/1182/1694 1190/1186/1694 +f 1177/1178/1693 1179/1180/1693 1193/1187/1693 +f 1180/1182/1696 1177/1178/1696 1193/1187/1696 +f 1179/1180/1697 1190/1186/1697 1193/1187/1697 +f 1190/1186/1698 1180/1182/1698 1193/1187/1698 +f 1188/1188/1699 1183/1189/1699 1194/1175/1699 +f 1181/1185/1700 1187/1184/1700 1195/1190/1700 +f 1175/1191/1701 1192/1192/1701 1195/1190/1701 +f 1192/1192/1702 1181/1185/1702 1195/1190/1702 +f 1194/1175/1703 1175/1191/1703 1195/1190/1703 +f 1176/1179/1704 1177/1178/1704 1196/1193/1704 +f 1186/1194/1705 1176/1179/1705 1196/1193/1705 +f 1188/1188/1706 1182/1195/1706 1196/1193/1706 +f 1183/1189/1707 1191/1196/1707 1197/1197/1707 +f 1191/1196/1708 1185/1198/1708 1197/1197/1708 +f 1177/1178/1709 1180/1182/1709 1198/1199/1709 +f 1180/1182/1694 1178/1181/1694 1198/1199/1694 +f 1196/1193/1710 1177/1178/1710 1198/1199/1710 +f 1178/1181/1711 1196/1193/1711 1198/1199/1711 +f 1176/1179/1712 1186/1194/1712 1199/1200/1712 +f 1189/1183/1693 1176/1179/1693 1199/1200/1693 +f 1187/1184/1713 1182/1195/1713 1200/1176/1713 +f 1195/1190/1714 1187/1184/1714 1200/1176/1714 +f 1194/1175/1715 1195/1190/1715 1200/1176/1715 +f 1183/1189/1716 1188/1188/1716 1201/1201/1716 +f 1178/1181/1717 1191/1196/1717 1201/1201/1717 +f 1191/1196/1718 1183/1189/1718 1201/1201/1718 +f 1196/1193/1719 1178/1181/1719 1201/1201/1719 +f 1188/1188/1720 1196/1193/1720 1201/1201/1720 +f 1178/1181/1694 1189/1183/1694 1202/1202/1694 +f 1191/1196/1721 1178/1181/1721 1202/1202/1721 +f 1185/1198/1722 1191/1196/1722 1202/1202/1722 +f 1184/1203/1723 1186/1194/1723 1203/1204/1723 +f 1186/1194/1724 1196/1193/1724 1203/1204/1724 +f 1196/1193/1725 1182/1195/1725 1203/1204/1725 +f 1182/1195/1726 1187/1184/1726 1204/1205/1726 +f 1187/1184/1727 1184/1203/1727 1204/1205/1727 +f 1203/1204/1728 1182/1195/1728 1204/1205/1728 +f 1184/1203/1729 1203/1204/1729 1204/1205/1729 +f 1184/1203/1730 1187/1184/1730 1205/1206/1730 +f 1187/1184/1731 1189/1183/1731 1205/1206/1731 +f 1199/1200/1732 1184/1203/1732 1205/1206/1732 +f 1189/1183/1693 1199/1200/1693 1205/1206/1693 +f 1189/1183/1733 1181/1185/1733 1206/1207/1733 +f 1181/1185/1734 1192/1192/1734 1206/1207/1734 +f 1192/1192/1735 1185/1198/1735 1206/1207/1735 +f 1202/1202/1736 1189/1183/1736 1206/1207/1736 +f 1185/1198/1737 1202/1202/1737 1206/1207/1737 +f 1186/1194/1738 1184/1203/1738 1207/1208/1738 +f 1199/1200/1739 1186/1194/1739 1207/1208/1739 +f 1184/1203/1740 1199/1200/1740 1207/1208/1740 +f 1185/1198/1741 1192/1192/1741 1208/1209/1741 +f 1197/1197/1742 1185/1198/1742 1208/1209/1742 +f 1192/1192/1743 1197/1197/1743 1208/1209/1743 +f 1192/1192/1744 1175/1191/1744 1209/1210/1744 +f 1175/1191/1745 1194/1175/1745 1209/1210/1745 +f 1194/1175/1746 1183/1189/1746 1209/1210/1746 +f 1183/1189/1747 1197/1197/1747 1209/1210/1747 +f 1197/1197/1748 1192/1192/1748 1209/1210/1748 +f 1182/1195/1749 1188/1188/1749 1210/1177/1749 +f 1188/1188/1750 1194/1175/1750 1210/1177/1750 +f 1200/1176/1751 1182/1195/1751 1210/1177/1751 +o Bowl_hull_38 +v -0.039240 -0.047428 0.011009 +v -0.025879 -0.078894 0.050235 +v -0.025879 -0.075009 0.050235 +v -0.025879 -0.040094 -0.011846 +v -0.041826 -0.040098 0.012735 +v -0.042259 -0.071993 0.049797 +v -0.025879 -0.040531 -0.004511 +v -0.041395 -0.067679 0.050235 +v -0.042259 -0.040531 0.005837 +v -0.026310 -0.052601 0.006263 +v -0.031483 -0.076737 0.048503 +v -0.027603 -0.042251 -0.008395 +v -0.042259 -0.059065 0.030394 +v -0.040965 -0.072426 0.048934 +v -0.042259 -0.066821 0.049366 +v -0.026310 -0.078894 0.048940 +v -0.032344 -0.040960 -0.005374 +v -0.042259 -0.040098 0.012735 +v -0.035361 -0.072856 0.045057 +v -0.025879 -0.062077 0.021345 +v -0.034929 -0.075875 0.050235 +v -0.042259 -0.040098 0.005837 +v -0.025879 -0.040094 -0.005374 +v -0.026310 -0.062077 0.021345 +v -0.040965 -0.062939 0.034708 +v -0.042259 -0.047428 0.014454 +v -0.026310 -0.048723 0.000228 +v -0.041395 -0.040098 0.012303 +v -0.036655 -0.040531 -0.001060 +v -0.025879 -0.040964 -0.011415 +v -0.042259 -0.071993 0.050235 +v -0.027171 -0.045700 -0.003655 +v -0.041826 -0.066821 0.049366 +v -0.041826 -0.056049 0.025654 +vt 0.680403 0.488939 +vt 0.423649 0.189017 +vt 0.604052 0.411218 +vt 1.000000 0.899863 +vt 1.000000 1.000000 +vt 0.000000 0.000000 +vt 0.118148 0.011257 +vt 1.000000 0.710944 +vt 0.992952 0.822142 +vt 0.284847 0.011257 +vt 0.979052 0.833301 +vt 0.986002 0.688821 +vt 0.395948 0.000098 +vt 0.395948 0.000098 +vt 0.972103 0.944401 +vt 0.916601 0.844362 +vt 0.534652 0.566562 +vt 0.979150 1.000000 +vt 1.000000 0.922181 +vt 0.284847 0.000098 +vt 0.104248 0.000000 +vt 0.534652 0.566562 +vt 0.291699 0.322337 +vt 0.055599 0.055599 +vt 0.749902 0.588782 +vt 0.194499 0.222396 +vt 0.388998 0.000098 +vt 0.104248 0.022318 +vt 0.368148 0.189017 +vt 0.173747 0.011257 +vt 0.006950 0.022416 +vt 1.000000 0.822142 +vt 0.131950 0.144479 +vt 0.986002 0.688821 +vn -0.6386 -0.6215 -0.4538 +vn 1.0000 0.0000 0.0000 +vn -0.0000 -0.0000 1.0000 +vn -1.0000 -0.0000 0.0000 +vn -0.5439 -0.6983 -0.4653 +vn 0.0000 0.8079 0.5894 +vn -0.3836 -0.7971 -0.4663 +vn 0.8337 -0.4773 -0.2778 +vn -0.4443 -0.8652 -0.2322 +vn -0.3978 -0.8375 -0.3746 +vn -0.3147 -0.9434 0.1049 +vn -0.3536 -0.8998 -0.2557 +vn -0.0002 1.0000 0.0000 +vn 0.0000 1.0000 0.0002 +vn -0.2979 -0.8151 -0.4968 +vn -0.3596 -0.7901 -0.4964 +vn -0.3537 -0.7933 -0.4956 +vn 0.0000 -0.8468 -0.5320 +vn 0.0000 -0.8539 -0.5204 +vn -0.4908 -0.7163 -0.4960 +vn -0.5394 -0.7005 -0.4672 +vn -0.3986 -0.7716 -0.4958 +vn -0.4018 -0.7700 -0.4956 +vn 0.3888 -0.7751 -0.4981 +vn 0.4799 0.7345 0.4798 +vn 0.5152 0.7252 0.4567 +vn 0.4573 0.7934 0.4016 +vn 0.0018 1.0000 0.0018 +vn -0.5637 -0.6593 -0.4975 +vn -0.7074 0.0000 -0.7068 +vn -0.7761 0.0000 -0.6306 +vn -0.4420 0.7982 -0.4093 +vn -0.5670 -0.6570 -0.4969 +vn -0.6096 -0.6189 -0.4954 +vn -0.6419 -0.3408 -0.6869 +vn -0.5335 -0.6243 -0.5706 +vn 0.4458 -0.7524 -0.4849 +vn -0.6373 0.1277 0.7600 +vn -0.4680 -0.8837 0.0000 +vn -0.4562 -0.7388 -0.4960 +vn -0.4496 -0.7431 -0.4956 +vn -0.4233 -0.7580 -0.4963 +vn -0.3514 -0.7720 -0.5297 +vn -0.3369 -0.7777 -0.5308 +vn 0.3574 0.7545 0.5504 +vn 0.3530 0.7473 0.5629 +vn 0.0000 0.7114 0.7027 +vn -0.5014 -0.7085 -0.4966 +vn -0.5399 -0.6802 -0.4958 +vn -0.5082 -0.7032 -0.4973 +vn -0.5607 -0.6665 -0.4914 +usemtl None +s off +f 1223/1211/1752 1236/1212/1752 1244/1213/1752 +f 1213/1214/1753 1212/1215/1753 1214/1216/1753 +f 1213/1214/1753 1214/1216/1753 1217/1217/1753 +f 1212/1215/1754 1213/1214/1754 1218/1218/1754 +f 1216/1219/1755 1219/1220/1755 1223/1211/1755 +f 1216/1219/1756 1223/1211/1756 1224/1221/1756 +f 1219/1220/1755 1216/1219/1755 1225/1222/1755 +f 1225/1222/1757 1215/1223/1757 1228/1224/1757 +f 1219/1220/1755 1225/1222/1755 1228/1224/1755 +f 1221/1225/1758 1224/1221/1758 1229/1226/1758 +f 1214/1216/1753 1212/1215/1753 1230/1227/1753 +f 1212/1215/1759 1226/1228/1759 1230/1227/1759 +f 1212/1215/1754 1218/1218/1754 1231/1229/1754 +f 1216/1219/1760 1224/1221/1760 1231/1229/1760 +f 1224/1221/1761 1221/1225/1761 1231/1229/1761 +f 1226/1228/1762 1212/1215/1762 1231/1229/1762 +f 1221/1225/1763 1226/1228/1763 1231/1229/1763 +f 1228/1224/1764 1214/1216/1764 1232/1230/1764 +f 1219/1220/1755 1228/1224/1755 1232/1230/1755 +f 1217/1217/1753 1214/1216/1753 1233/1231/1753 +f 1214/1216/1764 1228/1224/1764 1233/1231/1764 +f 1228/1224/1765 1215/1223/1765 1233/1231/1765 +f 1226/1228/1766 1221/1225/1766 1234/1232/1766 +f 1229/1226/1767 1220/1233/1767 1234/1232/1767 +f 1221/1225/1768 1229/1226/1768 1234/1232/1768 +f 1220/1233/1769 1230/1227/1769 1234/1232/1769 +f 1230/1227/1770 1226/1228/1770 1234/1232/1770 +f 1223/1211/1771 1222/1234/1771 1235/1235/1771 +f 1224/1221/1772 1223/1211/1772 1235/1235/1772 +f 1223/1211/1755 1219/1220/1755 1236/1212/1755 +f 1220/1233/1773 1229/1226/1773 1237/1236/1773 +f 1229/1226/1774 1224/1221/1774 1237/1236/1774 +f 1230/1227/1775 1220/1233/1775 1237/1236/1775 +f 1215/1223/1776 1213/1214/1776 1238/1237/1776 +f 1213/1214/1777 1217/1217/1777 1238/1237/1777 +f 1217/1217/1778 1233/1231/1778 1238/1237/1778 +f 1233/1231/1779 1215/1223/1779 1238/1237/1779 +f 1227/1238/1780 1211/1239/1780 1239/1240/1780 +f 1214/1216/1781 1227/1238/1781 1239/1240/1781 +f 1219/1220/1782 1232/1230/1782 1239/1240/1782 +f 1232/1230/1783 1214/1216/1783 1239/1240/1783 +f 1211/1239/1784 1236/1212/1784 1239/1240/1784 +f 1236/1212/1785 1219/1220/1785 1239/1240/1785 +f 1227/1238/1786 1214/1216/1786 1240/1241/1786 +f 1222/1234/1787 1227/1238/1787 1240/1241/1787 +f 1214/1216/1753 1230/1227/1753 1240/1241/1753 +f 1230/1227/1788 1237/1236/1788 1240/1241/1788 +f 1218/1218/1789 1225/1222/1789 1241/1242/1789 +f 1225/1222/1755 1216/1219/1755 1241/1242/1755 +f 1231/1229/1754 1218/1218/1754 1241/1242/1754 +f 1216/1219/1790 1231/1229/1790 1241/1242/1790 +f 1235/1235/1791 1222/1234/1791 1242/1243/1791 +f 1224/1221/1792 1235/1235/1792 1242/1243/1792 +f 1237/1236/1793 1224/1221/1793 1242/1243/1793 +f 1222/1234/1794 1240/1241/1794 1242/1243/1794 +f 1240/1241/1795 1237/1236/1795 1242/1243/1795 +f 1213/1214/1796 1215/1223/1796 1243/1244/1796 +f 1218/1218/1797 1213/1214/1797 1243/1244/1797 +f 1215/1223/1757 1225/1222/1757 1243/1244/1757 +f 1225/1222/1798 1218/1218/1798 1243/1244/1798 +f 1222/1234/1799 1223/1211/1799 1244/1213/1799 +f 1211/1239/1800 1227/1238/1800 1244/1213/1800 +f 1227/1238/1801 1222/1234/1801 1244/1213/1801 +f 1236/1212/1802 1211/1239/1802 1244/1213/1802 +o Bowl_hull_39 +v -0.024582 -0.059067 0.015314 +v -0.013376 -0.081912 0.050235 +v -0.013376 -0.078461 0.050235 +v -0.013376 -0.040094 -0.021331 +v -0.025445 -0.040528 -0.004946 +v -0.025877 -0.075441 0.050235 +v -0.013376 -0.040528 -0.013996 +v -0.025877 -0.078457 0.048070 +v -0.025877 -0.040962 -0.011839 +v -0.014237 -0.042681 -0.017877 +v -0.013807 -0.080185 0.045919 +v -0.021996 -0.080185 0.048932 +v -0.025014 -0.075011 0.049793 +v -0.013376 -0.078032 0.049800 +v -0.025877 -0.040098 -0.005807 +v -0.020703 -0.040528 -0.017016 +v -0.013807 -0.054327 0.001520 +v -0.025014 -0.040098 -0.005807 +v -0.025877 -0.079321 0.050235 +v -0.025877 -0.050876 0.003244 +v -0.017686 -0.081478 0.049366 +v -0.025877 -0.040098 -0.012273 +v -0.013376 -0.040958 -0.020896 +v -0.013376 -0.081912 0.048939 +v -0.015963 -0.041821 -0.018304 +v -0.025445 -0.072424 0.037723 +v -0.013376 -0.040094 -0.014858 +v -0.025877 -0.073287 0.047208 +v -0.020271 -0.044842 -0.010550 +v -0.025877 -0.065956 0.027384 +vt 0.042287 0.041308 +vt 0.825176 0.773101 +vt 0.680697 0.618442 +vt 1.000000 0.917482 +vt 1.000000 1.000000 +vt 0.000000 0.000000 +vt 1.000000 0.845243 +vt 0.102486 0.010376 +vt 0.969753 0.917384 +vt 0.132635 0.020752 +vt 0.993833 0.834965 +vt 0.993931 0.907204 +vt 0.216915 0.000098 +vt 0.981793 0.958692 +vt 0.048258 0.061864 +vt 0.319303 0.340348 +vt 0.228955 0.010376 +vt 0.216915 0.000098 +vt 1.000000 0.938039 +vt 0.343383 0.257831 +vt 0.060298 0.010376 +vt 0.939702 0.958692 +vt 0.987862 0.989624 +vt 0.126566 0.000098 +vt 0.006069 0.020654 +vt 0.981891 1.000000 +vt 0.090446 0.000000 +vt 0.957713 0.793755 +vt 0.512040 0.453700 +vt 0.150646 0.113547 +vn -0.3055 -0.8129 -0.4957 +vn 1.0000 0.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn -1.0000 -0.0000 0.0000 +vn 0.1362 0.5634 0.8149 +vn 0.1810 0.6990 0.6918 +vn -0.2356 -0.8355 -0.4964 +vn 0.2136 0.8273 0.5195 +vn 0.3621 0.8036 0.4724 +vn 0.2144 0.8272 0.5194 +vn 0.0000 0.8948 0.4464 +vn -0.3144 -0.8817 -0.3518 +vn -0.4324 -0.7535 -0.4953 +vn -0.1570 -0.8534 -0.4970 +vn -0.2035 -0.8444 -0.4957 +vn -0.1802 -0.8695 0.4599 +vn -0.2677 -0.9486 -0.1685 +vn -0.0003 1.0000 0.0000 +vn -0.6504 -0.3413 -0.6786 +vn -0.2776 0.8812 -0.3827 +vn -0.4469 -0.4019 -0.7992 +vn -0.0823 -0.8552 -0.5116 +vn 0.4075 -0.7877 -0.4620 +vn 0.0621 -0.8625 -0.5023 +vn -0.1002 -0.9950 -0.0000 +vn -0.1347 -0.8682 -0.4775 +vn -0.3582 -0.7180 -0.5968 +vn -0.2673 -0.8021 -0.5341 +vn -0.2566 -0.8298 -0.4956 +vn -0.2594 -0.8295 -0.4946 +vn -0.2856 -0.8199 -0.4962 +vn 0.3299 0.8431 0.4246 +vn 0.0000 1.0000 0.0005 +vn 0.0950 0.8426 0.5301 +vn -0.1087 0.8100 0.5763 +vn -0.2103 0.8287 0.5188 +vn -0.3694 -0.7869 -0.4943 +vn -0.3794 -0.7811 -0.4959 +vn -0.3311 -0.8024 -0.4965 +vn -0.3522 -0.7892 -0.5031 +vn -0.3922 -0.7802 -0.4874 +vn -0.3138 -0.8097 -0.4958 +vn -0.3981 -0.7851 -0.4745 +usemtl None +s off +f 1269/1245/1803 1270/1246/1803 1274/1247/1803 +f 1247/1248/1804 1246/1249/1804 1248/1250/1804 +f 1246/1249/1805 1247/1248/1805 1250/1251/1805 +f 1247/1248/1804 1248/1250/1804 1251/1252/1804 +f 1252/1253/1806 1250/1251/1806 1253/1254/1806 +f 1250/1251/1807 1247/1248/1807 1257/1255/1807 +f 1247/1248/1804 1251/1252/1804 1258/1256/1804 +f 1257/1255/1808 1247/1248/1808 1258/1256/1808 +f 1253/1254/1806 1250/1251/1806 1259/1257/1806 +f 1256/1258/1809 1254/1259/1809 1261/1260/1809 +f 1249/1261/1810 1257/1255/1810 1262/1262/1810 +f 1258/1256/1811 1251/1252/1811 1262/1262/1811 +f 1257/1255/1812 1258/1256/1812 1262/1262/1812 +f 1259/1257/1813 1249/1261/1813 1262/1262/1813 +f 1246/1249/1805 1250/1251/1805 1263/1263/1805 +f 1250/1251/1806 1252/1253/1806 1263/1263/1806 +f 1252/1253/1814 1256/1258/1814 1263/1263/1814 +f 1252/1253/1806 1253/1254/1806 1264/1264/1806 +f 1253/1254/1815 1260/1265/1815 1264/1264/1815 +f 1261/1260/1816 1255/1266/1816 1265/1267/1816 +f 1256/1258/1817 1261/1260/1817 1265/1267/1817 +f 1246/1249/1818 1263/1263/1818 1265/1267/1818 +f 1263/1263/1819 1256/1258/1819 1265/1267/1819 +f 1259/1257/1820 1248/1250/1820 1266/1268/1820 +f 1253/1254/1806 1259/1257/1806 1266/1268/1806 +f 1260/1265/1821 1253/1254/1821 1266/1268/1821 +f 1248/1250/1822 1260/1265/1822 1266/1268/1822 +f 1248/1250/1804 1246/1249/1804 1267/1269/1804 +f 1260/1265/1823 1248/1250/1823 1267/1269/1823 +f 1261/1260/1824 1254/1259/1824 1267/1269/1824 +f 1261/1260/1825 1267/1269/1825 1268/1270/1825 +f 1255/1266/1826 1261/1260/1826 1268/1270/1826 +f 1246/1249/1827 1265/1267/1827 1268/1270/1827 +f 1265/1267/1828 1255/1266/1828 1268/1270/1828 +f 1267/1269/1804 1246/1249/1804 1268/1270/1804 +f 1260/1265/1829 1267/1269/1829 1269/1245/1829 +f 1267/1269/1830 1254/1259/1830 1269/1245/1830 +f 1254/1259/1831 1256/1258/1831 1270/1246/1831 +f 1256/1258/1832 1252/1253/1832 1270/1246/1832 +f 1269/1245/1833 1254/1259/1833 1270/1246/1833 +f 1251/1252/1804 1248/1250/1804 1271/1271/1804 +f 1248/1250/1820 1259/1257/1820 1271/1271/1820 +f 1262/1262/1834 1251/1252/1834 1271/1271/1834 +f 1259/1257/1835 1262/1262/1835 1271/1271/1835 +f 1257/1255/1836 1249/1261/1836 1272/1272/1836 +f 1250/1251/1837 1257/1255/1837 1272/1272/1837 +f 1249/1261/1838 1259/1257/1838 1272/1272/1838 +f 1259/1257/1806 1250/1251/1806 1272/1272/1806 +f 1245/1273/1839 1264/1264/1839 1273/1274/1839 +f 1264/1264/1840 1260/1265/1840 1273/1274/1840 +f 1269/1245/1841 1245/1273/1841 1273/1274/1841 +f 1260/1265/1842 1269/1245/1842 1273/1274/1842 +f 1264/1264/1843 1245/1273/1843 1274/1247/1843 +f 1252/1253/1806 1264/1264/1806 1274/1247/1806 +f 1245/1273/1844 1269/1245/1844 1274/1247/1844 +f 1270/1246/1845 1252/1253/1845 1274/1247/1845 diff --git a/cram_pr2/cram_pr2_pick_place_demo/resource/breakfast_cereal.stl b/cram_demos/cram_projection_demos/resource/household/breakfast_cereal.stl similarity index 100% rename from cram_pr2/cram_pr2_pick_place_demo/resource/breakfast_cereal.stl rename to cram_demos/cram_projection_demos/resource/household/breakfast_cereal.stl diff --git a/cram_pr2/cram_pr2_pick_place_demo/resource/buttermilk.dae b/cram_demos/cram_projection_demos/resource/household/buttermilk.dae similarity index 100% rename from cram_pr2/cram_pr2_pick_place_demo/resource/buttermilk.dae rename to cram_demos/cram_projection_demos/resource/household/buttermilk.dae diff --git a/cram_pr2/cram_pr2_pick_place_demo/resource/cereal.dae b/cram_demos/cram_projection_demos/resource/household/cereal.dae similarity index 100% rename from cram_pr2/cram_pr2_pick_place_demo/resource/cereal.dae rename to cram_demos/cram_projection_demos/resource/household/cereal.dae diff --git a/cram_demos/cram_projection_demos/resource/household/cube.stl b/cram_demos/cram_projection_demos/resource/household/cube.stl new file mode 100644 index 0000000000..7202c452ee Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/household/cube.stl differ diff --git a/cram_demos/cram_projection_demos/resource/household/cup.obj b/cram_demos/cram_projection_demos/resource/household/cup.obj new file mode 100644 index 0000000000..6f38a826b1 --- /dev/null +++ b/cram_demos/cram_projection_demos/resource/household/cup.obj @@ -0,0 +1,4111 @@ +# Blender v2.83.4 OBJ File: '' +# www.blender.org +mtllib cup_33.mtl +o Cup_hull_1 +v 0.014889 0.020425 -0.050166 +v -0.014857 -0.020390 -0.048198 +v -0.015384 -0.020122 -0.048198 +v 0.014889 0.020425 -0.048198 +v 0.019895 -0.015647 -0.050166 +v -0.020386 0.014891 -0.050166 +v -0.015648 0.019893 -0.048198 +v 0.020427 -0.014856 -0.048198 +v -0.015384 -0.020122 -0.050166 +v -0.020390 -0.014856 -0.048198 +v 0.020423 0.014891 -0.050166 +v 0.014893 -0.020390 -0.048198 +v -0.014857 0.020425 -0.050166 +v 0.020423 0.014891 -0.048198 +v 0.014893 -0.020390 -0.050166 +v -0.020390 -0.014856 -0.050166 +v -0.020386 0.014891 -0.048198 +v 0.020427 -0.014856 -0.050166 +v -0.014857 0.020425 -0.048198 +v -0.014857 -0.020390 -0.050166 +v 0.018577 0.017260 -0.048198 +v -0.018808 0.016997 -0.050166 +v 0.016999 -0.018807 -0.048198 +v -0.019072 -0.016702 -0.048198 +v 0.017258 0.018579 -0.050166 +v -0.016702 -0.019071 -0.050166 +v -0.018808 0.016997 -0.048198 +v 0.016999 -0.018807 -0.050166 +v -0.016966 0.018839 -0.050166 +v 0.018840 -0.016966 -0.048198 +v -0.019072 -0.016702 -0.050166 +vt 0.090348 0.032302 +vt 0.032302 0.090348 +vt 0.032302 0.090348 +vt 0.122651 0.006558 +vt 0.135572 0.000000 +vt 0.864330 1.000000 +vt 0.864330 1.000000 +vt 0.986981 0.116190 +vt 0.000098 0.864428 +vt 0.116190 0.986981 +vt 1.000000 0.135572 +vt 0.122651 0.006558 +vt 0.000000 0.135572 +vt 0.999902 0.864428 +vt 0.864428 0.000000 +vt 0.135572 1.000000 +vt 0.999902 0.864428 +vt 0.864428 0.000000 +vt 0.000000 0.135572 +vt 0.000098 0.864428 +vt 1.000000 0.135572 +vt 0.135572 1.000000 +vt 0.135572 0.000000 +vt 0.954679 0.922475 +vt 0.038763 0.916014 +vt 0.916014 0.038763 +vt 0.922377 0.954777 +vt 0.038763 0.916014 +vt 0.916014 0.038763 +vt 0.083888 0.961139 +vt 0.961139 0.083888 +vn -0.7071 -0.7071 0.0000 +vn 0.0000 0.0000 1.0000 +vn -0.0000 0.0000 -1.0000 +vn -0.4526 -0.8917 0.0000 +vn 0.0000 1.0000 0.0000 +vn 1.0000 0.0001 0.0000 +vn 0.0000 -1.0000 0.0000 +vn -1.0000 0.0001 0.0000 +vn 0.8301 -0.5576 0.0000 +vn -0.5576 0.8301 0.0000 +vn 0.7888 0.6146 0.0000 +vn -0.8002 0.5998 0.0000 +vn 0.6007 -0.7995 0.0000 +vn -0.8137 -0.5813 0.0000 +vn 0.6146 0.7889 0.0000 +vn 0.6495 0.7570 0.0720 +vn 0.7569 0.6495 -0.0720 +vn -0.6232 -0.7820 0.0000 +vn -0.6786 -0.7317 0.0640 +vn -0.6007 0.7990 -0.0258 +vn -0.6745 0.7360 0.0575 +vn -0.7071 0.7071 0.0000 +vn 0.7990 -0.6008 0.0258 +vn 0.7360 -0.6746 -0.0575 +vn 0.7071 -0.7071 0.0000 +usemtl None +s off +f 26/1/1 24/2/1 31/3/1 +f 3/4/2 2/5/2 4/6/2 +f 1/7/3 5/8/3 6/9/3 +f 3/4/2 4/6/2 7/10/2 +f 4/6/2 2/5/2 8/11/2 +f 2/5/4 3/4/4 9/12/4 +f 6/9/3 5/8/3 9/12/3 +f 3/4/2 7/10/2 10/13/2 +f 5/8/3 1/7/3 11/14/3 +f 8/11/2 2/5/2 12/15/2 +f 4/6/5 1/7/5 13/16/5 +f 1/7/3 6/9/3 13/16/3 +f 4/6/2 8/11/2 14/17/2 +f 8/11/6 11/14/6 14/17/6 +f 9/12/3 5/8/3 15/18/3 +f 12/15/7 2/5/7 15/18/7 +f 6/9/3 9/12/3 16/19/3 +f 10/13/8 6/9/8 16/19/8 +f 6/9/8 10/13/8 17/20/8 +f 10/13/2 7/10/2 17/20/2 +f 8/11/9 5/8/9 18/21/9 +f 5/8/3 11/14/3 18/21/3 +f 11/14/6 8/11/6 18/21/6 +f 7/10/2 4/6/2 19/22/2 +f 4/6/5 13/16/5 19/22/5 +f 13/16/10 7/10/10 19/22/10 +f 2/5/4 9/12/4 20/23/4 +f 15/18/7 2/5/7 20/23/7 +f 9/12/3 15/18/3 20/23/3 +f 4/6/2 14/17/2 21/24/2 +f 14/17/11 11/14/11 21/24/11 +f 13/16/3 6/9/3 22/25/3 +f 6/9/12 17/20/12 22/25/12 +f 8/11/2 12/15/2 23/26/2 +f 12/15/13 15/18/13 23/26/13 +f 3/4/2 10/13/2 24/2/2 +f 10/13/14 16/19/14 24/2/14 +f 1/7/15 4/6/15 25/27/15 +f 11/14/3 1/7/3 25/27/3 +f 4/6/16 21/24/16 25/27/16 +f 21/24/17 11/14/17 25/27/17 +f 9/12/18 3/4/18 26/1/18 +f 16/19/3 9/12/3 26/1/3 +f 3/4/19 24/2/19 26/1/19 +f 17/20/2 7/10/2 27/28/2 +f 22/25/12 17/20/12 27/28/12 +f 15/18/3 5/8/3 28/29/3 +f 23/26/13 15/18/13 28/29/13 +f 7/10/20 13/16/20 29/30/20 +f 13/16/3 22/25/3 29/30/3 +f 27/28/21 7/10/21 29/30/21 +f 22/25/22 27/28/22 29/30/22 +f 5/8/23 8/11/23 30/31/23 +f 8/11/2 23/26/2 30/31/2 +f 28/29/24 5/8/24 30/31/24 +f 23/26/25 28/29/25 30/31/25 +f 24/2/14 16/19/14 31/3/14 +f 16/19/3 26/1/3 31/3/3 +o Cup_hull_2 +v 0.020427 0.005943 -0.048198 +v 0.013054 0.012263 0.015036 +v 0.013317 0.011736 0.013909 +v 0.020427 0.012526 0.015036 +v 0.013054 0.012526 -0.048198 +v 0.017003 0.005943 0.015036 +v 0.020427 0.012526 -0.048198 +v 0.016740 0.006206 -0.048198 +v 0.020427 0.005943 0.015036 +v 0.013054 0.012526 0.015036 +v 0.013317 0.011736 -0.048198 +v 0.017003 0.005943 -0.048198 +v 0.016740 0.006206 0.015036 +v 0.013054 0.012263 -0.048198 +vt 1.000000 0.000000 +vt 1.000000 0.035732 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 0.000000 0.535683 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.499951 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 0.017815 0.035732 +vt 1.000000 0.535683 +vt 0.000000 0.499951 +vn 0.0000 0.0000 -1.0000 +vn -0.0000 0.0000 1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.8945 -0.4470 0.0000 +vn -0.8503 -0.5263 0.0000 +vn -0.7073 -0.7069 0.0000 +vn -0.8534 -0.5194 0.0435 +usemtl None +s off +f 36/32/26 42/33/26 45/34/26 +f 35/35/27 33/36/27 37/37/27 +f 35/35/28 32/38/28 38/39/28 +f 32/38/26 36/32/26 38/39/26 +f 36/32/29 35/35/29 38/39/29 +f 36/32/26 32/38/26 39/40/26 +f 32/38/28 35/35/28 40/41/28 +f 35/35/27 37/37/27 40/41/27 +f 37/37/30 32/38/30 40/41/30 +f 33/36/27 35/35/27 41/42/27 +f 35/35/29 36/32/29 41/42/29 +f 36/32/31 33/36/31 41/42/31 +f 34/43/32 33/36/32 42/33/32 +f 36/32/26 39/40/26 42/33/26 +f 39/40/33 34/43/33 42/33/33 +f 32/38/30 37/37/30 43/44/30 +f 39/40/26 32/38/26 43/44/26 +f 37/37/34 39/40/34 43/44/34 +f 33/36/35 34/43/35 44/45/35 +f 37/37/27 33/36/27 44/45/27 +f 34/43/33 39/40/33 44/45/33 +f 39/40/34 37/37/34 44/45/34 +f 33/36/31 36/32/31 45/34/31 +f 42/33/32 33/36/32 45/34/32 +o Cup_hull_3 +v -0.012229 0.013316 -0.048198 +v -0.020392 0.007259 0.015036 +v -0.016442 0.007259 0.015036 +v -0.020392 0.013316 0.015036 +v -0.020392 0.007259 -0.048198 +v -0.020392 0.013316 -0.048198 +v -0.012229 0.013316 0.015036 +v -0.016442 0.007259 -0.048198 +v -0.012229 0.013053 0.015036 +v -0.012229 0.013053 -0.048198 +v -0.016179 0.007523 -0.048198 +v -0.016179 0.007523 0.015036 +vt 1.000000 0.516104 +vt 0.000000 1.000000 +vt 0.000000 0.516104 +vt 0.000000 0.000000 +vt 0.000000 0.483896 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 0.483896 +vt 1.000000 1.000000 +vn 0.8137 -0.5813 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0001 1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.7084 -0.7059 0.0000 +vn 0.0001 0.0000 -1.0000 +usemtl None +s off +f 56/46/36 54/47/36 57/48/36 +f 47/49/37 48/50/37 49/51/37 +f 48/50/38 47/49/38 50/52/38 +f 47/49/39 49/51/39 50/52/39 +f 49/51/40 46/53/40 51/54/40 +f 46/53/41 50/52/41 51/54/41 +f 50/52/39 49/51/39 51/54/39 +f 49/51/37 48/50/37 52/55/37 +f 46/53/40 49/51/40 52/55/40 +f 50/52/41 46/53/41 53/56/41 +f 48/50/38 50/52/38 53/56/38 +f 46/53/42 52/55/42 54/47/42 +f 52/55/37 48/50/37 54/47/37 +f 53/56/41 46/53/41 55/57/41 +f 46/53/42 54/47/42 55/57/42 +f 48/50/43 53/56/43 56/46/43 +f 53/56/44 55/57/44 56/46/44 +f 55/57/36 54/47/36 56/46/36 +f 54/47/37 48/50/37 57/48/37 +f 48/50/43 56/46/43 57/48/43 +o Cup_hull_4 +v 0.017003 0.005679 0.015036 +v 0.020427 0.005943 -0.048198 +v 0.020427 -0.000377 -0.048198 +v 0.017003 0.005943 -0.048198 +v 0.020427 0.005943 0.015036 +v 0.018057 -0.000377 0.015036 +v 0.018057 -0.000377 -0.048198 +v 0.020427 -0.000377 0.015036 +v 0.017003 0.005943 0.015036 +v 0.017003 0.005415 -0.048198 +v 0.017003 0.005415 0.014751 +vt 1.000000 0.916504 +vt 0.000000 0.000000 +vt 0.004503 0.916504 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 1.000000 1.000000 +vt 0.000000 1.000000 +vt 0.000000 0.958203 +vt 1.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vn -0.9839 -0.1790 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.0001 0.0000 -1.0000 +vn -0.9730 -0.1693 0.1567 +usemtl None +s off +f 67/58/45 63/59/45 68/60/45 +f 59/61/46 60/62/46 61/63/46 +f 60/62/47 59/61/47 62/64/47 +f 59/61/48 61/63/48 62/64/48 +f 62/64/49 58/65/49 63/59/49 +f 61/63/46 60/62/46 64/66/46 +f 60/62/50 63/59/50 64/66/50 +f 60/62/47 62/64/47 65/67/47 +f 63/59/50 60/62/50 65/67/50 +f 62/64/49 63/59/49 65/67/49 +f 61/63/51 58/65/51 66/68/51 +f 58/65/49 62/64/49 66/68/49 +f 62/64/48 61/63/48 66/68/48 +f 58/65/51 61/63/51 67/58/51 +f 61/63/52 64/66/52 67/58/52 +f 64/66/45 63/59/45 67/58/45 +f 63/59/53 58/65/53 68/60/53 +f 58/65/51 67/58/51 68/60/51 +o Cup_hull_5 +v -0.002748 -0.025132 0.032181 +v -0.013281 -0.021446 0.050166 +v -0.013017 -0.021708 0.050166 +v 0.000413 -0.024341 0.050166 +v -0.012753 -0.018548 0.032181 +v 0.000413 -0.022761 0.032181 +v -0.013017 -0.021708 0.032181 +v -0.006961 -0.024342 0.050166 +v -0.012753 -0.020392 0.050166 +v 0.000413 -0.025132 0.050166 +v -0.009330 -0.023552 0.032181 +v 0.000413 -0.025132 0.032181 +v 0.000413 -0.024078 0.048477 +v -0.002485 -0.025132 0.050166 +v -0.013281 -0.018548 0.033306 +v -0.005909 -0.024605 0.032181 +v -0.009856 -0.023288 0.050166 +v 0.000413 -0.022761 0.033306 +v -0.013281 -0.021446 0.032181 +v -0.004591 -0.024868 0.050166 +v -0.013017 -0.018548 0.033306 +v -0.013281 -0.020392 0.050166 +v -0.006961 -0.024342 0.034992 +v -0.004591 -0.024868 0.032181 +v -0.008540 -0.023814 0.050166 +v -0.012753 -0.018548 0.032462 +vt 1.000000 0.038567 +vt 0.937451 0.019284 +vt 0.984338 0.038567 +vt 0.000000 0.000000 +vt 0.000000 0.019284 +vt 0.000000 1.000000 +vt 1.000000 0.769186 +vt 1.000000 1.000000 +vt 1.000000 0.019284 +vt 0.000000 0.461531 +vt 0.000000 0.038567 +vt 0.000000 1.000000 +vt 1.000000 0.288567 +vt 1.000000 1.000000 +vt 0.093872 1.000000 +vt 0.000000 0.788371 +vt 1.000000 0.538371 +vt 0.000000 0.250098 +vt 0.937451 1.000000 +vt 1.000000 0.000000 +vt 0.937451 0.000000 +vt 0.000000 0.634593 +vt 0.000000 0.000000 +vt 0.843677 0.461531 +vt 1.000000 0.634593 +vt 0.000000 0.346222 +vn 0.0000 1.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn -0.7047 -0.7095 0.0000 +vn 1.0000 0.0000 0.0000 +vn -0.4471 -0.8945 0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.2842 0.9474 0.1475 +vn -0.4470 -0.8945 0.0000 +vn 0.3048 0.9524 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.8931 0.1628 -0.4193 +vn -0.1242 -0.9923 0.0018 +vn -0.2169 -0.9762 0.0016 +vn 0.2801 0.9547 0.1000 +vn 0.0000 0.9941 0.1087 +vn -0.3164 -0.9486 0.0000 +vn -0.2941 -0.9555 -0.0207 +vn -0.2424 -0.9702 0.0000 +vn -0.1416 -0.9899 0.0000 +vn -0.1962 -0.9806 0.0000 +vn -0.3167 -0.9485 0.0000 +vn -0.3714 -0.9285 0.0027 +vn 0.2990 0.9507 0.0825 +vn 0.2898 0.9528 0.0907 +usemtl None +s off +f 73/69/54 89/70/54 94/71/54 +f 70/72/55 71/73/55 72/74/55 +f 69/75/56 73/69/56 74/76/56 +f 71/73/57 70/72/57 75/77/57 +f 73/69/56 69/75/56 75/77/56 +f 72/74/55 71/73/55 76/78/55 +f 70/72/55 72/74/55 77/79/55 +f 74/76/58 72/74/58 78/80/58 +f 72/74/55 76/78/55 78/80/55 +f 75/77/56 69/75/56 79/81/56 +f 71/73/59 75/77/59 79/81/59 +f 69/75/56 74/76/56 80/82/56 +f 78/80/60 69/75/60 80/82/60 +f 74/76/58 78/80/58 80/82/58 +f 72/74/58 74/76/58 81/83/58 +f 77/79/61 72/74/61 81/83/61 +f 69/75/60 78/80/60 82/84/60 +f 78/80/55 76/78/55 82/84/55 +f 79/81/56 69/75/56 84/85/56 +f 76/78/55 71/73/55 85/86/55 +f 71/73/62 79/81/62 85/86/62 +f 74/76/63 73/69/63 86/87/63 +f 81/83/58 74/76/58 86/87/58 +f 75/77/57 70/72/57 87/88/57 +f 73/69/56 75/77/56 87/88/56 +f 70/72/64 83/89/64 87/88/64 +f 83/89/65 73/69/65 87/88/65 +f 69/75/66 82/84/66 88/90/66 +f 82/84/55 76/78/55 88/90/55 +f 76/78/67 84/85/67 88/90/67 +f 77/79/68 81/83/68 89/70/68 +f 73/69/54 83/89/54 89/70/54 +f 83/89/69 77/79/69 89/70/69 +f 70/72/55 77/79/55 90/91/55 +f 83/89/64 70/72/64 90/91/64 +f 77/79/69 83/89/69 90/91/69 +f 76/78/70 79/81/70 91/92/70 +f 79/81/71 84/85/71 91/92/71 +f 84/85/72 76/78/72 91/92/72 +f 84/85/56 69/75/56 92/93/56 +f 69/75/73 88/90/73 92/93/73 +f 88/90/74 84/85/74 92/93/74 +f 79/81/75 76/78/75 93/94/75 +f 76/78/55 85/86/55 93/94/55 +f 85/86/76 79/81/76 93/94/76 +f 86/87/63 73/69/63 94/71/63 +f 81/83/77 86/87/77 94/71/77 +f 89/70/78 81/83/78 94/71/78 +o Cup_hull_6 +v -0.004591 -0.024868 0.018410 +v -0.013281 -0.021443 0.032177 +v -0.013017 -0.021707 0.032177 +v 0.000413 -0.022497 0.031895 +v -0.013017 -0.012229 0.015037 +v 0.000413 -0.018023 0.015037 +v -0.013281 -0.020390 0.015037 +v -0.013281 -0.018286 0.032177 +v 0.000413 -0.025130 0.032177 +v 0.000413 -0.024868 0.017286 +v -0.005909 -0.024605 0.032177 +v -0.009330 -0.023550 0.018410 +v -0.013017 -0.012756 0.017286 +v 0.000413 -0.020654 0.015037 +v 0.000413 -0.018548 0.018130 +v -0.013017 -0.021707 0.018130 +v -0.013281 -0.012229 0.015037 +v -0.009330 -0.023550 0.032177 +v -0.001695 -0.024341 0.016724 +v -0.002485 -0.025130 0.018410 +v -0.002485 -0.025130 0.032177 +v -0.005382 -0.024341 0.017286 +v -0.013017 -0.018286 0.032177 +v 0.000413 -0.025130 0.017848 +v -0.007751 -0.024077 0.018130 +v 0.000413 -0.022761 0.032177 +v 0.000413 -0.018023 0.015881 +v -0.013017 -0.012493 0.016444 +v -0.008804 -0.020654 0.015037 +v -0.013281 -0.021443 0.017848 +v -0.009068 -0.023288 0.017286 +v -0.005909 -0.024605 0.018410 +v -0.004591 -0.024868 0.032177 +v -0.002485 -0.024604 0.017006 +v -0.010910 -0.022761 0.017848 +v 0.000413 -0.024341 0.016724 +v -0.007751 -0.024077 0.032177 +vt 0.000000 0.288567 +vt 0.819561 0.403876 +vt 0.000000 0.403876 +vt 1.000000 0.019284 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.019284 +vt 0.016448 1.000000 +vt 0.000000 1.000000 +vt 0.868807 1.000000 +vt 0.000000 0.538371 +vt 1.000000 1.000000 +vt 0.819561 1.000000 +vt 0.819561 0.019284 +vt 1.000000 0.000000 +vt 0.868807 0.019284 +vt 0.000000 0.788371 +vt 0.803211 0.788371 +vt 0.803211 0.634593 +vt 0.000000 0.019284 +vt 0.836009 1.000000 +vt 0.803211 0.288567 +vt 0.000000 1.000000 +vt 0.950754 1.000000 +vt 0.917956 0.019284 +vt 1.000000 0.326938 +vt 0.901606 0.846124 +vt 0.836009 0.000000 +vt 0.868807 0.576840 +vt 0.868807 0.307655 +vt 0.803211 0.538371 +vt 0.000000 0.634593 +vt 0.885158 0.788371 +vt 0.836009 0.173160 +vt 0.901606 1.000000 +vn -0.3164 -0.9486 0.0000 +vn 0.0000 0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 1.0000 -0.0000 0.0000 +vn -0.7070 -0.7072 0.0000 +vn -0.6912 0.6814 0.2408 +vn 0.0000 -1.0000 0.0000 +vn -0.1238 -0.9923 0.0000 +vn 0.2885 0.8976 0.3333 +vn 0.0000 0.9375 0.3481 +vn 0.2363 0.7093 0.6641 +vn 0.3961 0.9182 0.0000 +vn 0.3797 0.9008 0.2105 +vn 0.3458 0.8958 0.2794 +vn 0.3704 0.8929 0.2561 +vn 0.0000 0.9828 0.1845 +vn -0.5337 0.8073 0.2518 +vn 0.3813 0.9086 0.1706 +vn -0.0270 -0.4585 -0.8883 +vn 0.0000 -0.4160 -0.9094 +vn -0.4896 -0.8165 -0.3060 +vn -0.2225 -0.7788 -0.5865 +vn -0.2486 -0.8701 -0.4256 +vn -0.1955 -0.9807 0.0000 +vn -0.1861 -0.9335 -0.3064 +vn -0.2756 -0.9613 0.0000 +vn -0.2162 -0.9231 -0.3180 +vn -0.0868 -0.5956 -0.7986 +vn -0.0006 -0.7308 -0.6826 +vn -0.1160 -0.9300 -0.3487 +vn -0.1183 -0.9286 -0.3518 +vn -0.1315 -0.6757 -0.7254 +vn -0.0415 -0.9052 -0.4230 +vn -0.0680 -0.9342 -0.3503 +vn -0.4472 -0.8945 0.0000 +vn -0.4578 -0.8314 -0.3151 +vn -0.4470 -0.8945 0.0000 +vn -0.4469 -0.8946 0.0000 +vn -0.3480 -0.8951 -0.2786 +vn -0.3632 -0.8403 -0.4024 +vn -0.3449 -0.8911 -0.2950 +vn 0.0000 -0.7297 -0.6837 +usemtl None +s off +f 112/95/79 119/96/79 131/97/79 +f 99/98/80 100/99/80 101/100/80 +f 101/100/81 96/101/81 102/102/81 +f 96/101/82 97/103/82 102/102/82 +f 100/99/83 98/104/83 103/105/83 +f 102/102/82 97/103/82 103/105/82 +f 100/99/83 103/105/83 104/106/83 +f 103/105/82 97/103/82 105/107/82 +f 101/100/80 100/99/80 108/108/80 +f 100/99/83 104/106/83 108/108/83 +f 98/104/83 100/99/83 109/109/83 +f 97/103/84 96/101/84 110/110/84 +f 99/98/80 101/100/80 111/111/80 +f 101/100/81 102/102/81 111/111/81 +f 102/102/85 107/112/85 111/111/85 +f 105/107/82 97/103/82 112/95/82 +f 103/105/82 105/107/82 115/113/82 +f 114/114/86 103/105/86 115/113/86 +f 95/115/87 114/114/87 115/113/87 +f 102/102/82 103/105/82 117/116/82 +f 98/104/88 107/112/88 117/116/88 +f 107/112/89 102/102/89 117/116/89 +f 104/106/83 103/105/83 118/117/83 +f 103/105/86 114/114/86 118/117/86 +f 112/95/79 106/118/79 119/96/79 +f 103/105/83 98/104/83 120/119/83 +f 98/104/90 117/116/90 120/119/90 +f 117/116/82 103/105/82 120/119/82 +f 100/99/91 99/98/91 121/120/91 +f 109/109/83 100/99/83 121/120/83 +f 109/109/92 121/120/92 122/121/92 +f 107/112/93 98/104/93 122/121/93 +f 98/104/94 109/109/94 122/121/94 +f 99/98/95 111/111/95 122/121/95 +f 111/111/96 107/112/96 122/121/96 +f 121/120/97 99/98/97 122/121/97 +f 101/100/80 108/108/80 123/122/80 +f 113/123/98 101/100/98 123/122/98 +f 108/108/99 113/123/99 123/122/99 +f 96/101/81 101/100/81 124/124/81 +f 110/110/84 96/101/84 124/124/84 +f 101/100/100 110/110/100 124/124/100 +f 101/100/101 116/125/101 125/126/101 +f 116/125/102 119/96/102 125/126/102 +f 95/115/103 105/107/103 126/127/103 +f 116/125/104 95/115/104 126/127/104 +f 105/107/105 119/96/105 126/127/105 +f 119/96/106 116/125/106 126/127/106 +f 105/107/103 95/115/103 127/128/103 +f 95/115/87 115/113/87 127/128/87 +f 115/113/82 105/107/82 127/128/82 +f 101/100/107 113/123/107 128/129/107 +f 113/123/108 104/106/108 128/129/108 +f 114/114/109 95/115/109 128/129/109 +f 95/115/110 116/125/110 128/129/110 +f 116/125/111 101/100/111 128/129/111 +f 104/106/112 118/117/112 128/129/112 +f 118/117/113 114/114/113 128/129/113 +f 97/103/114 110/110/114 129/130/114 +f 110/110/115 101/100/115 129/130/115 +f 112/95/116 97/103/116 129/130/116 +f 106/118/117 112/95/117 129/130/117 +f 119/96/118 106/118/118 129/130/118 +f 101/100/119 125/126/119 129/130/119 +f 125/126/120 119/96/120 129/130/120 +f 108/108/83 104/106/83 130/131/83 +f 104/106/121 113/123/121 130/131/121 +f 113/123/99 108/108/99 130/131/99 +f 105/107/82 112/95/82 131/97/82 +f 119/96/105 105/107/105 131/97/105 +o Cup_hull_7 +v -0.006700 0.024377 0.032460 +v -0.014335 0.019637 0.050164 +v -0.013806 0.019637 0.050164 +v -0.014335 0.017795 0.032460 +v 0.000413 0.024113 0.050164 +v 0.000413 0.022797 0.032460 +v -0.006700 0.024377 0.050164 +v -0.013806 0.021217 0.032460 +v 0.000413 0.025167 0.032460 +v -0.013017 0.021742 0.050164 +v -0.002222 0.025167 0.050164 +v -0.014070 0.017795 0.033306 +v -0.009855 0.023323 0.032460 +v 0.000413 0.025167 0.050164 +v -0.004328 0.024903 0.032460 +v -0.014335 0.020691 0.032460 +v -0.009855 0.023323 0.050164 +v -0.014335 0.020691 0.050164 +v 0.000413 0.022797 0.033586 +v -0.002222 0.025167 0.032460 +v -0.004328 0.024903 0.050164 +v -0.013017 0.021742 0.032460 +v -0.013806 0.021217 0.050164 +v -0.005646 0.024639 0.050164 +vt 0.000000 0.678543 +vt 1.000000 0.678543 +vt 0.000000 0.589174 +vt 0.000000 0.000000 +vt 0.000000 0.035826 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 1.000000 0.517717 +vt 1.000000 1.000000 +vt 0.000000 0.517717 +vt 1.000000 0.035826 +vt 1.000000 1.000000 +vt 0.000000 0.089370 +vt 0.000000 0.821359 +vt 0.952232 0.017913 +vt 1.000000 0.303739 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.303739 +vt 0.000000 0.000000 +vt 0.936374 1.000000 +vt 1.000000 0.821359 +vt 1.000000 0.089370 +vt 0.000000 0.035826 +vn -0.1960 0.9806 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 -0.9941 0.1086 +vn -0.3146 -0.9441 0.0983 +vn 0.2988 -0.9492 0.0991 +vn 0.3196 -0.9423 -0.0998 +vn -0.3167 0.9485 0.0000 +vn 0.0000 1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.4472 0.8944 0.0000 +vn -0.7056 0.7086 0.0000 +vn 0.3242 -0.9430 0.0749 +vn 0.3265 -0.9452 0.0000 +vn -0.1244 0.9922 0.0000 +vn -0.5540 0.8325 0.0000 +vn -0.2419 0.9703 0.0000 +vn -0.2166 0.9763 -0.0016 +usemtl None +s off +f 152/132/122 146/133/122 155/134/122 +f 133/135/123 134/136/123 136/137/123 +f 135/138/124 132/139/124 137/140/124 +f 133/135/123 136/137/123 138/141/123 +f 132/139/124 135/138/124 139/142/124 +f 137/140/124 132/139/124 140/143/124 +f 136/137/125 137/140/125 140/143/125 +f 133/135/123 138/141/123 141/144/123 +f 138/141/123 136/137/123 142/145/123 +f 134/136/126 133/135/126 143/146/126 +f 133/135/127 135/138/127 143/146/127 +f 136/137/128 134/136/128 143/146/128 +f 135/138/129 137/140/129 143/146/129 +f 138/141/130 132/139/130 144/147/130 +f 132/139/124 139/142/124 144/147/124 +f 136/137/125 140/143/125 145/148/125 +f 142/145/123 136/137/123 145/148/123 +f 140/143/131 142/145/131 145/148/131 +f 140/143/124 132/139/124 146/133/124 +f 135/138/132 133/135/132 147/149/132 +f 139/142/124 135/138/124 147/149/124 +f 141/144/123 138/141/123 148/150/123 +f 138/141/130 144/147/130 148/150/130 +f 144/147/133 141/144/133 148/150/133 +f 133/135/123 141/144/123 149/151/123 +f 147/149/132 133/135/132 149/151/132 +f 139/142/134 147/149/134 149/151/134 +f 137/140/125 136/137/125 150/152/125 +f 136/137/135 143/146/135 150/152/135 +f 143/146/136 137/140/136 150/152/136 +f 142/145/131 140/143/131 151/153/131 +f 140/143/124 146/133/124 151/153/124 +f 146/133/137 142/145/137 151/153/137 +f 138/141/123 142/145/123 152/132/123 +f 142/145/137 146/133/137 152/132/137 +f 139/142/138 141/144/138 153/154/138 +f 144/147/124 139/142/124 153/154/124 +f 141/144/133 144/147/133 153/154/133 +f 141/144/138 139/142/138 154/155/138 +f 149/151/123 141/144/123 154/155/123 +f 139/142/134 149/151/134 154/155/134 +f 132/139/139 138/141/139 155/134/139 +f 146/133/140 132/139/140 155/134/140 +f 138/141/123 152/132/123 155/134/123 +o Cup_hull_8 +v -0.003801 0.024902 0.017846 +v -0.014335 0.017794 0.032458 +v -0.014335 0.020688 0.032458 +v 0.000413 0.022796 0.032458 +v -0.014070 0.011212 0.015036 +v 0.000413 0.018057 0.015036 +v -0.014335 0.020426 0.015036 +v 0.000413 0.025166 0.032458 +v 0.000413 0.024376 0.016722 +v -0.009858 0.023322 0.032458 +v -0.014070 0.011475 0.017004 +v -0.009858 0.023322 0.018409 +v -0.005645 0.024639 0.032458 +v 0.000413 0.018320 0.017285 +v 0.000413 0.022532 0.032179 +v 0.000413 0.020426 0.015036 +v -0.014070 0.017531 0.032179 +v -0.013017 0.021741 0.018409 +v 0.000413 0.025166 0.017846 +v -0.014335 0.011212 0.016161 +v -0.002222 0.025166 0.032458 +v -0.006698 0.024376 0.018128 +v -0.013017 0.021741 0.032458 +v -0.014070 0.011212 0.016161 +v -0.005645 0.024111 0.017004 +v -0.002222 0.025166 0.018409 +v -0.004328 0.024902 0.018409 +v -0.013806 0.021215 0.018128 +v -0.001958 0.024639 0.017004 +v -0.006698 0.024376 0.032458 +v 0.000413 0.018057 0.015880 +v -0.004328 0.024902 0.032458 +v -0.014335 0.011212 0.015036 +v -0.014335 0.020688 0.017285 +v -0.013806 0.021215 0.032458 +v -0.009330 0.023322 0.017565 +vt 0.822516 0.517815 +vt 0.887029 0.589272 +vt 0.854821 0.339370 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.017913 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 0.903182 1.000000 +vt 0.000000 0.303543 +vt 0.000000 0.589272 +vt 0.870876 1.000000 +vt 0.016055 1.000000 +vt 1.000000 1.000000 +vt 0.016055 0.017913 +vt 0.887029 0.017913 +vt 0.806363 0.303543 +vt 0.806363 0.089370 +vt 0.838669 1.000000 +vt 0.935389 0.000000 +vt 0.000000 0.821359 +vt 0.000000 0.089370 +vt 0.935389 0.017913 +vt 0.838669 0.714272 +vt 0.806363 0.821359 +vt 0.806363 0.678543 +vt 0.822516 0.035826 +vt 0.887029 0.839272 +vt 0.000000 0.517815 +vt 0.951542 1.000000 +vt 0.000000 0.678543 +vt 1.000000 0.000000 +vt 0.870876 0.000000 +vt 0.000000 0.035826 +vn -0.2516 0.8624 -0.4393 +vn 0.0000 0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 0.3927 -0.9197 +vn 0.2065 -0.6089 0.7659 +vn 0.3054 -0.8844 0.3530 +vn 0.2437 -0.7058 0.6652 +vn -0.4409 0.8811 -0.1713 +vn -0.4475 0.8943 0.0000 +vn -0.4642 -0.8213 0.3317 +vn -0.2519 -0.8988 0.3587 +vn 0.0000 1.0000 0.0000 +vn -0.3166 0.9486 0.0000 +vn 0.4273 -0.9041 0.0000 +vn 0.3853 -0.8811 0.2743 +vn 0.4112 -0.8771 0.2481 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 -0.9548 0.2972 +vn -0.2012 0.8944 -0.3995 +vn -0.0599 0.9580 -0.2805 +vn -0.1242 0.9923 0.0000 +vn -0.1926 0.9646 -0.1803 +vn -0.2164 0.9763 -0.0020 +vn -0.1234 0.9856 -0.1155 +vn -0.5179 0.8459 -0.1275 +vn -0.5543 0.8323 0.0000 +vn -0.0430 0.5239 -0.8507 +vn -0.0570 0.9105 -0.4095 +vn 0.0223 0.8181 -0.5747 +vn -0.0894 0.6249 -0.7755 +vn -0.1204 0.8415 -0.5266 +vn -0.2415 0.9704 0.0000 +vn 0.4240 -0.8903 0.1661 +vn -0.1964 0.9805 0.0000 +vn -0.7064 0.7078 0.0000 +vn -0.6278 0.7731 -0.0901 +vn -0.3902 0.8877 -0.2442 +vn -0.3262 0.9230 -0.2041 +vn -0.2527 0.8463 -0.4689 +usemtl None +s off +f 177/156/141 180/157/141 191/158/141 +f 158/159/142 157/160/142 159/161/142 +f 161/162/143 160/163/143 162/164/143 +f 157/160/144 158/159/144 162/164/144 +f 158/159/142 159/161/142 163/165/142 +f 159/161/145 161/162/145 163/165/145 +f 163/165/145 161/162/145 164/166/145 +f 158/159/142 163/165/142 165/167/142 +f 165/167/142 163/165/142 168/168/142 +f 161/162/145 159/161/145 169/169/145 +f 169/169/145 159/161/145 170/170/145 +f 161/162/143 162/164/143 171/171/143 +f 164/166/145 161/162/145 171/171/145 +f 162/164/146 164/166/146 171/171/146 +f 159/161/147 157/160/147 172/172/147 +f 166/173/148 170/170/148 172/172/148 +f 170/170/149 159/161/149 172/172/149 +f 167/174/150 162/164/150 173/175/150 +f 165/167/151 167/174/151 173/175/151 +f 163/165/145 164/166/145 174/176/145 +f 157/160/144 162/164/144 175/177/144 +f 172/172/152 157/160/152 175/177/152 +f 166/173/153 172/172/153 175/177/153 +f 168/168/142 163/165/142 176/178/142 +f 163/165/154 174/176/154 176/178/154 +f 167/174/155 165/167/155 177/156/155 +f 158/159/142 165/167/142 178/179/142 +f 165/167/151 173/175/151 178/179/151 +f 160/163/156 161/162/156 179/180/156 +f 170/170/157 166/173/157 179/180/157 +f 169/169/158 170/170/158 179/180/158 +f 175/177/159 160/163/159 179/180/159 +f 166/173/160 175/177/160 179/180/160 +f 177/156/161 156/181/161 180/157/161 +f 174/176/162 156/181/162 181/182/162 +f 176/178/154 174/176/154 181/182/154 +f 176/178/163 181/182/163 182/183/163 +f 156/181/164 177/156/164 182/183/164 +f 177/156/165 168/168/165 182/183/165 +f 181/182/166 156/181/166 182/183/166 +f 173/175/167 162/164/167 183/184/167 +f 178/179/168 173/175/168 183/184/168 +f 164/166/169 162/164/169 184/185/169 +f 156/181/170 174/176/170 184/185/170 +f 174/176/171 164/166/171 184/185/171 +f 162/164/172 180/157/172 184/185/172 +f 180/157/173 156/181/173 184/185/173 +f 165/167/142 168/168/142 185/186/142 +f 177/156/155 165/167/155 185/186/155 +f 168/168/174 177/156/174 185/186/174 +f 161/162/145 169/169/145 186/187/145 +f 179/180/156 161/162/156 186/187/156 +f 169/169/175 179/180/175 186/187/175 +f 168/168/142 176/178/142 187/188/142 +f 176/178/163 182/183/163 187/188/163 +f 182/183/176 168/168/176 187/188/176 +f 162/164/143 160/163/143 188/189/143 +f 160/163/159 175/177/159 188/189/159 +f 175/177/144 162/164/144 188/189/144 +f 162/164/144 158/159/144 189/190/144 +f 158/159/177 183/184/177 189/190/177 +f 183/184/178 162/164/178 189/190/178 +f 158/159/142 178/179/142 190/191/142 +f 183/184/177 158/159/177 190/191/177 +f 178/179/168 183/184/168 190/191/168 +f 162/164/179 167/174/179 191/158/179 +f 167/174/180 177/156/180 191/158/180 +f 180/157/181 162/164/181 191/158/181 +o Cup_hull_9 +v 0.004625 -0.024868 0.026844 +v 0.008313 -0.016178 0.015036 +v 0.007785 -0.016178 0.015036 +v 0.008313 -0.022761 0.050166 +v 0.000413 -0.024077 0.049041 +v 0.000413 -0.018023 0.015036 +v 0.008313 -0.023814 0.017848 +v 0.000413 -0.025132 0.017848 +v 0.004363 -0.024868 0.050166 +v 0.008313 -0.020655 0.015036 +v 0.007785 -0.024077 0.050166 +v 0.000413 -0.025132 0.050166 +v 0.008049 -0.016178 0.016442 +v 0.000413 -0.020655 0.015036 +v 0.000676 -0.024077 0.049884 +v 0.002520 -0.025132 0.018409 +v 0.000413 -0.018023 0.015882 +v 0.001730 -0.024341 0.016724 +v 0.005942 -0.024604 0.018409 +v 0.007785 -0.022761 0.050166 +v 0.002520 -0.025132 0.050166 +v 0.008313 -0.023814 0.050166 +v 0.005679 -0.024077 0.017006 +v 0.004625 -0.024868 0.048477 +v 0.007785 -0.024077 0.018409 +v 0.000413 -0.024341 0.016724 +v 0.008313 -0.023287 0.017006 +v 0.003309 -0.024868 0.017567 +v 0.000940 -0.024077 0.050166 +v 0.008313 -0.016178 0.016442 +vt 0.959965 1.000000 +vt 0.000000 0.264781 +vt 0.959965 1.000000 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.793951 +vt 0.919930 0.147220 +vt 0.032009 0.117756 +vt 0.919930 0.000000 +vt 1.000000 0.500000 +vt 0.000000 0.029464 +vt 0.000000 0.117756 +vt 0.000000 0.000000 +vt 1.000000 0.500000 +vt 0.008027 0.117756 +vt 0.903974 0.000000 +vt 0.975920 0.793951 +vt 0.951938 0.088293 +vt 0.663861 0.029464 +vt 0.903974 0.058927 +vt 0.000000 0.264781 +vt 0.000000 0.000000 +vt 0.000000 0.147220 +vt 0.943911 0.117756 +vt 0.048062 0.029464 +vt 0.903974 0.117756 +vt 0.951938 0.088293 +vt 0.943911 0.206049 +vt 0.927956 0.029464 +vt 0.000000 0.117756 +vn 0.0000 0.9815 0.1916 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn -1.0000 -0.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 1.0000 0.0000 +vn -0.9093 0.3035 0.2846 +vn 0.0000 -1.0000 0.0000 +vn -0.2427 0.9701 0.0000 +vn -0.2377 0.9703 0.0446 +vn -0.4977 0.8532 0.1558 +vn -0.2432 0.9546 0.1719 +vn 0.0000 -0.4164 -0.9092 +vn 0.1524 -0.9883 -0.0071 +vn 0.1244 -0.9922 0.0000 +vn 0.4474 -0.8944 0.0000 +vn 0.0960 -0.5511 -0.8289 +vn 0.2249 -0.9738 0.0349 +vn 0.1964 -0.9805 0.0000 +vn 0.2416 -0.9704 0.0021 +vn 0.1417 -0.9897 0.0220 +vn 0.2697 -0.9439 -0.1905 +vn 0.2747 -0.9615 0.0000 +vn 0.0000 -0.8181 -0.5751 +vn 0.2466 -0.8217 -0.5138 +vn 0.1770 -0.5898 -0.7879 +vn 0.0645 -0.9680 -0.2426 +vn 0.0212 -0.8294 -0.5583 +vn 0.1503 -0.9749 -0.1644 +vn 0.2113 -0.9015 -0.3778 +vn 0.2112 -0.9013 -0.3782 +vn 0.0968 -0.7522 -0.6518 +vn -0.6860 0.3432 0.6416 +vn -0.1968 0.9630 0.1841 +vn -0.1855 0.9647 0.1869 +usemtl None +s off +f 204/192/182 195/193/182 221/194/182 +f 194/195/183 193/196/183 197/197/183 +f 193/196/184 195/193/184 198/198/184 +f 196/199/185 197/197/185 199/200/185 +f 197/197/183 193/196/183 201/201/183 +f 193/196/184 198/198/184 201/201/184 +f 195/193/186 200/202/186 202/203/186 +f 196/199/185 199/200/185 203/204/185 +f 200/202/186 195/193/186 203/204/186 +f 193/196/187 194/195/187 204/192/187 +f 199/200/185 197/197/185 205/205/185 +f 197/197/183 201/201/183 205/205/183 +f 196/199/188 203/204/188 206/206/188 +f 203/204/189 199/200/189 207/207/189 +f 194/195/190 197/197/190 208/208/190 +f 197/197/185 196/199/185 208/208/185 +f 204/192/191 194/195/191 208/208/191 +f 196/199/192 206/206/192 208/208/192 +f 206/206/193 204/192/193 208/208/193 +f 205/205/194 201/201/194 209/209/194 +f 192/210/195 207/207/195 210/211/195 +f 203/204/186 195/193/186 211/212/186 +f 195/193/182 204/192/182 211/212/182 +f 200/202/186 203/204/186 212/213/186 +f 207/207/196 192/210/196 212/213/196 +f 203/204/189 207/207/189 212/213/189 +f 198/198/184 195/193/184 213/214/184 +f 202/203/197 198/198/197 213/214/197 +f 195/193/186 202/203/186 213/214/186 +f 209/209/198 201/201/198 214/215/198 +f 202/203/199 200/202/199 215/216/199 +f 192/210/200 210/211/200 215/216/200 +f 210/211/201 202/203/201 215/216/201 +f 212/213/196 192/210/196 215/216/196 +f 200/202/202 212/213/202 215/216/202 +f 198/198/197 202/203/197 216/217/197 +f 210/211/203 198/198/203 216/217/203 +f 202/203/204 210/211/204 216/217/204 +f 199/200/185 205/205/185 217/218/185 +f 209/209/205 199/200/205 217/218/205 +f 205/205/194 209/209/194 217/218/194 +f 201/201/184 198/198/184 218/219/184 +f 198/198/206 214/215/206 218/219/206 +f 214/215/207 201/201/207 218/219/207 +f 207/207/208 199/200/208 219/220/208 +f 199/200/209 209/209/209 219/220/209 +f 210/211/210 207/207/210 219/220/210 +f 198/198/211 210/211/211 219/220/211 +f 214/215/212 198/198/212 219/220/212 +f 209/209/213 214/215/213 219/220/213 +f 206/206/214 203/204/214 220/221/214 +f 204/192/215 206/206/215 220/221/215 +f 203/204/186 211/212/186 220/221/186 +f 211/212/216 204/192/216 220/221/216 +f 195/193/184 193/196/184 221/194/184 +f 193/196/187 204/192/187 221/194/187 +o Cup_hull_10 +v 0.021743 -0.013016 0.050164 +v 0.025167 -0.000378 0.032460 +v 0.025167 -0.002222 0.032460 +v 0.017793 -0.014070 0.032460 +v 0.024113 -0.000379 0.050164 +v 0.021743 -0.013016 0.032460 +v 0.022796 -0.000379 0.032460 +v 0.019637 -0.014335 0.050164 +v 0.024640 -0.005645 0.050164 +v 0.024113 -0.007750 0.032460 +v 0.025167 -0.000378 0.050164 +v 0.020691 -0.014335 0.032460 +v 0.023323 -0.009856 0.050164 +v 0.019637 -0.013806 0.050164 +v 0.017793 -0.014070 0.033306 +v 0.020691 -0.014335 0.050164 +v 0.022796 -0.000379 0.033586 +v 0.025167 -0.002222 0.050164 +v 0.024903 -0.004328 0.032460 +v 0.023323 -0.009856 0.032460 +v 0.017793 -0.014335 0.032460 +v 0.024113 -0.007750 0.050164 +v 0.021217 -0.013806 0.032460 +v 0.024903 -0.004328 0.050164 +v 0.024640 -0.005645 0.032460 +v 0.021217 -0.013806 0.050164 +vt 0.000000 0.000000 +vt 1.000000 0.037882 +vt 0.000000 0.037882 +vt 1.000000 1.000000 +vt 1.000000 0.867854 +vt 1.000000 0.018990 +vt 1.000000 0.094460 +vt 1.000000 0.999902 +vt 0.000000 0.094460 +vt 0.000000 0.999902 +vt 0.000000 0.000000 +vt 0.000000 0.622651 +vt 1.000000 0.471809 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.320869 +vt 0.000000 0.037882 +vt 0.952232 0.018990 +vt 0.936374 0.999902 +vt 0.000000 0.867854 +vt 1.000000 0.717012 +vt 1.000000 0.320869 +vt 1.000000 0.000000 +vt 0.000000 0.471809 +vt 0.000000 0.717012 +vt 1.000000 0.622651 +vn 0.7093 -0.7049 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 0.0000 1.0000 +vn 1.0000 0.0000 0.0000 +vn -0.0006 1.0000 0.0000 +vn 0.8944 -0.4472 0.0000 +vn -0.9941 0.0000 0.1087 +vn -0.9392 0.3433 0.0000 +vn -0.9441 0.3147 0.0984 +vn 0.0000 -1.0000 0.0000 +vn -0.0013 1.0000 0.0001 +vn -0.9371 0.3410 0.0744 +vn 0.9923 -0.1242 0.0000 +vn 0.9363 -0.3513 0.0000 +vn -0.9444 -0.3139 0.0984 +vn -1.0000 0.0000 0.0000 +vn 0.9701 -0.2428 0.0000 +vn 0.8322 -0.5545 0.0000 +vn 0.9806 -0.1962 0.0000 +usemtl None +s off +f 237/222/217 244/223/217 247/224/217 +f 223/225/218 224/226/218 225/227/218 +f 225/227/218 224/226/218 227/228/218 +f 223/225/218 225/227/218 228/229/218 +f 222/230/219 226/231/219 229/232/219 +f 226/231/219 222/230/219 230/233/219 +f 227/228/218 224/226/218 231/234/218 +f 224/226/220 223/225/220 232/235/220 +f 223/225/221 228/229/221 232/235/221 +f 226/231/219 230/233/219 232/235/219 +f 225/227/218 227/228/218 233/236/218 +f 222/230/222 227/228/222 234/237/222 +f 230/233/219 222/230/219 234/237/219 +f 229/232/219 226/231/219 235/238/219 +f 229/232/223 235/238/223 236/239/223 +f 228/229/224 225/227/224 236/239/224 +f 235/238/225 226/231/225 236/239/225 +f 222/230/219 229/232/219 237/222/219 +f 229/232/226 233/236/226 237/222/226 +f 232/235/221 228/229/221 238/240/221 +f 226/231/227 232/235/227 238/240/227 +f 228/229/224 236/239/224 238/240/224 +f 236/239/228 226/231/228 238/240/228 +f 224/226/220 232/235/220 239/241/220 +f 232/235/219 230/233/219 239/241/219 +f 231/234/218 224/226/218 240/242/218 +f 224/226/229 239/241/229 240/242/229 +f 227/228/218 231/234/218 241/243/218 +f 234/237/222 227/228/222 241/243/222 +f 231/234/230 234/237/230 241/243/230 +f 225/227/218 233/236/218 242/244/218 +f 233/236/226 229/232/226 242/244/226 +f 229/232/231 236/239/231 242/244/231 +f 236/239/232 225/227/232 242/244/232 +f 231/234/233 230/233/233 243/245/233 +f 230/233/219 234/237/219 243/245/219 +f 234/237/230 231/234/230 243/245/230 +f 227/228/234 222/230/234 244/223/234 +f 233/236/218 227/228/218 244/223/218 +f 237/222/217 233/236/217 244/223/217 +f 239/241/219 230/233/219 245/246/219 +f 230/233/235 240/242/235 245/246/235 +f 240/242/229 239/241/229 245/246/229 +f 230/233/233 231/234/233 246/247/233 +f 231/234/218 240/242/218 246/247/218 +f 240/242/235 230/233/235 246/247/235 +f 222/230/219 237/222/219 247/224/219 +f 244/223/234 222/230/234 247/224/234 +o Cup_hull_11 +v 0.024903 -0.004329 0.032460 +v 0.021479 -0.000377 0.016161 +v 0.020426 -0.000379 0.015036 +v 0.020426 -0.014335 0.015036 +v 0.011211 -0.014335 0.016161 +v 0.017530 -0.014071 0.032177 +v 0.022533 -0.000377 0.032177 +v 0.025166 -0.000377 0.017846 +v 0.020690 -0.014335 0.032458 +v 0.018056 -0.000379 0.015036 +v 0.023322 -0.009856 0.018411 +v 0.025166 -0.000377 0.032460 +v 0.011211 -0.014335 0.015036 +v 0.023322 -0.009856 0.032460 +v 0.024375 -0.006699 0.018128 +v 0.018318 -0.000379 0.017285 +v 0.011474 -0.014071 0.017004 +v 0.021743 -0.013016 0.018411 +v 0.024375 -0.000905 0.016724 +v 0.017794 -0.014335 0.032458 +v 0.025166 -0.002222 0.018411 +v 0.024112 -0.007750 0.032460 +v 0.021743 -0.013016 0.032460 +v 0.024375 -0.004329 0.017004 +v 0.011211 -0.014071 0.016161 +v 0.022796 -0.000377 0.032460 +v 0.021216 -0.013807 0.018130 +v 0.024903 -0.004329 0.018411 +v 0.025166 -0.002222 0.032460 +v 0.023586 -0.008277 0.017285 +v 0.018056 -0.000379 0.015880 +v 0.024639 -0.005646 0.032460 +v 0.020690 -0.014335 0.017285 +v 0.011211 -0.014071 0.015036 +v 0.021216 -0.013807 0.032458 +vt 0.822435 0.037784 +vt 0.000000 0.094460 +vt 0.000098 0.037784 +vt 1.000000 0.999902 +vt 0.935395 1.000000 +vt 0.838684 1.000000 +vt 0.016249 1.000000 +vt 0.935395 0.000000 +vt 1.000000 0.000000 +vt 0.000098 0.000000 +vt 1.000000 0.999902 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.716915 +vt 0.000000 0.320869 +vt 0.016249 0.018892 +vt 0.887040 0.018892 +vt 0.806284 0.320869 +vt 0.806284 0.094460 +vt 0.903093 0.962216 +vt 0.000098 0.000000 +vt 0.806284 0.867854 +vt 0.000000 0.471809 +vt 0.822533 0.547083 +vt 0.887040 0.716915 +vt 0.935395 0.018892 +vt 0.870889 0.999902 +vt 0.000000 1.000000 +vt 0.806284 0.716915 +vt 0.000000 0.867854 +vt 0.870889 0.434025 +vt 0.951547 0.999902 +vt 0.000000 0.622553 +vt 0.870889 0.000000 +vt 1.000000 0.018892 +vn 0.8321 -0.5547 0.0000 +vn 0.0010 1.0000 -0.0021 +vn 0.0000 1.0000 -0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 1.0000 -0.0012 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 0.0000 1.0000 +vn -0.8998 -0.2478 0.3591 +vn -0.8795 0.3213 0.3510 +vn 0.8812 -0.4404 -0.1718 +vn 0.8945 -0.4470 0.0000 +vn 0.3931 0.0000 -0.9195 +vn 0.3488 0.7294 -0.5885 +vn -0.8201 -0.4665 0.3313 +vn 1.0000 0.0000 0.0000 +vn 0.9364 -0.3510 0.0000 +vn 0.9484 -0.3169 -0.0058 +vn 0.0000 -0.0013 1.0000 +vn 0.5751 -0.0666 -0.8153 +vn 0.8266 -0.0458 -0.5610 +vn 0.9275 -0.1094 -0.3575 +vn -1.0000 0.0000 0.0000 +vn -0.8684 0.4306 0.2457 +vn -0.9544 0.0000 0.2986 +vn -0.8736 0.4026 0.2734 +vn -0.7070 0.2583 0.6584 +vn -0.6033 0.2161 0.7677 +vn -0.0004 0.0000 1.0000 +vn 0.8456 -0.5183 -0.1275 +vn 0.9923 -0.1242 0.0000 +vn 0.9237 -0.1641 -0.3461 +vn 0.9300 -0.1164 -0.3485 +vn 0.8884 -0.3554 -0.2906 +vn 0.9131 -0.3265 -0.2442 +vn 0.7927 -0.1996 -0.5760 +vn 0.8765 -0.2063 -0.4350 +vn -0.0004 1.0000 0.0000 +vn -0.0010 1.0000 0.0002 +vn -0.8944 0.4472 0.0000 +vn -0.8809 0.4438 0.1644 +vn 0.9700 -0.2431 0.0000 +vn 0.9805 -0.1963 0.0000 +vn 0.9762 -0.2169 -0.0020 +vn 0.7740 -0.6267 -0.0907 +vn 0.7081 -0.7062 0.0000 +vn 0.0065 -0.0065 1.0000 +usemtl None +s off +f 274/248/236 270/249/236 282/250/236 +f 250/251/237 249/252/237 255/253/237 +f 249/252/238 254/254/238 255/253/238 +f 252/255/239 251/256/239 256/257/239 +f 249/252/240 250/251/240 257/258/240 +f 250/251/241 251/256/241 257/258/241 +f 255/253/238 254/254/238 259/259/238 +f 251/256/239 252/255/239 260/260/239 +f 257/258/241 251/256/241 260/260/241 +f 248/261/242 259/259/242 261/262/242 +f 252/255/243 253/263/243 264/264/243 +f 253/263/244 254/254/244 264/264/244 +f 251/256/245 258/265/245 265/266/245 +f 258/265/246 261/262/246 265/266/246 +f 251/256/247 250/251/247 266/267/247 +f 250/251/248 255/253/248 266/267/248 +f 253/263/249 252/255/249 267/268/249 +f 252/255/239 256/257/239 267/268/239 +f 255/253/250 259/259/250 268/269/250 +f 248/261/242 261/262/242 269/270/242 +f 261/262/251 258/265/251 269/270/251 +f 258/265/252 262/271/252 269/270/252 +f 261/262/242 259/259/242 270/249/242 +f 265/266/246 261/262/246 270/249/246 +f 267/268/253 256/257/253 270/249/253 +f 251/256/254 266/267/254 271/272/254 +f 266/267/255 255/253/255 271/272/255 +f 255/253/256 268/269/256 271/272/256 +f 260/260/257 252/255/257 272/273/257 +f 254/254/258 263/274/258 272/273/258 +f 252/255/259 264/264/259 272/273/259 +f 264/264/260 254/254/260 272/273/260 +f 254/254/261 253/263/261 273/275/261 +f 259/259/238 254/254/238 273/275/238 +f 253/263/262 267/268/262 273/275/262 +f 270/249/242 259/259/242 273/275/242 +f 267/268/263 270/249/263 273/275/263 +f 251/256/264 265/266/264 274/248/264 +f 265/266/236 270/249/236 274/248/236 +f 268/269/265 248/261/265 275/276/265 +f 262/271/266 271/272/266 275/276/266 +f 271/272/267 268/269/267 275/276/267 +f 259/259/242 248/261/242 276/277/242 +f 248/261/265 268/269/265 276/277/265 +f 268/269/250 259/259/250 276/277/250 +f 258/265/268 251/256/268 277/278/268 +f 262/271/269 258/265/269 277/278/269 +f 251/256/270 271/272/270 277/278/270 +f 271/272/271 262/271/271 277/278/271 +f 254/254/272 249/252/272 278/279/272 +f 249/252/272 257/258/272 278/279/272 +f 263/274/273 254/254/273 278/279/273 +f 257/258/274 272/273/274 278/279/274 +f 272/273/275 263/274/275 278/279/275 +f 248/261/242 269/270/242 279/280/242 +f 269/270/276 262/271/276 279/280/276 +f 275/276/277 248/261/277 279/280/277 +f 262/271/278 275/276/278 279/280/278 +f 256/257/239 251/256/239 280/281/239 +f 251/256/279 274/248/279 280/281/279 +f 274/248/280 256/257/280 280/281/280 +f 257/258/241 260/260/241 281/282/241 +f 260/260/257 272/273/257 281/282/257 +f 272/273/274 257/258/274 281/282/274 +f 270/249/281 256/257/281 282/250/281 +f 256/257/280 274/248/280 282/250/280 +o Cup_hull_12 +v 0.024903 0.004363 0.050164 +v 0.021217 0.013580 0.032460 +v 0.021481 0.013315 0.032460 +v 0.022796 -0.000377 0.032460 +v 0.020164 0.013052 0.050164 +v 0.018320 0.013315 0.032460 +v 0.025167 0.002257 0.032460 +v 0.024113 -0.000377 0.050164 +v 0.023322 0.009891 0.050164 +v 0.024376 0.006732 0.032460 +v 0.025167 -0.000377 0.032460 +v 0.021217 0.013580 0.050164 +v 0.025167 -0.000377 0.050164 +v 0.018320 0.013315 0.033306 +v 0.023060 0.010417 0.032460 +v 0.021743 0.013052 0.050164 +v 0.022796 -0.000377 0.033586 +v 0.018320 0.013580 0.033306 +v 0.024376 0.006732 0.050164 +v 0.025167 0.002257 0.050164 +v 0.020164 0.013580 0.050164 +v 0.024903 0.004363 0.032460 +v 0.022006 0.012525 0.032460 +v 0.023586 0.009103 0.032460 +v 0.024640 0.005682 0.045386 +vt 1.000000 0.339663 +vt 1.000000 0.509397 +vt 0.269871 0.434123 +vt 1.000000 1.000000 +vt 1.000000 0.981010 +vt 1.000000 0.000000 +vt 1.000000 0.981010 +vt 1.000000 0.188724 +vt 0.000000 0.339663 +vt 0.000000 0.962216 +vt 0.000000 0.000000 +vt 0.000000 0.735709 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 0.952232 0.981010 +vt 1.000000 0.773395 +vt 0.000000 0.962216 +vt 0.936374 0.000000 +vt 0.952232 1.000000 +vt 0.000000 0.509397 +vt 0.000000 0.188724 +vt 0.000000 1.000000 +vt 1.000000 0.924432 +vt 1.000000 0.679229 +vn 0.9762 0.2171 -0.0023 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn -0.9505 -0.3107 0.0000 +vn -0.9546 -0.2807 0.1000 +vn 0.7093 0.7049 -0.0001 +vn 0.7079 0.7063 0.0000 +vn 0.8946 0.4468 -0.0000 +vn -0.9483 -0.3085 0.0753 +vn -0.0870 0.9506 -0.2979 +vn 0.0000 1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.9941 0.0000 0.1087 +vn 0.9922 0.1244 0.0000 +vn 0.8325 0.5540 -0.0041 +vn 0.8945 0.4471 -0.0000 +vn 0.9282 0.3720 -0.0027 +vn 0.9486 0.3164 0.0001 +vn 0.9488 0.3160 0.0000 +vn 0.9761 0.2171 0.0062 +vn 0.9698 0.2438 0.0000 +vn 0.9807 0.1954 0.0000 +usemtl None +s off +f 304/283/282 292/284/282 307/285/282 +f 284/286/283 285/287/283 286/288/283 +f 284/286/283 286/288/283 288/289/283 +f 286/288/283 285/287/283 289/290/283 +f 283/291/284 287/292/284 290/293/284 +f 287/292/284 283/291/284 291/294/284 +f 289/290/283 285/287/283 292/284/283 +f 286/288/283 289/290/283 293/295/283 +f 290/293/285 286/288/285 293/295/285 +f 287/292/284 291/294/284 294/296/284 +f 283/291/284 290/293/284 295/297/284 +f 293/295/286 289/290/286 295/297/286 +f 290/293/285 293/295/285 295/297/285 +f 288/289/287 286/288/287 296/298/287 +f 290/293/288 287/292/288 296/298/288 +f 292/284/283 285/287/283 297/299/283 +f 285/287/289 284/286/289 298/300/289 +f 284/286/290 294/296/290 298/300/290 +f 294/296/284 291/294/284 298/300/284 +f 291/294/291 297/299/291 298/300/291 +f 286/288/285 290/293/285 299/301/285 +f 296/298/287 286/288/287 299/301/287 +f 290/293/292 296/298/292 299/301/292 +f 284/286/293 288/289/293 300/302/293 +f 294/296/294 284/286/294 300/302/294 +f 288/289/295 296/298/295 300/302/295 +f 296/298/296 287/292/296 300/302/296 +f 291/294/284 283/291/284 301/303/284 +f 289/290/297 283/291/297 302/304/297 +f 283/291/284 295/297/284 302/304/284 +f 295/297/286 289/290/286 302/304/286 +f 287/292/284 294/296/284 303/305/284 +f 294/296/294 300/302/294 303/305/294 +f 300/302/296 287/292/296 303/305/296 +f 283/291/297 289/290/297 304/283/297 +f 289/290/283 292/284/283 304/283/283 +f 297/299/283 285/287/283 305/306/283 +f 285/287/298 298/300/298 305/306/298 +f 298/300/299 297/299/299 305/306/299 +f 297/299/300 291/294/300 306/307/300 +f 292/284/283 297/299/283 306/307/283 +f 291/294/301 301/303/301 306/307/301 +f 301/303/302 292/284/302 306/307/302 +f 301/303/303 283/291/303 307/285/303 +f 292/284/304 301/303/304 307/285/304 +f 283/291/305 304/283/305 307/285/305 +o Cup_hull_13 +v 0.022533 0.001203 0.032460 +v 0.020425 0.013580 0.015036 +v 0.024113 0.006469 0.017285 +v 0.018057 -0.000377 0.015036 +v 0.012001 0.013580 0.015880 +v 0.021215 0.013580 0.032458 +v 0.025167 -0.000377 0.032460 +v 0.024903 -0.000377 0.017285 +v 0.018057 0.013315 0.032177 +v 0.022533 -0.000377 0.032177 +v 0.024640 0.005682 0.032460 +v 0.023060 0.010418 0.018409 +v 0.024903 0.004363 0.018409 +v 0.012001 0.013580 0.015036 +v 0.018319 -0.000377 0.017285 +v 0.020425 -0.000377 0.015036 +v 0.023060 0.010418 0.032460 +v 0.012001 0.013315 0.015880 +v 0.021478 0.013315 0.017846 +v 0.025167 0.002257 0.018409 +v 0.024375 0.006732 0.018409 +v 0.018319 0.013580 0.032458 +v 0.024375 0.000677 0.016724 +v 0.025167 0.002257 0.032460 +v 0.022007 0.012525 0.032460 +v 0.012265 0.013315 0.016724 +v 0.025167 -0.000377 0.017848 +v 0.023585 0.009101 0.032460 +v 0.023585 0.009101 0.018130 +v 0.024375 0.004101 0.017004 +v 0.022007 0.012525 0.018409 +v 0.021215 0.013580 0.017846 +v 0.018057 -0.000377 0.015880 +v 0.024903 0.004363 0.032460 +v 0.024375 0.006732 0.032460 +v 0.022797 -0.000377 0.032460 +v 0.024903 0.003048 0.017567 +vt 0.870889 0.000000 +vt 0.887040 0.320869 +vt 0.854738 0.245399 +vt 1.000000 1.000000 +vt 0.951547 1.000000 +vt 0.000098 1.000000 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 0.016249 0.000000 +vt 0.000000 0.113254 +vt 0.000000 0.434123 +vt 1.000000 1.000000 +vt 0.870889 0.000000 +vt 1.000000 0.000000 +vt 0.000000 0.773493 +vt 0.951547 0.981010 +vt 0.806382 0.773493 +vt 0.838684 0.981010 +vt 0.806382 0.339663 +vt 0.806382 0.509397 +vt 0.870889 0.490505 +vt 0.000098 1.000000 +vt 0.016249 0.981010 +vt 0.903093 0.075568 +vt 0.000000 0.188724 +vt 0.806382 0.188724 +vt 0.000000 0.924432 +vt 0.903093 0.981010 +vt 0.838587 0.000000 +vt 0.000000 0.679131 +vt 0.822435 0.679131 +vt 0.806382 0.924432 +vt 0.838684 1.000000 +vt 0.951547 0.000000 +vt 0.000000 0.339663 +vt 0.000000 0.509397 +vt 0.000000 0.000000 +vn 0.7754 0.0517 -0.6294 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.0000 0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn -0.9103 -0.3950 -0.1240 +vn -1.0000 0.0000 0.0000 +vn -0.8884 -0.3842 0.2513 +vn 0.8637 0.4163 -0.2843 +vn 0.9761 0.2172 -0.0021 +vn 0.9402 0.2092 -0.2690 +vn -0.8192 0.4811 0.3122 +vn 0.3931 0.0000 -0.9195 +vn 0.4355 -0.2435 -0.8667 +vn 1.0000 0.0000 0.0000 +vn 0.9922 0.1244 0.0000 +vn 0.8945 0.4471 0.0000 +vn 0.7999 0.6001 0.0035 +vn 0.0000 0.0016 1.0000 +vn -0.0005 -0.0000 1.0000 +vn -0.9208 0.1815 0.3451 +vn -0.8954 -0.2927 0.3356 +vn -0.9544 0.0000 0.2987 +vn -0.8925 -0.3541 0.2793 +vn 0.9287 0.3708 0.0000 +vn 0.9486 0.3164 0.0000 +vn 0.8514 0.3069 -0.4254 +vn 0.8648 0.4076 -0.2933 +vn 0.9203 0.2739 -0.2795 +vn 0.7206 0.1602 -0.6746 +vn 0.5691 0.0670 -0.8196 +vn 0.7744 0.0515 -0.6306 +vn 0.8750 0.4373 -0.2079 +vn 0.8311 0.5561 0.0000 +vn 0.6962 0.6906 -0.1957 +vn 0.7100 0.7043 0.0000 +vn -0.9145 -0.4045 0.0000 +vn -0.9014 -0.3987 0.1686 +vn 0.9807 0.1956 0.0000 +vn 0.9698 0.2439 0.0000 +vn -0.7111 -0.2325 0.6636 +vn -0.6165 -0.1977 0.7621 +vn -0.0008 -0.0001 1.0000 +vn 0.9349 0.1913 -0.2988 +vn 0.9740 0.1222 -0.1907 +vn 0.9047 0.0349 -0.4247 +vn 0.9661 0.0538 -0.2524 +vn 0.8487 0.1544 -0.5059 +usemtl None +s off +f 315/308/306 337/309/306 344/310/306 +f 309/311/307 312/312/307 313/313/307 +f 314/314/308 311/315/308 315/308/308 +f 311/315/308 314/314/308 317/316/308 +f 308/317/309 314/314/309 318/318/309 +f 309/311/310 311/315/310 321/319/310 +f 312/312/307 309/311/307 321/319/307 +f 311/315/308 317/316/308 322/320/308 +f 311/315/310 309/311/310 323/321/310 +f 315/308/308 311/315/308 323/321/308 +f 308/317/309 318/318/309 324/322/309 +f 321/319/311 311/315/311 325/323/311 +f 312/312/312 321/319/312 325/323/312 +f 322/320/313 317/316/313 325/323/313 +f 319/324/314 309/311/314 326/325/314 +f 318/318/315 320/326/315 328/327/315 +f 320/326/316 310/328/316 328/327/316 +f 313/313/307 312/312/307 329/329/307 +f 312/312/317 316/330/317 329/329/317 +f 323/321/318 309/311/318 330/331/318 +f 315/308/319 323/321/319 330/331/319 +f 318/318/309 314/314/309 331/332/309 +f 314/314/320 327/333/320 331/332/320 +f 327/333/321 320/326/321 331/332/321 +f 308/317/309 324/322/309 332/334/309 +f 324/322/322 319/324/322 332/334/322 +f 326/325/323 313/313/323 332/334/323 +f 313/313/324 329/329/324 332/334/324 +f 329/329/325 308/317/325 332/334/325 +f 316/330/326 312/312/326 333/335/326 +f 317/316/327 316/330/327 333/335/327 +f 312/312/328 325/323/328 333/335/328 +f 325/323/329 317/316/329 333/335/329 +f 314/314/308 315/308/308 334/336/308 +f 327/333/320 314/314/320 334/336/320 +f 324/322/309 318/318/309 335/337/309 +f 319/324/330 324/322/330 335/337/330 +f 335/337/331 328/327/331 336/338/331 +f 310/328/332 309/311/332 336/338/332 +f 309/311/333 319/324/333 336/338/333 +f 328/327/334 310/328/334 336/338/334 +f 319/324/330 335/337/330 336/338/330 +f 309/311/335 310/328/335 337/309/335 +f 330/331/336 309/311/336 337/309/336 +f 315/308/337 330/331/337 337/309/337 +f 319/324/338 326/325/338 338/339/338 +f 332/334/322 319/324/322 338/339/322 +f 326/325/339 332/334/339 338/339/339 +f 309/311/307 313/313/307 339/340/307 +f 326/325/340 309/311/340 339/340/340 +f 313/313/341 326/325/341 339/340/341 +f 311/315/308 322/320/308 340/341/308 +f 325/323/342 311/315/342 340/341/342 +f 322/320/343 325/323/343 340/341/343 +f 320/326/344 318/318/344 341/342/344 +f 318/318/309 331/332/309 341/342/309 +f 331/332/321 320/326/321 341/342/321 +f 318/318/345 328/327/345 342/343/345 +f 335/337/309 318/318/309 342/343/309 +f 328/327/331 335/337/331 342/343/331 +f 314/314/309 308/317/309 343/344/309 +f 317/316/308 314/314/308 343/344/308 +f 316/330/346 317/316/346 343/344/346 +f 329/329/347 316/330/347 343/344/347 +f 308/317/348 329/329/348 343/344/348 +f 310/328/349 320/326/349 344/310/349 +f 320/326/350 327/333/350 344/310/350 +f 334/336/351 315/308/351 344/310/351 +f 327/333/352 334/336/352 344/310/352 +f 337/309/353 310/328/353 344/310/353 +o Cup_hull_14 +v 0.008313 0.022796 0.050166 +v 0.001204 0.025166 0.017848 +v 0.003047 0.024902 0.017567 +v 0.008049 0.015951 0.015036 +v 0.000413 0.024112 0.050166 +v 0.000413 0.018058 0.015036 +v 0.008313 0.023849 0.018130 +v 0.004363 0.024902 0.050166 +v 0.000413 0.024376 0.016724 +v 0.008313 0.020427 0.015036 +v 0.000413 0.025166 0.050166 +v 0.008313 0.023849 0.050166 +v 0.005679 0.024639 0.018409 +v 0.008313 0.015951 0.015318 +v 0.000413 0.018058 0.015882 +v 0.000413 0.020428 0.015036 +v 0.002257 0.025166 0.018409 +v 0.008049 0.015951 0.015318 +v 0.007785 0.022796 0.050166 +v 0.000413 0.025166 0.017848 +v 0.006733 0.023849 0.017006 +v 0.006733 0.024377 0.050166 +v 0.002257 0.025166 0.047913 +v 0.004363 0.024902 0.018409 +v 0.006733 0.024377 0.018409 +v 0.003836 0.024112 0.016724 +v 0.008313 0.023323 0.017006 +v 0.005679 0.024639 0.050166 +vt 0.000000 0.914342 +vt 0.903974 0.942829 +vt 0.000000 0.942829 +vt 0.000000 0.885659 +vt 0.000000 0.742830 +vt 0.000000 0.971415 +vt 0.919930 1.000000 +vt 0.927956 0.971415 +vt 0.951938 0.914244 +vt 1.000000 0.228684 +vt 1.000000 0.000000 +vt 1.000000 0.485756 +vt 0.911903 0.857073 +vt 0.000000 1.000000 +vt 0.000000 0.857073 +vt 0.991973 0.000000 +vt 0.975920 0.228684 +vt 1.000000 0.485854 +vt 0.903974 1.000000 +vt 0.991973 0.000000 +vt 0.000000 0.742830 +vt 0.919930 1.000000 +vt 0.943911 0.857073 +vt 0.064115 1.000000 +vt 0.903974 0.971415 +vt 0.903974 0.914342 +vt 0.951938 0.885659 +vt 0.943911 0.800000 +vn 0.2417 0.9704 0.0000 +vn -0.0000 0.0000 1.0000 +vn 0.0259 0.8092 -0.5869 +vn -1.0000 0.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.7297 -0.0430 -0.6824 +vn -0.2660 -0.9640 0.0000 +vn 0.0000 0.3932 -0.9194 +vn 0.1080 0.9732 -0.2030 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -0.9812 0.1928 +vn 0.0000 -1.0000 0.0000 +vn -0.2506 -0.9533 0.1683 +vn -0.1726 -0.9668 0.1886 +vn 0.0000 0.8182 -0.5750 +vn 0.2058 0.9106 -0.3583 +vn 0.3168 0.9485 0.0000 +vn 0.0664 0.9963 0.0544 +vn 0.1241 0.9923 0.0000 +vn 0.1962 0.9806 0.0000 +vn 0.1876 0.9375 -0.2931 +vn 0.1219 0.9741 -0.1904 +vn 0.2431 0.9079 -0.3415 +vn 0.2270 0.9115 -0.3429 +vn 0.0581 0.7547 -0.6535 +vn 0.0347 0.4508 -0.8920 +vn 0.1305 0.7812 -0.6105 +vn 0.1300 0.5392 -0.8321 +vn 0.2887 0.8672 -0.4056 +vn 0.1841 0.5529 -0.8126 +usemtl None +s off +f 366/345/354 357/346/354 372/347/354 +f 349/348/355 345/349/355 352/350/355 +f 346/351/356 347/352/356 353/353/356 +f 350/354/357 349/348/357 353/353/357 +f 348/355/358 350/354/358 354/356/358 +f 351/357/359 345/349/359 354/356/359 +f 349/348/355 352/350/355 355/358/355 +f 353/353/357 349/348/357 355/358/357 +f 345/349/359 351/357/359 356/359/359 +f 352/350/355 345/349/355 356/359/355 +f 354/356/359 345/349/359 358/360/359 +f 348/355/360 354/356/360 358/360/360 +f 349/348/357 350/354/357 359/361/357 +f 350/354/361 348/355/361 359/361/361 +f 350/354/357 353/353/357 360/362/357 +f 354/356/358 350/354/358 360/362/358 +f 353/353/362 354/356/362 360/362/362 +f 347/352/363 346/351/363 361/363/363 +f 346/351/364 355/358/364 361/363/364 +f 358/360/365 345/349/365 362/364/365 +f 348/355/366 358/360/366 362/364/366 +f 359/361/361 348/355/361 362/364/361 +f 349/348/367 359/361/367 362/364/367 +f 345/349/355 349/348/355 363/365/355 +f 362/364/365 345/349/365 363/365/365 +f 349/348/368 362/364/368 363/365/368 +f 346/351/369 353/353/369 364/366/369 +f 355/358/364 346/351/364 364/366/364 +f 353/353/357 355/358/357 364/366/357 +f 347/352/370 357/346/370 365/367/370 +f 356/359/371 351/357/371 366/345/371 +f 352/350/355 356/359/355 366/345/355 +f 355/358/372 352/350/372 367/368/372 +f 361/363/364 355/358/364 367/368/364 +f 352/350/373 361/363/373 367/368/373 +f 352/350/374 357/346/374 368/369/374 +f 357/346/375 347/352/375 368/369/375 +f 347/352/376 361/363/376 368/369/376 +f 361/363/373 352/350/373 368/369/373 +f 351/357/377 365/367/377 369/370/377 +f 365/367/378 357/346/378 369/370/378 +f 366/345/371 351/357/371 369/370/371 +f 357/346/354 366/345/354 369/370/354 +f 353/353/379 347/352/379 370/371/379 +f 354/356/380 353/353/380 370/371/380 +f 347/352/381 365/367/381 370/371/381 +f 365/367/382 354/356/382 370/371/382 +f 351/357/359 354/356/359 371/372/359 +f 365/367/383 351/357/383 371/372/383 +f 354/356/384 365/367/384 371/372/384 +f 357/346/374 352/350/374 372/347/374 +f 352/350/355 366/345/355 372/347/355 +o Cup_hull_15 +v -0.002221 -0.020392 -0.048198 +v -0.020392 -0.014862 0.015036 +v -0.020126 -0.015389 0.015036 +v -0.002221 -0.017758 0.015036 +v -0.013280 -0.011965 -0.048198 +v -0.014860 -0.020392 -0.048198 +v -0.014860 -0.020392 0.015036 +v -0.013280 -0.011965 0.015036 +v -0.020392 -0.011965 -0.048198 +v -0.002221 -0.020392 0.015036 +v -0.002221 -0.017758 -0.048198 +v -0.020392 -0.011965 0.015036 +v -0.020126 -0.015389 -0.048198 +v -0.016704 -0.019073 -0.027679 +v -0.019074 -0.016704 0.015036 +v -0.019074 -0.016704 -0.048198 +v -0.020392 -0.014862 -0.048198 +v -0.015386 -0.020128 0.015036 +v -0.015386 -0.020128 -0.048198 +v -0.016968 -0.018811 0.015036 +v -0.016704 -0.019073 -0.048198 +vt 0.000000 0.188430 +vt 1.000000 0.072533 +vt 1.000000 0.202917 +vt 0.000000 0.000000 +vt 0.000000 0.014585 +vt 0.000000 1.000000 +vt 1.000000 0.391347 +vt 1.000000 1.000000 +vt 1.000000 0.304424 +vt 0.000000 0.304424 +vt 0.000000 0.391347 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 0.000000 0.000000 +vt 1.000000 0.014585 +vt 0.000000 0.072533 +vt 1.000000 0.000000 +vt 0.000000 0.275450 +vt 1.000000 0.275450 +vt 0.675509 0.202917 +vn -0.7071 -0.7071 -0.0000 +vn -0.0000 0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.4640 0.8858 0.0000 +vn -0.0001 1.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.8934 -0.4492 0.0000 +vn -0.7807 -0.6248 0.0000 +vn -0.4482 -0.8939 0.0000 +vn -0.6246 -0.7809 0.0000 +vn -0.7072 -0.7070 0.0000 +vn -0.6398 -0.7685 0.0008 +vn -0.7059 -0.7083 0.0000 +usemtl None +s off +f 392/373/385 388/374/385 393/375/385 +f 374/376/386 375/377/386 376/378/386 +f 377/379/387 373/380/387 378/381/387 +f 378/381/388 373/380/388 379/382/388 +f 376/378/386 375/377/386 379/382/386 +f 374/376/386 376/378/386 380/383/386 +f 376/378/389 377/379/389 380/383/389 +f 380/383/390 377/379/390 381/384/390 +f 377/379/387 378/381/387 381/384/387 +f 373/380/391 376/378/391 382/385/391 +f 379/382/388 373/380/388 382/385/388 +f 376/378/386 379/382/386 382/385/386 +f 376/378/391 373/380/391 383/386/391 +f 373/380/387 377/379/387 383/386/387 +f 377/379/389 376/378/389 383/386/389 +f 374/376/386 380/383/386 384/387/386 +f 380/383/390 381/384/390 384/387/390 +f 381/384/392 374/376/392 384/387/392 +f 375/377/393 374/376/393 385/388/393 +f 381/384/387 378/381/387 385/388/387 +f 379/382/386 375/377/386 387/389/386 +f 375/377/394 385/388/394 387/389/394 +f 385/388/387 378/381/387 388/374/387 +f 387/389/394 385/388/394 388/374/394 +f 374/376/392 381/384/392 389/390/392 +f 385/388/393 374/376/393 389/390/393 +f 381/384/387 385/388/387 389/390/387 +f 378/381/395 379/382/395 390/391/395 +f 379/382/386 387/389/386 390/391/386 +f 388/374/387 378/381/387 391/392/387 +f 378/381/395 390/391/395 391/392/395 +f 390/391/396 386/393/396 391/392/396 +f 387/389/397 388/374/397 392/373/397 +f 386/393/398 390/391/398 392/373/398 +f 390/391/386 387/389/386 392/373/386 +f 388/374/387 391/392/387 393/375/387 +f 391/392/396 386/393/396 393/375/396 +f 386/393/399 392/373/399 393/375/399 +o Cup_hull_16 +v -0.020127 -0.011963 0.015036 +v -0.018021 -0.000377 -0.048198 +v -0.013545 -0.011700 -0.048198 +v -0.020392 -0.011963 -0.048198 +v -0.020392 -0.000377 0.015029 +v -0.013545 -0.011963 0.015036 +v -0.018021 -0.000377 0.015036 +v -0.020392 -0.000377 -0.048198 +v -0.020392 -0.011963 0.015029 +v -0.013545 -0.011963 -0.048198 +v -0.013545 -0.011700 0.015036 +vt 1.000000 0.022712 +vt 0.000000 1.000000 +vt 0.000000 0.022712 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000098 1.000000 +vt 1.000000 1.000000 +vt 0.000098 0.000000 +vt 1.000000 0.000000 +vn 0.9300 0.3677 0.0000 +vn -0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn -0.0026 0.0005 1.0000 +vn 0.0000 1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.0234 0.0000 0.9997 +vn 1.0000 0.0000 0.0000 +usemtl None +s off +f 396/394/400 400/395/400 404/396/400 +f 395/397/401 396/394/401 397/398/401 +f 394/399/402 397/398/402 399/400/402 +f 394/399/403 399/400/403 400/395/403 +f 396/394/400 395/397/400 400/395/400 +f 398/401/404 394/399/404 400/395/404 +f 395/397/405 398/401/405 400/395/405 +f 395/397/401 397/398/401 401/402/401 +f 397/398/406 398/401/406 401/402/406 +f 398/401/405 395/397/405 401/402/405 +f 397/398/402 394/399/402 402/403/402 +f 394/399/407 398/401/407 402/403/407 +f 398/401/406 397/398/406 402/403/406 +f 397/398/401 396/394/401 403/404/401 +f 396/394/408 399/400/408 403/404/408 +f 399/400/402 397/398/402 403/404/402 +f 399/400/408 396/394/408 404/396/408 +f 400/395/403 399/400/403 404/396/403 +o Cup_hull_17 +v 0.015424 -0.020127 0.015036 +v 0.020163 -0.000379 -0.048198 +v 0.018057 -0.000379 -0.048198 +v 0.012263 -0.020390 -0.048198 +v 0.020426 -0.014861 -0.048192 +v 0.018057 -0.000379 0.015036 +v 0.012263 -0.013017 0.015036 +v 0.020426 -0.014859 0.015036 +v 0.012263 -0.013017 -0.048198 +v 0.020426 -0.000379 0.015036 +v 0.012263 -0.020390 0.015036 +v 0.014897 -0.020390 -0.048198 +v 0.018846 -0.016967 -0.048198 +v 0.020426 -0.000379 -0.048192 +v 0.018583 -0.017230 0.015036 +v 0.017003 -0.018811 -0.048198 +v 0.014897 -0.020390 0.015036 +v 0.017003 -0.018811 0.015036 +v 0.019899 -0.015651 0.015036 +v 0.015424 -0.020127 -0.044540 +v 0.019899 -0.015651 -0.048198 +vt 0.000000 0.236832 +vt 1.000000 0.171040 +vt 1.000000 0.236832 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 0.000000 0.013119 +vt 0.000000 0.368416 +vt 0.000000 0.276385 +vt 1.000000 0.368416 +vt 0.000000 1.000000 +vt 0.999902 0.276287 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 0.999902 1.000000 +vt 0.000000 0.157920 +vt 1.000000 0.078911 +vt 0.000000 0.000000 +vt 0.000000 0.078911 +vt 0.942150 0.013119 +vn 0.7809 -0.6247 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 1.0000 0.0000 +vn -0.0000 0.0000 1.0000 +vn -0.9090 0.4167 0.0000 +vn -1.0000 0.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0235 0.0000 -0.9997 +vn 0.4461 -0.8950 0.0000 +vn 0.7072 -0.7070 0.0000 +vn 0.7071 -0.7071 0.0000 +vn 0.6404 -0.7681 0.0000 +vn 0.8326 -0.5539 0.0000 +vn 0.7682 -0.6403 0.0005 +vn 0.5997 -0.7997 -0.0289 +vn 0.0121 -0.0002 -0.9999 +vn 0.8319 -0.5549 0.0000 +usemtl None +s off +f 423/405/409 417/406/409 425/407/409 +f 407/408/410 406/409/410 408/410/410 +f 406/409/411 407/408/411 410/411/411 +f 405/412/412 410/411/412 411/413/412 +f 410/411/413 407/408/413 411/413/413 +f 410/411/412 405/412/412 412/414/412 +f 407/408/410 408/410/410 413/415/410 +f 411/413/413 407/408/413 413/415/413 +f 408/410/414 411/413/414 413/415/414 +f 406/409/411 410/411/411 414/416/411 +f 412/414/415 409/417/415 414/416/415 +f 410/411/412 412/414/412 414/416/412 +f 405/412/412 411/413/412 415/418/412 +f 411/413/414 408/410/414 415/418/414 +f 408/410/410 406/409/410 416/419/410 +f 415/418/416 408/410/416 416/419/416 +f 416/419/410 406/409/410 417/406/410 +f 409/417/417 406/409/417 418/420/417 +f 406/409/411 414/416/411 418/420/411 +f 414/416/415 409/417/415 418/420/415 +f 412/414/412 405/412/412 419/421/412 +f 416/419/410 417/406/410 420/422/410 +f 405/412/412 415/418/412 421/423/412 +f 416/419/418 405/412/418 421/423/418 +f 415/418/416 416/419/416 421/423/416 +f 419/421/412 405/412/412 422/424/412 +f 417/406/419 419/421/419 422/424/419 +f 420/422/420 417/406/420 422/424/420 +f 405/412/421 420/422/421 422/424/421 +f 409/417/422 412/414/422 423/405/422 +f 412/414/412 419/421/412 423/405/412 +f 419/421/423 417/406/423 423/405/423 +f 405/412/418 416/419/418 424/425/418 +f 420/422/421 405/412/421 424/425/421 +f 416/419/424 420/422/424 424/425/424 +f 406/409/425 409/417/425 425/407/425 +f 417/406/410 406/409/410 425/407/410 +f 409/417/426 423/405/426 425/407/426 +o Cup_hull_18 +v -0.015651 0.019899 -0.048198 +v -0.020392 0.013317 0.015036 +v -0.011965 0.013317 0.015036 +v 0.000413 0.020426 0.015036 +v -0.011965 0.013317 -0.048198 +v 0.000413 0.018056 -0.048198 +v -0.014861 0.020425 0.015036 +v -0.020392 0.014897 -0.048198 +v 0.000413 0.020426 -0.048198 +v 0.000413 0.018056 0.015036 +v -0.020392 0.013317 -0.048198 +v -0.018811 0.017002 0.015036 +v -0.014861 0.020425 -0.048198 +v -0.020392 0.014897 0.015036 +v -0.018811 0.017002 -0.048198 +v -0.017231 0.018583 0.015036 +v -0.020127 0.015424 0.015036 +v -0.016966 0.018846 -0.048198 +v -0.015651 0.019899 0.015036 +v -0.020127 0.015424 -0.045667 +vt 0.000000 0.012725 +vt 1.000000 0.075959 +vt 0.959965 0.012725 +vt 0.000000 0.000000 +vt 0.000000 0.405051 +vt 0.000000 1.000000 +vt 1.000000 0.405051 +vt 1.000000 1.000000 +vt 1.000000 0.227878 +vt 0.000000 0.265858 +vt 1.000000 0.000000 +vt 1.000000 1.000000 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.075959 +vt 1.000000 0.265858 +vt 0.000000 0.000000 +vt 0.000000 0.151919 +vt 1.000000 0.164644 +vt 0.000000 0.227878 +vn -0.7682 0.6402 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.3576 -0.9339 0.0000 +vn -0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn -0.0000 1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.5543 0.8323 0.0000 +vn -0.7072 0.7070 0.0000 +vn -0.8935 0.4490 0.0000 +vn -0.7069 0.7074 -0.0000 +vn -0.6400 0.7684 0.0005 +vn -0.6249 0.7807 0.0000 +vn -0.7991 0.5998 -0.0413 +usemtl None +s off +f 442/426/427 440/427/427 445/428/427 +f 427/429/428 428/430/428 429/431/428 +f 428/430/429 427/429/429 430/432/429 +f 428/430/430 430/432/430 431/433/430 +f 430/432/431 426/434/431 431/433/431 +f 427/429/428 429/431/428 432/435/428 +f 426/434/431 430/432/431 433/436/431 +f 429/431/432 431/433/432 434/437/432 +f 431/433/431 426/434/431 434/437/431 +f 432/435/433 429/431/433 434/437/433 +f 429/431/428 428/430/428 435/438/428 +f 428/430/430 431/433/430 435/438/430 +f 431/433/432 429/431/432 435/438/432 +f 430/432/429 427/429/429 436/439/429 +f 433/436/431 430/432/431 436/439/431 +f 427/429/434 433/436/434 436/439/434 +f 427/429/428 432/435/428 437/440/428 +f 426/434/435 432/435/435 438/441/435 +f 434/437/431 426/434/431 438/441/431 +f 432/435/433 434/437/433 438/441/433 +f 433/436/434 427/429/434 439/442/434 +f 427/429/428 437/440/428 439/442/428 +f 426/434/431 433/436/431 440/427/431 +f 440/427/436 437/440/436 441/443/436 +f 437/440/428 432/435/428 441/443/428 +f 433/436/437 439/442/437 442/426/437 +f 439/442/428 437/440/428 442/426/428 +f 437/440/427 440/427/427 442/426/427 +f 426/434/431 440/427/431 443/444/431 +f 440/427/438 441/443/438 443/444/438 +f 443/444/439 441/443/439 444/445/439 +f 432/435/435 426/434/435 444/445/435 +f 441/443/428 432/435/428 444/445/428 +f 426/434/440 443/444/440 444/445/440 +f 440/427/441 433/436/441 445/428/441 +f 433/436/437 442/426/437 445/428/437 +o Cup_hull_19 +v 0.018056 0.017793 -0.048198 +v 0.000413 0.018056 0.015036 +v 0.012788 0.012527 0.015036 +v 0.014896 0.020427 0.015036 +v 0.000413 0.020426 -0.048198 +v 0.012788 0.012527 -0.048198 +v 0.020427 0.012527 0.015036 +v 0.020427 0.012527 -0.048192 +v 0.014896 0.020427 -0.048198 +v 0.000413 0.020426 0.015036 +v 0.000413 0.018056 -0.048198 +v 0.020427 0.014897 0.015036 +v 0.020427 0.014897 -0.048192 +v 0.018319 0.017529 0.015036 +v 0.015686 0.019898 0.015036 +v 0.019900 0.015686 -0.048198 +v 0.017265 0.018583 -0.048198 +v 0.019900 0.015686 0.015036 +v 0.018583 0.017266 -0.048198 +v 0.015686 0.019898 -0.048198 +v 0.017792 0.018056 0.015036 +vt 1.000000 0.842013 +vt 0.000000 0.763117 +vt 0.000000 0.868344 +vt 0.000000 0.000000 +vt 0.000000 0.618344 +vt 0.000000 0.723669 +vt 1.000000 0.618344 +vt 1.000000 0.000000 +vt 1.000000 0.881558 +vt 0.000000 1.000000 +vt 0.999902 1.000000 +vt 1.000000 0.723669 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 0.999902 1.000000 +vt 0.000000 0.894675 +vt 1.000000 0.973669 +vt 0.000000 0.973669 +vt 1.000000 0.907890 +vt 1.000000 0.763117 +vn 0.6585 0.7526 0.0008 +vn 0.0000 0.0000 1.0000 +vn -0.4079 -0.9130 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.0001 1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.5560 0.8312 0.0000 +vn 0.0008 -0.0018 -1.0000 +vn 0.0117 0.0000 -0.9999 +vn 0.8317 0.5552 -0.0000 +vn 0.8315 0.5555 0.0000 +vn 0.7682 0.6402 0.0000 +vn 0.7069 0.7073 0.0000 +vn -0.0001 0.0000 -1.0000 +vn 0.7590 0.6511 0.0005 +vn 0.6401 0.7683 0.0000 +vn 0.7066 0.7076 0.0000 +usemtl None +s off +f 462/446/442 460/447/442 466/448/442 +f 447/449/443 448/450/443 449/451/443 +f 448/450/444 447/449/444 451/452/444 +f 450/453/445 446/454/445 451/452/445 +f 448/450/446 451/452/446 452/455/446 +f 449/451/443 448/450/443 452/455/443 +f 452/455/446 451/452/446 453/456/446 +f 446/454/445 450/453/445 454/457/445 +f 450/453/447 449/451/447 454/457/447 +f 447/449/443 449/451/443 455/458/443 +f 449/451/447 450/453/447 455/458/447 +f 450/453/448 447/449/448 455/458/448 +f 447/449/448 450/453/448 456/459/448 +f 451/452/444 447/449/444 456/459/444 +f 450/453/445 451/452/445 456/459/445 +f 449/451/443 452/455/443 457/460/443 +f 452/455/449 453/456/449 457/460/449 +f 457/460/449 453/456/449 458/461/449 +f 449/451/443 457/460/443 459/462/443 +f 454/457/450 449/451/450 460/447/450 +f 449/451/443 459/462/443 460/447/443 +f 451/452/445 446/454/445 461/463/445 +f 453/456/451 451/452/451 461/463/451 +f 458/461/452 453/456/452 461/463/452 +f 457/460/453 458/461/453 461/463/453 +f 446/454/445 454/457/445 462/446/445 +f 459/462/443 457/460/443 463/464/443 +f 457/460/454 461/463/454 463/464/454 +f 463/464/455 461/463/455 464/465/455 +f 446/454/456 459/462/456 464/465/456 +f 461/463/457 446/454/457 464/465/457 +f 459/462/458 463/464/458 464/465/458 +f 454/457/450 460/447/450 465/466/450 +f 462/446/445 454/457/445 465/466/445 +f 460/447/459 462/446/459 465/466/459 +f 459/462/456 446/454/456 466/448/456 +f 460/447/443 459/462/443 466/448/443 +f 446/454/460 462/446/460 466/448/460 +o Cup_hull_20 +v -0.019075 -0.016703 0.048477 +v -0.021180 -0.009068 0.034429 +v -0.023551 -0.009068 0.034429 +v -0.013281 -0.021182 0.034429 +v -0.013281 -0.020127 0.050166 +v -0.022498 -0.009068 0.050166 +v -0.019075 -0.016703 0.034429 +v -0.013281 -0.018811 0.034429 +v -0.021708 -0.013019 0.050166 +v -0.015389 -0.020127 0.050166 +v -0.020918 -0.014335 0.034429 +v -0.023287 -0.009859 0.050166 +v -0.016705 -0.019074 0.034429 +v -0.013808 -0.021182 0.050166 +v -0.022234 -0.009068 0.049039 +v -0.014335 -0.020917 0.034429 +v -0.021180 -0.009068 0.035553 +v -0.022498 -0.011439 0.034429 +v -0.016705 -0.019074 0.050166 +v -0.013281 -0.018811 0.035553 +v -0.020127 -0.015387 0.050166 +v -0.023551 -0.009068 0.046230 +v -0.013281 -0.021182 0.050166 +v -0.023551 -0.009332 0.034429 +v -0.021708 -0.013019 0.034429 +v -0.023287 -0.009068 0.050166 +v -0.013808 -0.021182 0.034429 +vt 0.000000 0.000000 +vt 1.000000 0.021829 +vt 1.000000 0.000000 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 0.369714 +vt 1.000000 0.195673 +vt 0.000000 0.087020 +vt 0.000000 0.673845 +vt 0.000000 0.087020 +vt 1.000000 0.565192 +vt 0.000000 0.934710 +vt 0.107283 0.369714 +vt 1.000000 0.173943 +vt 0.071554 1.000000 +vt 0.928543 1.000000 +vt 1.000000 0.804229 +vt 0.000000 0.173943 +vt 0.928543 0.195673 +vt 0.000000 0.478367 +vt 0.250098 1.000000 +vt 0.000000 0.000000 +vt 1.000000 0.978172 +vt 1.000000 0.673845 +vt 0.000000 1.000000 +vn -0.4486 -0.8937 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 1.0000 -0.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn -0.7074 -0.7068 0.0000 +vn 0.7560 0.6300 0.1775 +vn -0.6137 -0.7895 -0.0015 +vn -0.5547 -0.8321 0.0046 +vn 0.7768 0.6297 0.0000 +vn 0.7728 0.6317 0.0604 +vn -0.8945 -0.4471 0.0000 +vn -0.6248 -0.7808 0.0000 +vn 0.7756 0.6287 0.0566 +vn -0.7810 -0.6246 0.0000 +vn -0.7892 -0.6141 -0.0014 +vn -0.8318 -0.5551 0.0047 +vn -0.7311 -0.6784 0.0731 +vn 0.0000 -1.0000 0.0000 +vn -0.0001 0.0000 -1.0000 +vn -0.8946 -0.4469 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.9579 -0.2870 0.0064 +vn -0.8574 -0.5147 0.0000 +vn -0.8943 -0.4474 0.0000 +vn -0.9978 0.0000 0.0668 +usemtl None +s off +f 480/467/461 482/468/461 493/469/461 +f 469/470/462 468/471/462 470/472/462 +f 468/471/463 469/470/463 472/473/463 +f 469/470/462 470/472/462 473/474/462 +f 470/472/462 468/471/462 474/475/462 +f 471/476/464 470/472/464 474/475/464 +f 471/476/465 472/473/465 475/477/465 +f 471/476/465 475/477/465 476/478/465 +f 469/470/462 473/474/462 477/479/462 +f 475/477/465 472/473/465 478/480/465 +f 467/481/466 473/474/466 479/482/466 +f 473/474/462 470/472/462 479/482/462 +f 471/476/465 476/478/465 480/467/465 +f 468/471/463 472/473/463 481/483/463 +f 472/473/467 471/476/467 481/483/467 +f 479/482/462 470/472/462 482/468/462 +f 476/478/468 479/482/468 482/468/468 +f 480/467/469 476/478/469 482/468/469 +f 474/475/470 468/471/470 483/484/470 +f 468/471/463 481/483/463 483/484/463 +f 481/483/471 471/476/471 483/484/471 +f 469/470/462 477/479/462 484/485/462 +f 475/477/472 478/480/472 484/485/472 +f 476/478/465 475/477/465 485/486/465 +f 467/481/466 479/482/466 485/486/466 +f 479/482/473 476/478/473 485/486/473 +f 471/476/464 474/475/464 486/487/464 +f 474/475/470 483/484/470 486/487/470 +f 483/484/474 471/476/474 486/487/474 +f 473/474/475 467/481/475 487/488/475 +f 477/479/476 473/474/476 487/488/476 +f 475/477/477 477/479/477 487/488/477 +f 467/481/478 485/486/478 487/488/478 +f 485/486/465 475/477/465 487/488/465 +f 472/473/463 469/470/463 488/489/463 +f 470/472/464 471/476/464 489/490/464 +f 480/467/479 470/472/479 489/490/479 +f 471/476/465 480/467/465 489/490/465 +f 469/470/480 484/485/480 490/491/480 +f 484/485/481 478/480/481 490/491/481 +f 488/489/482 469/470/482 490/491/482 +f 478/480/483 488/489/483 490/491/483 +f 477/479/484 475/477/484 491/492/484 +f 484/485/462 477/479/462 491/492/462 +f 475/477/485 484/485/485 491/492/485 +f 478/480/465 472/473/465 492/493/465 +f 472/473/463 488/489/463 492/493/463 +f 488/489/486 478/480/486 492/493/486 +f 470/472/479 480/467/479 493/469/479 +f 482/468/462 470/472/462 493/469/462 +o Cup_hull_21 +v -0.016705 -0.019073 0.034427 +v -0.015388 -0.009068 0.015038 +v -0.020391 -0.009068 0.015038 +v -0.013281 -0.020391 0.015038 +v -0.023552 -0.009332 0.034427 +v -0.013281 -0.018548 0.034143 +v -0.020127 -0.015387 0.015038 +v -0.020918 -0.009068 0.034143 +v -0.013281 -0.011966 0.015038 +v -0.023552 -0.009068 0.018410 +v -0.013808 -0.021182 0.018129 +v -0.013281 -0.021182 0.034427 +v -0.020918 -0.014335 0.034427 +v -0.016969 -0.018811 0.015038 +v -0.021708 -0.013019 0.018129 +v -0.015915 -0.009068 0.017568 +v -0.019075 -0.016704 0.034427 +v -0.014335 -0.020917 0.034427 +v -0.015388 -0.020126 0.015038 +v -0.021181 -0.009068 0.034427 +v -0.013281 -0.012492 0.017287 +v -0.022760 -0.009859 0.017006 +v -0.019075 -0.016704 0.015038 +v -0.023552 -0.009068 0.034427 +v -0.023552 -0.009332 0.018410 +v -0.021708 -0.013019 0.034427 +v -0.013281 -0.021182 0.017568 +v -0.013281 -0.018811 0.034427 +v -0.020391 -0.014861 0.015038 +v -0.020918 -0.014335 0.018410 +v -0.013808 -0.021182 0.034427 +v -0.022497 -0.009068 0.016725 +v -0.014335 -0.020917 0.018410 +vt 0.000000 0.021829 +vt 1.000000 0.087118 +vt 0.826057 0.021829 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.065290 +vt 1.000000 0.478367 +vt 0.014683 1.000000 +vt 1.000000 0.760768 +vt 0.014683 0.217404 +vt 0.826057 1.000000 +vt 0.000000 0.978172 +vt 0.000000 0.174041 +vt 0.000000 0.000000 +vt 0.000000 0.565192 +vt 1.000000 0.195673 +vt 0.869518 1.000000 +vt 0.000000 0.369616 +vt 0.000000 1.000000 +vt 0.884005 0.717306 +vt 1.000000 0.369616 +vt 0.000000 1.000000 +vt 0.826057 0.978172 +vt 0.840544 0.673845 +vt 0.898493 0.934710 +vt 0.000000 0.673845 +vt 0.869518 0.000000 +vt 0.840544 0.000000 +vt 0.000000 0.195673 +vt 1.000000 0.521731 +vt 0.826057 0.565192 +vt 0.000000 0.000000 +vt 0.912980 1.000000 +vn -0.6004 -0.7997 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 1.0000 0.0000 +vn 1.0000 0.0000 0.0000 +vn -0.0000 0.0000 1.0000 +vn 0.7581 0.6107 0.2288 +vn -0.7893 -0.6140 0.0011 +vn -0.7070 -0.7072 0.0000 +vn -0.6396 -0.7687 -0.0017 +vn -0.6140 -0.7893 0.0012 +vn 0.8012 0.5826 0.1364 +vn 0.7884 0.5929 0.1641 +vn 0.7832 0.5852 0.2102 +vn -0.7813 -0.6242 0.0000 +vn -0.7073 -0.7069 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.8944 -0.4473 0.0000 +vn -0.8713 0.0000 -0.4908 +vn 0.0001 0.0000 1.0000 +vn -0.8574 -0.5147 0.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.1189 -0.9477 -0.2963 +vn -0.2242 -0.9516 -0.2102 +vn 0.6737 0.5426 0.5017 +vn 0.6308 0.5114 0.5836 +vn -0.8882 -0.4454 -0.1129 +vn -0.8916 -0.4368 -0.1194 +vn -0.8797 -0.2601 -0.3981 +vn -0.7995 -0.6007 0.0000 +vn -0.8532 -0.5202 -0.0377 +vn -0.4486 -0.8937 0.0000 +vn -0.8440 0.0935 -0.5281 +vn -0.6252 0.0000 -0.7804 +vn -0.6798 -0.0338 -0.7326 +vn -0.4726 -0.8793 -0.0586 +usemtl None +s off +f 511/494/487 512/495/487 526/496/487 +f 496/497/488 495/498/488 497/499/488 +f 496/497/488 497/499/488 500/500/488 +f 495/498/489 496/497/489 501/501/489 +f 497/499/488 495/498/488 502/502/488 +f 499/503/490 497/499/490 502/502/490 +f 501/501/489 496/497/489 503/504/489 +f 498/505/491 494/506/491 505/507/491 +f 497/499/490 499/503/490 505/507/490 +f 494/506/491 498/505/491 506/508/491 +f 500/500/488 497/499/488 507/509/488 +f 495/498/489 501/501/489 509/510/489 +f 501/501/492 499/503/492 509/510/492 +f 494/506/491 506/508/491 510/511/491 +f 506/508/493 500/500/493 510/511/493 +f 507/509/494 494/506/494 510/511/494 +f 505/507/491 494/506/491 511/494/491 +f 507/509/488 497/499/488 512/495/488 +f 494/506/495 507/509/495 512/495/495 +f 511/494/496 494/506/496 512/495/496 +f 501/501/489 503/504/489 513/512/489 +f 498/505/491 505/507/491 513/512/491 +f 502/502/497 495/498/497 514/513/497 +f 499/503/490 502/502/490 514/513/490 +f 495/498/498 509/510/498 514/513/498 +f 509/510/499 499/503/499 514/513/499 +f 500/500/488 507/509/488 516/514/488 +f 510/511/500 500/500/500 516/514/500 +f 507/509/501 510/511/501 516/514/501 +f 503/504/502 498/505/502 517/515/502 +f 498/505/491 513/512/491 517/515/491 +f 513/512/489 503/504/489 517/515/489 +f 498/505/502 503/504/502 518/516/502 +f 508/517/503 498/505/503 518/516/503 +f 503/504/504 515/518/504 518/516/504 +f 506/508/505 498/505/505 519/519/505 +f 498/505/503 508/517/503 519/519/503 +f 508/517/506 506/508/506 519/519/506 +f 497/499/490 505/507/490 520/520/490 +f 505/507/507 504/521/507 520/520/507 +f 512/495/508 497/499/508 520/520/508 +f 504/521/509 512/495/509 520/520/509 +f 499/503/510 501/501/510 521/522/510 +f 505/507/490 499/503/490 521/522/490 +f 501/501/511 513/512/511 521/522/511 +f 513/512/491 505/507/491 521/522/491 +f 496/497/488 500/500/488 522/523/488 +f 500/500/512 508/517/512 522/523/512 +f 508/517/513 518/516/513 522/523/513 +f 518/516/514 515/518/514 522/523/514 +f 500/500/515 506/508/515 523/524/515 +f 508/517/516 500/500/516 523/524/516 +f 506/508/506 508/517/506 523/524/506 +f 504/521/507 505/507/507 524/525/507 +f 505/507/491 511/494/491 524/525/491 +f 511/494/517 504/521/517 524/525/517 +f 503/504/489 496/497/489 525/526/489 +f 515/518/518 503/504/518 525/526/518 +f 496/497/519 522/523/519 525/526/519 +f 522/523/520 515/518/520 525/526/520 +f 504/521/517 511/494/517 526/496/517 +f 512/495/521 504/521/521 526/496/521 +o Cup_hull_22 +v -0.024078 -0.007750 0.050164 +v -0.023025 -0.000378 0.033584 +v -0.025132 -0.000378 0.033584 +v -0.021182 -0.009067 0.033584 +v -0.024078 -0.000642 0.050164 +v -0.023814 -0.008540 0.033584 +v -0.022499 -0.009067 0.050164 +v -0.025132 -0.002485 0.050164 +v -0.024868 -0.004592 0.033584 +v -0.025132 -0.000378 0.050164 +v -0.021182 -0.008803 0.034991 +v -0.023551 -0.009067 0.050164 +v -0.023551 -0.009067 0.033584 +v -0.024604 -0.005907 0.050164 +v -0.023025 -0.000378 0.034991 +v -0.022499 -0.008540 0.050164 +v -0.025132 -0.002485 0.033584 +v -0.024604 -0.005907 0.033584 +v -0.024868 -0.004592 0.050164 +v -0.024078 -0.000378 0.048758 +v -0.021182 -0.008540 0.033584 +vt 0.915133 1.000000 +vt 0.915133 0.030345 +vt 1.000000 0.060689 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 1.000000 0.060689 +vt 0.000000 0.969655 +vt 0.000000 0.151527 +vt 0.000000 0.000000 +vt 0.000000 0.757537 +vt 1.000000 0.515074 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 0.000000 0.363645 +vt 0.000000 0.060689 +vt 1.000000 0.757537 +vt 1.000000 0.363645 +vt 0.000000 0.515074 +vt 0.084769 1.000000 +vn 0.9761 0.2136 0.0400 +vn 0.0000 0.0000 -1.0000 +vn -0.0000 0.0000 1.0000 +vn 0.0000 1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.9183 -0.3892 0.0729 +vn -0.9285 -0.3714 0.0029 +vn 0.0000 -1.0000 0.0000 +vn -0.8947 -0.4467 0.0000 +vn 0.9744 0.2132 0.0713 +vn 0.9773 0.1954 0.0814 +vn 0.9963 0.0000 0.0865 +vn -0.9922 -0.1244 0.0000 +vn -0.9578 -0.2874 -0.0015 +vn -0.9615 -0.2747 0.0000 +vn -0.9806 -0.1962 0.0000 +vn 0.2388 0.9544 0.1790 +vn 0.9238 0.3764 0.0706 +vn 1.0000 0.0000 0.0000 +vn 0.9754 0.2203 0.0000 +usemtl None +s off +f 541/527/522 537/528/522 547/529/522 +f 529/530/523 528/531/523 530/532/523 +f 529/530/523 530/532/523 532/533/523 +f 531/534/524 527/535/524 533/536/524 +f 527/535/524 531/534/524 534/537/524 +f 529/530/523 532/533/523 535/538/523 +f 528/531/525 529/530/525 536/539/525 +f 534/537/524 531/534/524 536/539/524 +f 529/530/526 534/537/526 536/539/526 +f 533/536/527 530/532/527 537/528/527 +f 527/535/528 532/533/528 538/540/528 +f 530/532/529 533/536/529 538/540/529 +f 533/536/524 527/535/524 538/540/524 +f 532/533/523 530/532/523 539/541/523 +f 538/540/530 532/533/530 539/541/530 +f 530/532/529 538/540/529 539/541/529 +f 527/535/524 534/537/524 540/542/524 +f 528/531/525 536/539/525 541/527/525 +f 531/534/531 537/528/531 541/527/531 +f 531/534/524 533/536/524 542/543/524 +f 537/528/532 531/534/532 542/543/532 +f 533/536/533 537/528/533 542/543/533 +f 534/537/526 529/530/526 543/544/526 +f 529/530/523 535/538/523 543/544/523 +f 535/538/534 534/537/534 543/544/534 +f 532/533/535 527/535/535 544/545/535 +f 535/538/523 532/533/523 544/545/523 +f 527/535/536 540/542/536 544/545/536 +f 540/542/537 535/538/537 544/545/537 +f 534/537/534 535/538/534 545/546/534 +f 540/542/524 534/537/524 545/546/524 +f 535/538/537 540/542/537 545/546/537 +f 536/539/538 531/534/538 546/547/538 +f 541/527/525 536/539/525 546/547/525 +f 531/534/539 541/527/539 546/547/539 +f 530/532/523 528/531/523 547/529/523 +f 537/528/540 530/532/540 547/529/540 +f 528/531/541 541/527/541 547/529/541 +o Cup_hull_23 +v -0.015652 -0.009067 0.015036 +v -0.025131 -0.002485 0.033582 +v -0.024868 -0.004592 0.033582 +v -0.024868 -0.003275 0.017567 +v -0.018022 -0.000378 0.015037 +v -0.020918 -0.009066 0.033301 +v -0.023550 -0.009066 0.017846 +v -0.022761 -0.000378 0.033301 +v -0.025131 -0.000378 0.017846 +v -0.020655 -0.008803 0.015037 +v -0.023550 -0.009066 0.033582 +v -0.015915 -0.008804 0.017004 +v -0.025131 -0.000378 0.033582 +v -0.020655 -0.000378 0.015037 +v -0.018549 -0.000378 0.018128 +v -0.024605 -0.005907 0.018409 +v -0.024341 -0.000378 0.016722 +v -0.025131 -0.002485 0.018409 +v -0.024078 -0.007750 0.033582 +v -0.024341 -0.004592 0.017004 +v -0.021181 -0.008277 0.033582 +v -0.020918 -0.008803 0.033301 +v -0.023024 -0.009066 0.017004 +v -0.023814 -0.008540 0.018409 +v -0.018022 -0.000378 0.015880 +v -0.022761 -0.000906 0.033582 +v -0.024868 -0.004592 0.018409 +v -0.024605 -0.005907 0.033582 +v -0.015652 -0.008804 0.015880 +v -0.020392 -0.009066 0.015037 +vt 0.893882 0.222222 +vt 0.999902 0.472149 +vt 0.999902 0.499951 +vt 0.015174 0.250024 +vt 0.999902 0.749976 +vt 0.848458 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.027704 +vt 0.000000 0.166716 +vt 1.000000 1.000000 +vt 0.015174 0.444445 +vt 0.848458 0.166716 +vt 0.893882 0.972198 +vt 0.000000 0.000000 +vt 0.999902 0.472149 +vt 0.833284 0.694371 +vt 0.863534 0.027704 +vt 0.909055 0.083309 +vt 0.818111 0.000000 +vt 0.000000 0.111111 +vt 0.818111 0.055507 +vt 0.893882 0.083309 +vt 0.000000 0.416642 +vt 0.015174 0.444445 +vt 0.818111 0.138913 +vt 0.954479 0.749976 +vt 0.000000 0.250024 +vt 0.818111 0.027704 +vt 0.000000 0.055507 +vt 0.954479 1.000000 +vn -0.5131 -0.5145 -0.6870 +vn 0.0000 1.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.0001 -1.0000 0.0000 +vn 0.6427 -0.7434 0.1853 +vn -1.0000 0.0000 0.0000 +vn 0.0000 0.0002 -1.0000 +vn -0.0004 0.0000 -1.0000 +vn 0.9313 0.2566 0.2585 +vn -0.8181 -0.0187 -0.5748 +vn -0.4157 0.0000 -0.9095 +vn -0.9923 -0.1237 0.0000 +vn -0.9683 -0.0645 -0.2414 +vn -0.9078 -0.2076 -0.3645 +vn -0.8945 -0.2302 -0.3832 +vn -0.7764 -0.0420 -0.6288 +vn -0.5198 -0.0569 -0.8524 +vn 0.1013 -0.3039 0.9473 +vn 0.9560 0.0000 0.2935 +vn 0.9357 0.2047 0.2872 +vn 0.7299 0.0000 0.6835 +vn -0.0001 -1.0000 -0.0001 +vn -0.8229 -0.2422 -0.5140 +vn -0.6161 -0.1813 -0.7665 +vn -0.8942 -0.4476 0.0000 +vn -0.9427 -0.2831 -0.1766 +vn -0.9283 -0.3718 0.0032 +vn -0.9577 -0.2876 -0.0017 +vn 0.9390 0.2641 0.2202 +vn 0.1042 0.4682 0.8774 +vn 0.9069 0.1984 0.3717 +vn 0.8662 0.1856 0.4639 +vn -0.9805 -0.1965 0.0000 +vn -0.9373 -0.1878 -0.2936 +vn -0.9743 -0.1214 -0.1898 +vn -0.9615 -0.2749 0.0000 +vn 0.9615 0.2623 -0.0817 +vn 0.7851 -0.5914 0.1841 +vn 0.9626 0.2708 0.0000 +vn -0.0004 -0.0004 -1.0000 +vn -0.0002 -1.0000 -0.0002 +usemtl None +s off +f 570/548/542 557/549/542 577/550/542 +f 555/551/543 552/552/543 556/553/543 +f 549/554/544 550/555/544 558/556/544 +f 548/557/545 553/558/545 558/556/545 +f 554/559/546 548/557/546 558/556/546 +f 553/558/547 548/557/547 559/560/547 +f 556/553/548 549/554/548 560/561/548 +f 555/551/543 556/553/543 560/561/543 +f 549/554/544 558/556/544 560/561/544 +f 552/552/549 548/557/549 561/562/549 +f 556/553/543 552/552/543 561/562/543 +f 548/557/550 557/549/550 561/562/550 +f 552/552/543 555/551/543 562/563/543 +f 555/551/551 559/560/551 562/563/551 +f 551/564/552 556/553/552 564/565/552 +f 556/553/543 561/562/543 564/565/543 +f 561/562/553 557/549/553 564/565/553 +f 550/555/554 549/554/554 565/566/554 +f 549/554/548 556/553/548 565/566/548 +f 556/553/555 551/564/555 565/566/555 +f 558/556/544 550/555/544 566/567/544 +f 563/568/556 551/564/556 567/569/556 +f 554/559/557 563/568/557 567/569/557 +f 551/564/558 564/565/558 567/569/558 +f 564/565/559 557/549/559 567/569/559 +f 558/556/560 553/558/560 568/570/560 +f 560/561/544 558/556/544 568/570/544 +f 553/558/561 559/560/561 569/571/561 +f 559/560/562 555/551/562 569/571/562 +f 568/570/563 553/558/563 569/571/563 +f 548/557/564 554/559/564 570/548/564 +f 554/559/565 567/569/565 570/548/565 +f 567/569/566 557/549/566 570/548/566 +f 554/559/567 558/556/567 571/572/567 +f 563/568/568 554/559/568 571/572/568 +f 558/556/569 566/567/569 571/572/569 +f 566/567/570 563/568/570 571/572/570 +f 552/552/543 562/563/543 572/573/543 +f 562/563/571 559/560/571 572/573/571 +f 555/551/572 560/561/572 573/574/572 +f 560/561/544 568/570/544 573/574/544 +f 569/571/573 555/551/573 573/574/573 +f 568/570/574 569/571/574 573/574/574 +f 563/568/575 550/555/575 574/575/575 +f 551/564/576 563/568/576 574/575/576 +f 550/555/554 565/566/554 574/575/554 +f 565/566/577 551/564/577 574/575/577 +f 550/555/575 563/568/575 575/576/575 +f 566/567/544 550/555/544 575/576/544 +f 563/568/578 566/567/578 575/576/578 +f 548/557/579 552/552/579 576/577/579 +f 559/560/580 548/557/580 576/577/580 +f 552/552/581 572/573/581 576/577/581 +f 572/573/571 559/560/571 576/577/571 +f 557/549/582 548/557/582 577/550/582 +f 548/557/583 570/548/583 577/550/583 +o Cup_hull_24 +v -0.025132 0.002520 0.050166 +v -0.021182 0.008313 0.032181 +v -0.023814 0.008313 0.032181 +v -0.022762 -0.000376 0.032181 +v -0.022762 0.008313 0.050166 +v -0.025132 -0.000376 0.032181 +v -0.024341 -0.000376 0.050166 +v -0.024078 0.007785 0.050166 +v -0.024604 0.005941 0.032181 +v -0.021182 0.007785 0.032744 +v -0.025132 -0.000376 0.050166 +v -0.025132 0.002520 0.032181 +v -0.024078 0.000677 0.050166 +v -0.022762 -0.000376 0.033306 +v -0.024604 0.005941 0.050166 +v -0.022762 0.007785 0.050166 +v -0.023814 0.008313 0.050166 +v -0.024078 0.007785 0.032181 +v -0.024868 0.004362 0.050166 +vt 0.000000 0.727068 +vt 1.000000 0.727068 +vt 0.000000 0.545276 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.333333 +vt 0.000000 0.939207 +vt 0.968677 0.939207 +vt 0.000000 0.000000 +vt 1.000000 0.333333 +vt 0.000000 0.121194 +vt 0.937451 0.000000 +vt 0.000000 0.939207 +vt 0.000000 1.000000 +vt 1.000000 0.939207 +vn -0.9864 0.1644 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 1.0000 0.0000 +vn 0.0000 -1.0000 -0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.9703 -0.1765 -0.1655 +vn 0.9919 0.0929 0.0871 +vn -1.0000 0.0000 0.0000 +vn 0.9791 -0.1835 0.0879 +vn 0.9818 -0.1901 0.0000 +vn 0.9662 -0.2416 0.0905 +vn -0.9615 0.2747 0.0000 +vn 0.9959 0.0000 0.0903 +vn 0.9794 -0.1813 0.0888 +vn -0.8950 0.4461 0.0000 +vn -0.9899 0.1419 0.0000 +vn -0.9883 0.1524 -0.0011 +usemtl None +s off +f 592/578/584 586/579/584 596/580/584 +f 580/581/585 579/582/585 581/583/585 +f 579/582/586 580/581/586 582/584/586 +f 580/581/585 581/583/585 583/585/585 +f 583/585/587 581/583/587 584/586/587 +f 582/584/588 578/587/588 584/586/588 +f 578/587/588 582/584/588 585/588/588 +f 580/581/585 583/585/585 586/579/585 +f 581/583/589 579/582/589 587/589/589 +f 579/582/590 582/584/590 587/589/590 +f 578/587/591 583/585/591 588/590/591 +f 583/585/587 584/586/587 588/590/587 +f 584/586/588 578/587/588 588/590/588 +f 583/585/591 578/587/591 589/591/591 +f 586/579/585 583/585/585 589/591/585 +f 582/584/588 584/586/588 590/592/588 +f 587/589/592 590/592/592 591/593/592 +f 584/586/587 581/583/587 591/593/587 +f 581/583/593 587/589/593 591/593/593 +f 590/592/594 584/586/594 591/593/594 +f 578/587/588 585/588/588 592/578/588 +f 585/588/595 586/579/595 592/578/595 +f 587/589/596 582/584/596 593/594/596 +f 582/584/588 590/592/588 593/594/588 +f 590/592/597 587/589/597 593/594/597 +f 582/584/586 580/581/586 594/595/586 +f 580/581/598 585/588/598 594/595/598 +f 585/588/588 582/584/588 594/595/588 +f 585/588/598 580/581/598 595/596/598 +f 580/581/585 586/579/585 595/596/585 +f 586/579/595 585/588/595 595/596/595 +f 589/591/599 578/587/599 596/580/599 +f 586/579/600 589/591/600 596/580/600 +f 578/587/588 592/578/588 596/580/588 +o Cup_hull_25 +v -0.023551 0.007522 0.017006 +v -0.025132 -0.000376 0.032177 +v -0.022760 -0.000376 0.032177 +v -0.020655 -0.000376 0.015037 +v -0.016179 0.008313 0.016444 +v -0.023814 0.008313 0.032177 +v -0.025132 -0.000376 0.017848 +v -0.018023 -0.000376 0.015881 +v -0.020917 0.008313 0.031895 +v -0.020655 0.008313 0.015037 +v -0.024604 0.005941 0.018410 +v -0.016179 0.007785 0.015037 +v -0.025132 0.002520 0.032177 +v -0.023814 0.008313 0.017848 +v -0.022497 -0.000376 0.031895 +v -0.024340 0.001730 0.016724 +v -0.025132 0.002520 0.018410 +v -0.024604 0.005941 0.032177 +v -0.018023 -0.000376 0.015037 +v -0.016179 0.008048 0.016444 +v -0.018549 -0.000376 0.018130 +v -0.020917 0.008048 0.031895 +v -0.021180 0.008313 0.032177 +v -0.024340 0.004362 0.017006 +v -0.024340 -0.000376 0.016724 +v -0.024077 0.007785 0.032177 +v -0.016179 0.008313 0.015037 +v -0.024077 0.007785 0.018410 +v -0.024867 0.004362 0.018130 +v -0.024867 0.001730 0.017286 +vt 0.803211 0.000000 +vt 0.819561 0.029561 +vt 0.868807 0.029561 +vt 0.000000 0.264879 +vt 0.000000 0.000000 +vt 1.000000 0.500000 +vt 0.000000 0.147220 +vt 0.836009 0.000000 +vt 0.950754 0.794048 +vt 0.917956 1.000000 +vt 0.016448 0.470732 +vt 1.000000 0.500000 +vt 1.000000 1.000000 +vt 0.000000 0.000000 +vt 0.836009 0.147220 +vt 0.885158 0.176586 +vt 0.016448 0.294244 +vt 0.901606 0.088391 +vt 0.000000 0.058927 +vt 1.000000 0.794048 +vt 0.917956 1.000000 +vt 0.819561 0.735219 +vt 0.016448 0.470732 +vt 0.000000 0.441366 +vt 0.885158 0.088391 +vt 0.901606 0.088391 +vt 0.000000 0.117756 +vt 0.803211 0.058927 +vt 1.000000 1.000000 +vt 0.803211 0.117756 +vn -0.9527 0.0929 -0.2895 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 1.0000 -0.0000 +vn -0.0000 0.0000 -1.0000 +vn -1.0000 0.0000 0.0000 +vn -0.5764 0.4982 -0.6477 +vn -0.4161 0.0000 -0.9093 +vn 0.9754 -0.2204 0.0000 +vn 0.9561 0.0000 0.2932 +vn 0.9755 -0.2162 0.0405 +vn 1.0000 0.0000 0.0000 +vn 0.9397 -0.2105 0.2695 +vn 0.9492 -0.2226 0.2223 +vn 0.7245 -0.1359 0.6757 +vn 0.9410 -0.1765 0.2886 +vn 0.6667 -0.1212 0.7354 +vn 0.7313 0.0000 0.6820 +vn -0.5831 0.1457 -0.7992 +vn -0.8571 0.2142 -0.4686 +vn -0.5422 0.0895 -0.8355 +vn -0.8946 0.4468 0.0000 +vn -0.9615 0.2747 0.0000 +vn -0.9441 0.2698 -0.1895 +vn -0.9058 0.2155 -0.3647 +vn -0.9898 0.1423 0.0000 +vn -0.9864 0.1642 0.0000 +vn -0.9883 0.1524 0.0014 +vn -0.8860 0.2066 -0.4151 +vn -0.8973 0.1348 -0.4203 +vn -0.9635 0.0510 -0.2626 +vn -0.7278 0.0730 -0.6819 +vn -0.8167 -0.0508 -0.5748 +vn -0.7298 0.0000 -0.6837 +usemtl None +s off +f 613/597/601 625/598/601 626/599/601 +f 599/600/602 598/601/602 600/602/602 +f 598/601/603 599/600/603 602/603/603 +f 600/602/602 598/601/602 603/604/602 +f 599/600/602 600/602/602 604/605/602 +f 601/606/604 602/603/604 605/607/604 +f 602/603/604 601/606/604 606/608/604 +f 600/602/605 606/608/605 608/609/605 +f 598/601/603 602/603/603 609/610/603 +f 603/604/606 598/601/606 609/610/606 +f 602/603/604 606/608/604 610/611/604 +f 606/608/607 597/612/607 610/611/607 +f 599/600/602 604/605/602 611/613/602 +f 606/608/608 600/602/608 612/614/608 +f 603/604/606 609/610/606 613/597/606 +f 609/610/603 602/603/603 614/615/603 +f 604/605/602 600/602/602 615/616/602 +f 600/602/605 608/609/605 615/616/605 +f 608/609/609 604/605/609 615/616/609 +f 601/606/610 605/607/610 616/617/610 +f 604/605/611 608/609/611 616/617/611 +f 608/609/612 601/606/612 616/617/612 +f 616/617/613 611/613/613 617/618/613 +f 611/613/602 604/605/602 617/618/602 +f 604/605/614 616/617/614 617/618/614 +f 599/600/615 611/613/615 618/619/615 +f 616/617/610 605/607/610 618/619/610 +f 611/613/616 616/617/616 618/619/616 +f 602/603/603 599/600/603 619/620/603 +f 605/607/604 602/603/604 619/620/604 +f 599/600/617 618/619/617 619/620/617 +f 618/619/618 605/607/618 619/620/618 +f 597/612/619 606/608/619 620/621/619 +f 610/611/620 597/612/620 620/621/620 +f 606/608/621 612/614/621 620/621/621 +f 600/602/602 603/604/602 621/622/602 +f 612/614/608 600/602/608 621/622/608 +f 602/603/622 610/611/622 622/623/622 +f 614/615/603 602/603/603 622/623/603 +f 607/624/623 614/615/623 622/623/623 +f 606/608/604 601/606/604 623/625/604 +f 601/606/612 608/609/612 623/625/612 +f 608/609/605 606/608/605 623/625/605 +f 610/611/624 607/624/624 624/626/624 +f 622/623/622 610/611/622 624/626/622 +f 607/624/623 622/623/623 624/626/623 +f 607/624/625 610/611/625 625/598/625 +f 613/597/626 609/610/626 625/598/626 +f 614/615/627 607/624/627 625/598/627 +f 609/610/628 614/615/628 625/598/628 +f 610/611/629 620/621/629 625/598/629 +f 625/598/630 620/621/630 626/599/630 +f 603/604/631 613/597/631 626/599/631 +f 620/621/632 612/614/632 626/599/632 +f 621/622/633 603/604/633 626/599/633 +f 612/614/634 621/622/634 626/599/634 +o Cup_hull_26 +v -0.020654 0.014632 0.050164 +v -0.014335 0.020690 0.033584 +v -0.014335 0.017793 0.033584 +v -0.023815 0.008313 0.033584 +v -0.022761 0.008313 0.050164 +v -0.014335 0.019373 0.050164 +v -0.021180 0.008578 0.034149 +v -0.020127 0.015422 0.033584 +v -0.015388 0.020163 0.050164 +v -0.023288 0.009895 0.050164 +v -0.021708 0.013055 0.033584 +v -0.016968 0.018846 0.033584 +v -0.018549 0.017265 0.050164 +v -0.023815 0.008313 0.050164 +v -0.021444 0.008313 0.033584 +v -0.014335 0.020690 0.050164 +v -0.021708 0.013055 0.050164 +v -0.023288 0.009895 0.033584 +v -0.022497 0.008578 0.050164 +v -0.014598 0.020690 0.033584 +v -0.014335 0.017793 0.034430 +v -0.021444 0.008313 0.035272 +v -0.018812 0.017002 0.033584 +v -0.016968 0.018846 0.050164 +v -0.023815 0.008578 0.050164 +v -0.015388 0.020163 0.033584 +v -0.023815 0.008578 0.033584 +v -0.019865 0.015685 0.050164 +v -0.014598 0.020690 0.050164 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 0.000000 1.000000 +vt 1.000000 1.000000 +vt 1.000000 0.765955 +vt 1.000000 0.000000 +vt 0.000000 0.893598 +vt 0.000000 0.510572 +vt 0.000000 0.000000 +vt 1.000000 0.574393 +vt 0.000000 0.957420 +vt 0.000000 0.127839 +vt 1.000000 0.383124 +vt 1.000000 0.851018 +vt 0.000000 0.723277 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 0.965936 0.021437 +vt 0.000000 0.383124 +vt 1.000000 0.127839 +vt 0.000000 0.021437 +vt 0.949002 0.765955 +vt 0.898199 0.000000 +vt 1.000000 0.702036 +vt 0.000000 0.851018 +vt 0.000000 0.021437 +vt 1.000000 0.957420 +vt 1.000000 0.021437 +vt 0.000000 0.595634 +vn 0.0000 1.0000 0.0000 +vn -0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.7967 -0.5975 -0.0911 +vn -0.8316 0.5553 0.0000 +vn -0.8317 0.5552 0.0000 +vn -0.8944 0.4473 0.0000 +vn 0.8027 -0.5963 0.0000 +vn 0.8012 -0.5966 0.0471 +vn 0.7095 -0.7047 0.0000 +vn 0.7081 -0.7034 0.0626 +vn 0.7958 -0.6018 0.0670 +vn 0.8011 -0.5955 0.0598 +vn -0.7073 0.7070 0.0000 +vn -0.6402 0.7682 0.0000 +vn -0.7071 0.7071 0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.9284 0.3716 0.0000 +vn -0.5551 0.8318 0.0000 +vn -0.8000 0.6001 0.0032 +vn 0.0001 0.0000 1.0000 +vn -0.7686 0.6397 0.0020 +vn -0.7684 0.6400 0.0021 +usemtl None +s off +f 642/627/635 646/628/635 655/629/635 +f 628/630/636 629/631/636 630/632/636 +f 629/631/637 628/630/637 632/633/637 +f 627/634/638 631/635/638 632/633/638 +f 628/630/636 630/632/636 634/636/636 +f 627/634/638 632/633/638 635/637/638 +f 631/635/638 627/634/638 636/638/638 +f 634/636/636 630/632/636 637/639/636 +f 628/630/636 634/636/636 638/640/636 +f 627/634/638 635/637/638 639/641/638 +f 630/632/639 631/635/639 640/642/639 +f 631/635/638 636/638/638 640/642/638 +f 630/632/636 629/631/636 641/643/636 +f 631/635/639 630/632/639 641/643/639 +f 629/631/640 633/644/640 641/643/640 +f 632/633/637 628/630/637 642/627/637 +f 635/637/638 632/633/638 642/627/638 +f 627/634/641 634/636/641 643/645/641 +f 636/638/638 627/634/638 643/645/638 +f 634/636/642 637/639/642 643/645/642 +f 637/639/643 636/638/643 643/645/643 +f 637/639/636 630/632/636 644/646/636 +f 636/638/643 637/639/643 644/646/643 +f 632/633/638 631/635/638 645/647/638 +f 628/630/636 638/640/636 646/628/636 +f 642/627/635 628/630/635 646/628/635 +f 629/631/637 632/633/637 647/648/637 +f 633/644/644 629/631/644 647/648/644 +f 633/644/645 647/648/645 648/649/645 +f 631/635/639 641/643/639 648/649/639 +f 641/643/646 633/644/646 648/649/646 +f 645/647/647 631/635/647 648/649/647 +f 632/633/648 645/647/648 648/649/648 +f 647/648/649 632/633/649 648/649/649 +f 638/640/636 634/636/636 649/650/636 +f 649/650/650 639/641/650 650/651/650 +f 635/637/651 638/640/651 650/651/651 +f 639/641/638 635/637/638 650/651/638 +f 638/640/652 649/650/652 650/651/652 +f 630/632/653 640/642/653 651/652/653 +f 640/642/638 636/638/638 651/652/638 +f 636/638/654 644/646/654 651/652/654 +f 638/640/651 635/637/651 652/653/651 +f 646/628/636 638/640/636 652/653/636 +f 635/637/655 646/628/655 652/653/655 +f 644/646/636 630/632/636 653/654/636 +f 630/632/653 651/652/653 653/654/653 +f 651/652/654 644/646/654 653/654/654 +f 634/636/656 627/634/656 654/655/656 +f 627/634/657 639/641/657 654/655/657 +f 649/650/658 634/636/658 654/655/658 +f 639/641/659 649/650/659 654/655/659 +f 635/637/638 642/627/638 655/629/638 +f 646/628/655 635/637/655 655/629/655 +o Cup_hull_27 +v -0.023550 0.008578 0.017568 +v -0.014335 0.020690 0.017848 +v -0.014335 0.020426 0.015039 +v -0.015915 0.008313 0.015882 +v -0.021180 0.008313 0.033582 +v -0.014335 0.020690 0.033582 +v -0.021708 0.013055 0.033582 +v -0.020127 0.015422 0.015039 +v -0.014335 0.017529 0.033301 +v -0.014335 0.010684 0.015039 +v -0.023815 0.008313 0.033582 +v -0.016968 0.018845 0.033582 +v -0.020654 0.008313 0.015039 +v -0.023288 0.009895 0.018411 +v -0.017233 0.018582 0.015039 +v -0.018812 0.017002 0.033582 +v -0.015388 0.020163 0.016724 +v -0.021708 0.013055 0.018411 +v -0.023815 0.008313 0.018411 +v -0.023288 0.009895 0.033582 +v -0.016179 0.008313 0.017005 +v -0.020127 0.015422 0.033582 +v -0.014598 0.020690 0.033582 +v -0.015915 0.008313 0.015039 +v -0.014335 0.010947 0.016443 +v -0.018812 0.017002 0.015039 +v -0.014335 0.017793 0.033582 +v -0.020391 0.014895 0.015039 +v -0.023815 0.008578 0.018411 +v -0.015388 0.020163 0.033582 +v -0.022761 0.008313 0.016724 +v -0.014862 0.020426 0.015039 +v -0.014598 0.020690 0.017848 +v -0.023815 0.008578 0.033582 +vt 0.000000 0.127839 +vt 0.818191 0.021437 +vt 0.000000 0.021437 +vt 1.000000 0.978661 +vt 0.848541 1.000000 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 0.000000 0.383125 +vt 0.015175 0.744616 +vt 1.000000 0.574393 +vt 1.000000 0.191562 +vt 0.954572 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.850920 +vt 1.000000 0.000000 +vt 1.000000 0.829679 +vt 0.000000 0.702036 +vt 0.909144 0.957420 +vt 0.818191 0.383125 +vt 0.818191 0.127839 +vt 0.818191 0.000000 +vt 0.893969 0.000000 +vt 0.000000 0.574393 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.924320 0.212803 +vt 1.000000 0.702036 +vt 0.000000 0.765955 +vt 1.000000 0.531813 +vt 0.863619 0.021437 +vt 0.000000 0.957420 +vt 0.909144 0.000000 +vt 1.000000 0.978661 +vt 0.848541 1.000000 +vn -0.9284 0.3716 0.0000 +vn 1.0000 0.0000 0.0000 +vn -0.0000 0.0000 1.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.7069 0.7073 0.0001 +vn -0.6500 0.7600 -0.0015 +vn -0.8317 0.5552 0.0000 +vn -0.8895 0.4449 -0.1046 +vn -0.8944 0.4473 0.0000 +vn 0.7835 -0.5747 0.2364 +vn -0.7686 0.6397 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.8321 -0.5546 0.0000 +vn 0.8439 -0.5274 0.0988 +vn 0.8227 -0.5347 0.1929 +vn 0.8217 -0.5309 0.2073 +vn -0.7072 0.7070 0.0000 +vn 0.7105 -0.5131 0.4816 +vn -0.8895 0.4448 -0.1047 +vn -0.9014 0.3608 -0.2395 +vn -0.9541 0.0000 -0.2995 +vn -1.0000 0.0000 0.0000 +vn -0.8985 0.3365 -0.2821 +vn -0.6405 0.7679 0.0000 +vn -0.5551 0.8318 0.0000 +vn -0.6501 -0.6421 -0.4063 +vn -0.7153 0.0799 -0.6942 +vn -0.6244 0.0250 -0.7807 +vn 0.0000 0.9956 -0.0936 +vn -0.6125 0.7875 -0.0684 +vn -0.5241 0.8511 -0.0309 +usemtl None +s off +f 675/656/660 684/657/660 689/658/660 +f 658/659/661 657/660/661 661/661/661 +f 660/662/662 661/661/662 662/663/662 +f 658/659/661 661/661/661 664/664/661 +f 663/665/663 658/659/663 665/666/663 +f 658/659/661 664/664/661 665/666/661 +f 659/667/664 660/662/664 666/668/664 +f 660/662/662 662/663/662 666/668/662 +f 662/663/662 661/661/662 667/669/662 +f 663/665/663 665/666/663 668/670/663 +f 659/667/664 666/668/664 668/670/664 +f 658/659/663 663/665/663 670/671/663 +f 667/669/665 670/671/665 671/672/665 +f 662/663/662 667/669/662 671/672/662 +f 670/671/666 667/669/666 672/673/666 +f 662/663/667 663/665/667 673/674/667 +f 663/665/668 669/675/668 673/674/668 +f 669/675/669 662/663/669 673/674/669 +f 668/670/664 666/668/664 674/676/664 +f 666/668/662 662/663/662 675/656/662 +f 662/663/669 669/675/669 675/656/669 +f 660/662/664 659/667/664 676/677/664 +f 664/664/670 660/662/670 676/677/670 +f 663/665/667 662/663/667 677/678/667 +f 662/663/662 671/672/662 677/678/662 +f 671/672/671 663/665/671 677/678/671 +f 661/661/672 657/660/672 678/679/672 +f 667/669/662 661/661/662 678/679/662 +f 665/666/673 659/667/673 679/680/673 +f 668/670/663 665/666/663 679/680/663 +f 659/667/664 668/670/664 679/680/664 +f 659/667/674 665/666/674 680/681/674 +f 665/666/661 664/664/661 680/681/661 +f 676/677/675 659/667/675 680/681/675 +f 664/664/676 676/677/676 680/681/676 +f 670/671/663 663/665/663 681/682/663 +f 671/672/677 670/671/677 681/682/677 +f 663/665/671 671/672/671 681/682/671 +f 661/661/662 660/662/662 682/683/662 +f 660/662/678 664/664/678 682/683/678 +f 664/664/661 661/661/661 682/683/661 +f 663/665/663 668/670/663 683/684/663 +f 669/675/679 663/665/679 683/684/679 +f 669/675/680 683/684/680 684/657/680 +f 656/685/681 674/676/681 684/657/681 +f 674/676/682 666/668/682 684/657/682 +f 675/656/660 669/675/660 684/657/660 +f 683/684/683 656/685/683 684/657/683 +f 672/673/684 667/669/684 685/686/684 +f 667/669/662 678/679/662 685/686/662 +f 678/679/685 672/673/685 685/686/685 +f 674/676/686 656/685/686 686/687/686 +f 668/670/664 674/676/664 686/687/664 +f 656/685/687 683/684/687 686/687/687 +f 683/684/688 668/670/688 686/687/688 +f 657/660/689 658/659/689 687/688/689 +f 658/659/663 670/671/663 687/688/663 +f 670/671/690 672/673/690 687/688/690 +f 678/679/672 657/660/672 688/689/672 +f 672/673/685 678/679/685 688/689/685 +f 657/660/689 687/688/689 688/689/689 +f 687/688/691 672/673/691 688/689/691 +f 666/668/662 675/656/662 689/658/662 +f 684/657/682 666/668/682 689/658/682 +o Cup_hull_28 +v 0.018582 -0.017233 0.015041 +v 0.008313 -0.023815 0.050164 +v 0.008579 -0.023815 0.050164 +v 0.019372 -0.014335 0.050164 +v 0.008313 -0.015916 0.015041 +v 0.008313 -0.023815 0.018414 +v 0.020425 -0.014335 0.015041 +v 0.015421 -0.020128 0.050164 +v 0.010685 -0.014335 0.015041 +v 0.015421 -0.020128 0.015041 +v 0.020689 -0.014598 0.050164 +v 0.008579 -0.022497 0.050164 +v 0.013054 -0.021707 0.018414 +v 0.008313 -0.020653 0.015041 +v 0.018055 -0.017759 0.050164 +v 0.008313 -0.015916 0.015883 +v 0.013056 -0.021707 0.050164 +v 0.009895 -0.023288 0.018132 +v 0.020688 -0.014599 0.017850 +v 0.017002 -0.018812 0.015041 +v 0.009105 -0.023023 0.017008 +v 0.020689 -0.014335 0.050164 +v 0.019898 -0.015651 0.050164 +v 0.009896 -0.023288 0.050164 +v 0.017001 -0.018812 0.050164 +v 0.008313 -0.022760 0.050164 +v 0.019899 -0.015652 0.015041 +v 0.018581 -0.017233 0.050164 +v 0.010948 -0.014335 0.016444 +v 0.008578 -0.023815 0.018414 +v 0.014896 -0.020391 0.015041 +v 0.020688 -0.014335 0.017850 +v 0.008578 -0.023550 0.017568 +vt 1.000000 0.531911 +vt 0.911992 0.127839 +vt 0.928047 0.021437 +vt 0.000000 0.000000 +vt 0.000000 0.021535 +vt 0.000000 0.893598 +vt 1.000000 0.000000 +vt 0.903965 0.000000 +vt 1.000000 0.829777 +vt 1.000000 0.978661 +vt 0.000000 0.574393 +vt 1.000000 0.191660 +vt 1.000000 0.574393 +vt 0.000000 1.000000 +vt 0.000000 0.021535 +vt 1.000000 0.000000 +vt 0.000000 0.787197 +vt 0.976016 0.000000 +vt 0.000000 0.383222 +vt 0.903965 0.383124 +vt 1.000000 0.702134 +vt 0.000000 1.000000 +vt 0.920020 0.999902 +vt 0.000000 0.936081 +vt 0.000000 0.127937 +vt 0.000000 0.702036 +vt 0.000000 0.000000 +vt 1.000000 0.936179 +vt 0.000000 0.829679 +vt 0.960059 0.212901 +vt 0.903965 0.021437 +vt 0.944004 0.064017 +vt 0.920020 0.999902 +vn 0.3165 -0.8917 -0.3237 +vn 0.0000 0.0000 1.0000 +vn -1.0000 -0.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 1.0000 0.0000 +vn -0.5547 0.8321 0.0000 +vn -0.5958 0.7878 0.1559 +vn 0.5550 -0.8318 0.0000 +vn 0.5548 -0.8320 -0.0000 +vn 0.4476 -0.8942 -0.0000 +vn 0.4524 -0.8865 -0.0974 +vn 0.6397 -0.7686 0.0000 +vn 0.7070 -0.7072 0.0000 +vn 1.0000 0.0000 -0.0000 +vn 0.3716 -0.9284 -0.0000 +vn 0.6400 -0.7683 0.0000 +vn 0.7069 -0.7073 0.0000 +vn -0.6949 0.7052 0.1408 +vn 0.9220 -0.3679 -0.1209 +vn 0.8005 -0.5993 -0.0000 +vn 0.7996 -0.6005 0.0000 +vn 0.7684 -0.6399 0.0000 +vn 0.7074 -0.7068 0.0000 +vn 0.7683 -0.6401 0.0000 +vn -0.5306 0.8372 0.1326 +vn -0.5274 0.8438 0.0988 +vn 0.4439 -0.8887 -0.1148 +vn 0.0253 -0.6334 -0.7734 +vn 0.9957 0.0000 -0.0932 +vn -0.8238 -0.4136 -0.3877 +vn -0.1297 -0.6585 -0.7413 +vn 0.0000 -0.9544 -0.2984 +vn 0.3032 -0.9095 -0.2844 +vn 0.1567 -0.7887 -0.5944 +usemtl None +s off +f 720/690/692 707/691/692 722/692/692 +f 691/693/693 692/694/693 693/695/693 +f 691/693/694 694/696/694 695/697/694 +f 692/694/695 691/693/695 695/697/695 +f 690/698/696 694/696/696 696/699/696 +f 693/695/693 692/694/693 697/700/693 +f 693/695/697 696/699/697 698/701/697 +f 696/699/696 694/696/696 698/701/696 +f 694/696/696 690/698/696 699/702/696 +f 693/695/693 697/700/693 700/703/693 +f 691/693/693 693/695/693 701/704/693 +f 695/697/694 694/696/694 703/705/694 +f 694/696/696 699/702/696 703/705/696 +f 700/703/693 697/700/693 704/706/693 +f 694/696/694 691/693/694 705/707/694 +f 698/701/698 694/696/698 705/707/698 +f 701/704/699 693/695/699 705/707/699 +f 697/700/693 692/694/693 706/708/693 +f 699/702/700 697/700/700 706/708/700 +f 702/709/701 699/702/701 706/708/701 +f 702/709/702 706/708/702 707/691/702 +f 699/702/703 702/709/703 707/691/703 +f 699/702/696 690/698/696 709/710/696 +f 697/700/704 699/702/704 709/710/704 +f 690/698/705 704/706/705 709/710/705 +f 696/699/697 693/695/697 711/711/697 +f 693/695/693 700/703/693 711/711/693 +f 700/703/706 708/712/706 711/711/706 +f 700/703/693 704/706/693 712/713/693 +f 706/708/693 692/694/693 713/714/693 +f 707/691/702 706/708/702 713/714/702 +f 692/694/707 707/691/707 713/714/707 +f 704/706/693 697/700/693 714/715/693 +f 697/700/708 709/710/708 714/715/708 +f 709/710/709 704/706/709 714/715/709 +f 691/693/693 701/704/693 715/716/693 +f 705/707/694 691/693/694 715/716/694 +f 701/704/710 705/707/710 715/716/710 +f 690/698/696 696/699/696 716/717/696 +f 696/699/711 708/712/711 716/717/711 +f 708/712/712 700/703/712 716/717/712 +f 700/703/713 712/713/713 716/717/713 +f 716/717/714 712/713/714 717/718/714 +f 704/706/715 690/698/715 717/718/715 +f 712/713/693 704/706/693 717/718/693 +f 690/698/716 716/717/716 717/718/716 +f 693/695/697 698/701/697 718/719/697 +f 705/707/717 693/695/717 718/719/717 +f 698/701/718 705/707/718 718/719/718 +f 692/694/695 695/697/695 719/720/695 +f 707/691/707 692/694/707 719/720/707 +f 703/705/696 699/702/696 720/690/696 +f 699/702/719 707/691/719 720/690/719 +f 710/721/720 703/705/720 720/690/720 +f 708/712/721 696/699/721 721/722/721 +f 696/699/697 711/711/697 721/722/697 +f 711/711/706 708/712/706 721/722/706 +f 695/697/722 703/705/722 722/692/722 +f 703/705/723 710/721/723 722/692/723 +f 719/720/724 695/697/724 722/692/724 +f 707/691/725 719/720/725 722/692/725 +f 710/721/726 720/690/726 722/692/726 +o Cup_hull_29 +v -0.020392 -0.000377 0.015036 +v -0.016441 0.007259 -0.048198 +v -0.016441 0.006732 -0.048198 +v -0.020392 0.007259 -0.048198 +v -0.016441 0.007259 0.015036 +v -0.018022 -0.000377 -0.048198 +v -0.020392 0.007259 0.015036 +v -0.018022 -0.000377 0.015036 +v -0.020392 -0.000377 -0.048198 +v -0.016441 0.006732 0.013624 +vt 0.000000 0.000000 +vt 1.000000 0.930991 +vt 0.022318 0.930991 +vt 1.000000 1.000000 +vt 1.000000 1.000000 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vn 0.9762 -0.2170 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 1.0000 0.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0000 0.0000 1.0000 +vn 0.0000 -1.0000 0.0000 +vn 0.9765 -0.2021 0.0755 +usemtl None +s off +f 730/723/727 725/724/727 732/725/727 +f 724/726/728 725/724/728 726/727/728 +f 725/724/729 724/726/729 727/728/729 +f 724/726/730 726/727/730 727/728/730 +f 726/727/728 725/724/728 728/729/728 +f 726/727/731 723/730/731 729/731/731 +f 723/730/732 727/728/732 729/731/732 +f 727/728/730 726/727/730 729/731/730 +f 727/728/732 723/730/732 730/723/732 +f 728/729/727 725/724/727 730/723/727 +f 723/730/733 728/729/733 730/723/733 +f 723/730/731 726/727/731 731/732/731 +f 726/727/728 728/729/728 731/732/728 +f 728/729/733 723/730/733 731/732/733 +f 725/724/729 727/728/729 732/725/729 +f 727/728/734 730/723/734 732/725/734 +o Cup_hull_30 +v 0.017529 0.018321 0.034429 +v 0.008314 0.022795 0.050166 +v 0.008314 0.023587 0.050166 +v 0.021217 0.013580 0.050166 +v 0.018582 0.013580 0.034429 +v 0.008314 0.021480 0.034429 +v 0.015686 0.019899 0.050166 +v 0.009894 0.023322 0.034429 +v 0.019899 0.013580 0.050166 +v 0.021217 0.013844 0.034429 +v 0.019899 0.015687 0.050166 +v 0.012527 0.022006 0.050166 +v 0.013843 0.021216 0.034429 +v 0.008314 0.023587 0.034429 +v 0.008314 0.021480 0.035553 +v 0.009105 0.023587 0.050166 +v 0.008314 0.022533 0.048477 +v 0.017793 0.018057 0.050166 +v 0.019899 0.015687 0.034429 +v 0.018582 0.013580 0.035553 +v 0.021217 0.013580 0.034429 +v 0.015686 0.019899 0.034429 +v 0.021217 0.013844 0.050166 +v 0.018319 0.017530 0.034429 +v 0.012527 0.022006 0.034429 +v 0.014633 0.020688 0.050166 +v 0.010421 0.023059 0.050166 +v 0.009105 0.023587 0.034429 +v 0.018319 0.017530 0.050166 +v 0.020689 0.014634 0.050166 +vt 0.000000 0.897905 +vt 0.000000 1.000000 +vt 0.000000 0.959084 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 1.000000 0.000000 +vt 1.000000 0.714174 +vt 1.000000 0.795810 +vt 0.000000 0.571359 +vt 1.000000 0.122455 +vt 0.000000 0.897905 +vt 1.000000 1.000000 +vt 0.000000 0.326547 +vt 1.000000 0.428543 +vt 1.000000 0.000000 +vt 0.928543 0.000000 +vt 0.000000 0.061276 +vt 0.107283 0.000000 +vt 0.000000 0.734632 +vt 1.000000 0.897905 +vt 0.928543 0.795810 +vt 1.000000 1.000000 +vt 1.000000 0.571359 +vt 1.000000 0.775450 +vt 1.000000 0.326547 +vt 0.000000 0.489722 +vt 0.000000 0.163273 +vt 1.000000 0.061276 +vt 0.000000 0.775450 +vn 0.0001 0.0000 1.0000 +vn 0.0000 0.0000 1.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.6098 -0.7926 0.0000 +vn 0.0000 1.0000 0.0000 +vn -0.6179 -0.7769 0.1208 +vn -0.6160 -0.7851 0.0640 +vn 0.6581 0.7529 0.0016 +vn -0.6089 -0.7914 0.0549 +vn 1.0000 0.0000 0.0000 +vn 0.6504 0.7596 0.0000 +vn 0.7070 0.7072 -0.0000 +vn 0.7593 0.6508 0.0000 +vn 0.4472 0.8945 0.0000 +vn 0.5144 0.8575 0.0000 +vn 0.5305 0.8477 0.0018 +vn 0.5997 0.8002 0.0000 +vn 0.5816 0.8135 -0.0019 +vn 0.4471 0.8945 0.0000 +vn 0.3723 0.9281 0.0031 +vn 0.3177 0.9482 0.0000 +vn 0.7073 0.7069 0.0000 +vn 0.8001 0.5998 0.0000 +vn 0.8136 0.5814 -0.0019 +vn 0.8316 0.5554 0.0000 +usemtl None +s off +f 743/733/735 755/734/735 762/735/735 +f 735/736/736 734/737/736 736/738/736 +f 734/737/737 735/736/737 738/739/737 +f 733/740/738 737/741/738 738/739/738 +f 735/736/736 736/738/736 739/742/736 +f 733/740/738 738/739/738 740/743/738 +f 736/738/736 734/737/736 741/744/736 +f 737/741/739 736/738/739 741/744/739 +f 737/741/738 733/740/738 742/745/738 +f 739/742/736 736/738/736 743/733/736 +f 735/736/736 739/742/736 744/746/736 +f 733/740/738 740/743/738 745/747/738 +f 738/739/737 735/736/737 746/748/737 +f 740/743/738 738/739/738 746/748/738 +f 734/737/737 738/739/737 747/749/737 +f 738/739/740 737/741/740 747/749/740 +f 735/736/736 744/746/736 748/750/736 +f 746/748/741 735/736/741 748/750/741 +f 741/744/742 734/737/742 749/751/742 +f 734/737/737 747/749/737 749/751/737 +f 747/749/743 741/744/743 749/751/743 +f 733/740/744 739/742/744 750/752/744 +f 739/742/736 743/733/736 750/752/736 +f 742/745/738 733/740/738 751/753/738 +f 737/741/739 741/744/739 752/754/739 +f 747/749/740 737/741/740 752/754/740 +f 741/744/745 747/749/745 752/754/745 +f 736/738/739 737/741/739 753/755/739 +f 742/745/746 736/738/746 753/755/746 +f 737/741/738 742/745/738 753/755/738 +f 739/742/747 733/740/747 754/756/747 +f 733/740/738 745/747/738 754/756/738 +f 736/738/746 742/745/746 755/734/746 +f 743/733/736 736/738/736 755/734/736 +f 733/740/748 750/752/748 756/757/748 +f 743/733/749 751/753/749 756/757/749 +f 751/753/738 733/740/738 756/757/738 +f 740/743/750 744/746/750 757/758/750 +f 745/747/738 740/743/738 757/758/738 +f 744/746/751 745/747/751 757/758/751 +f 744/746/736 739/742/736 758/759/736 +f 745/747/752 744/746/752 758/759/752 +f 739/742/753 754/756/753 758/759/753 +f 754/756/754 745/747/754 758/759/754 +f 744/746/755 740/743/755 759/760/755 +f 748/750/736 744/746/736 759/760/736 +f 740/743/756 748/750/756 759/760/756 +f 740/743/738 746/748/738 760/761/738 +f 748/750/757 740/743/757 760/761/757 +f 746/748/741 748/750/741 760/761/741 +f 750/752/736 743/733/736 761/762/736 +f 756/757/758 750/752/758 761/762/758 +f 743/733/749 756/757/749 761/762/749 +f 751/753/759 743/733/759 762/735/759 +f 742/745/760 751/753/760 762/735/760 +f 755/734/761 742/745/761 762/735/761 +o Cup_hull_31 +v 0.019899 0.015687 0.015038 +v 0.008313 0.021479 0.034427 +v 0.008313 0.023586 0.034427 +v 0.021215 0.013581 0.034427 +v 0.008577 0.015687 0.015038 +v 0.008313 0.023586 0.017568 +v 0.014633 0.020689 0.034427 +v 0.012262 0.013581 0.017568 +v 0.014896 0.020425 0.015038 +v 0.020425 0.013581 0.015038 +v 0.018319 0.013581 0.034143 +v 0.018319 0.017531 0.034427 +v 0.010421 0.023059 0.018129 +v 0.008313 0.020425 0.015038 +v 0.008313 0.016214 0.017006 +v 0.009894 0.023322 0.034427 +v 0.011737 0.013581 0.015038 +v 0.017793 0.018057 0.015038 +v 0.021215 0.013844 0.018410 +v 0.020689 0.014634 0.034427 +v 0.012526 0.022005 0.018129 +v 0.008313 0.021215 0.033862 +v 0.015685 0.019899 0.034427 +v 0.012526 0.022005 0.034427 +v 0.009104 0.023586 0.018129 +v 0.015686 0.019899 0.015038 +v 0.018583 0.013581 0.034427 +v 0.013844 0.021215 0.018410 +v 0.017529 0.018320 0.034427 +v 0.008841 0.022795 0.016725 +v 0.019899 0.015687 0.034427 +v 0.009104 0.023586 0.034427 +v 0.021215 0.013581 0.018410 +v 0.018319 0.017531 0.015038 +v 0.020425 0.014897 0.015038 +v 0.008313 0.015951 0.015038 +v 0.021215 0.013844 0.034427 +vt 0.826057 1.000000 +vt 0.000000 0.959275 +vt 0.000000 1.000000 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 0.000000 1.000000 +vt 0.869518 0.000000 +vt 0.000000 0.489868 +vt 1.000000 0.897993 +vt 1.000000 0.020460 +vt 1.000000 0.510230 +vt 1.000000 0.938815 +vt 0.869518 0.306118 +vt 0.014683 0.775526 +vt 0.000000 0.775526 +vt 1.000000 0.000000 +vt 0.898493 0.000000 +vt 0.000000 0.122565 +vt 1.000000 0.265394 +vt 1.000000 0.734802 +vt 0.840544 0.163387 +vt 0.840544 0.326579 +vt 0.029170 0.000000 +vt 0.000000 0.571415 +vt 0.000000 0.326579 +vt 0.840544 0.061282 +vt 1.000000 0.571512 +vt 0.000000 0.795986 +vt 0.826057 0.428683 +vt 0.000000 0.714342 +vt 0.912980 0.040920 +vt 0.000000 0.897993 +vt 0.000000 0.061282 +vt 0.826057 1.000000 +vt 1.000000 0.775526 +vt 1.000000 0.938815 +vt 1.000000 0.000000 +vn 0.8325 0.5541 0.0000 +vn 0.0000 0.0000 1.0000 +vn -1.0000 0.0000 0.0000 +vn 0.0000 0.0000 -1.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.5631 -0.8140 0.1424 +vn -0.5630 -0.8004 0.2057 +vn -0.5511 -0.8266 0.1144 +vn 0.8154 0.5789 -0.0018 +vn 0.4447 0.8885 -0.1132 +vn -0.5754 -0.7414 0.3454 +vn -0.5946 -0.7708 0.2287 +vn 0.4476 0.8943 0.0000 +vn 0.4476 0.8942 0.0000 +vn 0.0000 1.0000 0.0000 +vn 0.2744 0.8807 -0.3862 +vn 0.3600 0.9000 -0.2456 +vn 0.3714 0.9285 -0.0030 +vn 0.6002 0.7999 0.0000 +vn -0.5307 -0.6901 0.4921 +vn 0.5196 0.8536 -0.0379 +vn 0.5299 0.8481 0.0018 +vn 0.5140 0.8578 0.0000 +vn 0.5792 0.8152 -0.0017 +vn 0.5537 0.8324 -0.0223 +vn 0.7071 0.7071 0.0000 +vn 0.6583 0.7528 -0.0013 +vn 0.6504 0.7596 0.0000 +vn 0.1198 0.7605 -0.6382 +vn -0.2966 0.5968 -0.7456 +vn 0.0000 0.5799 -0.8147 +vn 0.7592 0.6508 0.0000 +vn 0.7999 0.6001 0.0000 +vn 0.0001 0.0000 1.0000 +vn 0.3161 0.9487 0.0000 +vn 0.9737 0.0000 -0.2279 +vn 1.0000 0.0000 0.0000 +vn 0.7075 0.7067 0.0000 +vn 0.8320 0.5544 -0.0217 +vn -0.7033 -0.7046 0.0943 +usemtl None +s off +f 781/763/762 782/764/762 799/765/762 +f 765/766/763 764/767/763 766/768/763 +f 764/767/764 765/766/764 768/769/764 +f 765/766/763 766/768/763 769/770/763 +f 763/771/765 767/772/765 771/773/765 +f 767/772/765 763/771/765 772/774/765 +f 766/768/766 770/775/766 772/774/766 +f 770/775/766 766/768/766 773/776/766 +f 769/770/763 766/768/763 774/777/763 +f 764/767/764 768/769/764 776/778/764 +f 771/773/765 767/772/765 776/778/765 +f 767/772/767 770/775/767 777/779/767 +f 770/775/768 773/776/768 777/779/768 +f 764/767/764 776/778/764 777/779/764 +f 765/766/763 769/770/763 778/780/763 +f 770/775/769 767/772/769 779/781/769 +f 767/772/765 772/774/765 779/781/765 +f 772/774/766 770/775/766 779/781/766 +f 763/771/765 771/773/765 780/782/765 +f 774/777/763 766/768/763 782/764/763 +f 781/763/770 763/771/770 782/764/770 +f 771/773/771 775/783/771 783/784/771 +f 773/776/772 764/767/772 784/785/772 +f 764/767/764 777/779/764 784/785/764 +f 777/779/773 773/776/773 784/785/773 +f 769/770/763 774/777/763 785/786/763 +f 778/780/763 769/770/763 786/787/763 +f 775/783/774 778/780/774 786/787/774 +f 783/784/775 775/783/775 786/787/775 +f 768/769/776 765/766/776 787/788/776 +f 771/773/777 768/769/777 787/788/777 +f 775/783/778 771/773/778 787/788/778 +f 778/780/779 775/783/779 787/788/779 +f 780/782/765 771/773/765 788/789/765 +f 769/770/780 785/786/780 788/789/780 +f 766/768/763 764/767/763 789/790/763 +f 764/767/781 773/776/781 789/790/781 +f 773/776/766 766/768/766 789/790/766 +f 771/773/782 783/784/782 790/791/782 +f 786/787/783 769/770/783 790/791/783 +f 783/784/784 786/787/784 790/791/784 +f 769/770/785 788/789/785 790/791/785 +f 788/789/786 771/773/786 790/791/786 +f 774/777/787 780/782/787 791/792/787 +f 785/786/763 774/777/763 791/792/763 +f 780/782/788 788/789/788 791/792/788 +f 788/789/789 785/786/789 791/792/789 +f 768/769/790 771/773/790 792/793/790 +f 776/778/791 768/769/791 792/793/791 +f 771/773/792 776/778/792 792/793/792 +f 763/771/793 774/777/793 793/794/793 +f 782/764/794 763/771/794 793/794/794 +f 774/777/795 782/764/795 793/794/795 +f 765/766/763 778/780/763 794/795/763 +f 787/788/776 765/766/776 794/795/776 +f 778/780/796 787/788/796 794/795/796 +f 766/768/766 772/774/766 795/796/766 +f 772/774/797 781/763/797 795/796/797 +f 781/763/798 766/768/798 795/796/798 +f 774/777/793 763/771/793 796/797/793 +f 763/771/765 780/782/765 796/797/765 +f 780/782/799 774/777/799 796/797/799 +f 772/774/765 763/771/765 797/798/765 +f 763/771/800 781/763/800 797/798/800 +f 781/763/797 772/774/797 797/798/797 +f 776/778/765 767/772/765 798/799/765 +f 767/772/801 777/779/801 798/799/801 +f 777/779/764 776/778/764 798/799/764 +f 766/768/798 781/763/798 799/765/798 +f 782/764/763 766/768/763 799/765/763 +o Cup_hull_32 +v 0.004626 -0.019601 -0.043977 +v -0.002221 -0.020391 0.015036 +v 0.001203 -0.020392 -0.005762 +v 0.004626 -0.017495 0.015036 +v -0.002221 -0.017758 -0.048198 +v -0.002221 -0.020391 -0.048198 +v -0.002221 -0.017758 0.014751 +v 0.004626 -0.020392 0.015036 +v 0.004625 -0.017495 -0.048198 +v 0.004625 -0.020392 -0.048198 +v 0.003308 -0.017495 0.013624 +v 0.003308 -0.017495 -0.048198 +v -0.002221 -0.018022 0.015036 +vt 0.000000 1.000000 +vt 0.004503 0.000000 +vt 0.000000 0.000000 +vt 0.000000 0.000000 +vt 1.000000 0.000000 +vt 1.000000 0.000000 +vt 0.328896 0.500000 +vt 0.000000 1.000000 +vt 0.933242 1.000000 +vt 1.000000 0.999902 +vt 1.000000 0.999902 +vt 0.022318 0.807557 +vt 1.000000 0.807557 +vn -0.0564 0.7329 0.6780 +vn -1.0000 0.0000 0.0000 +vn -0.0001 -1.0000 0.0000 +vn -0.0000 -1.0000 0.0000 +vn -0.0000 0.0000 1.0000 +vn 1.0000 0.0000 0.0000 +vn 1.0000 0.0003 -0.0000 +vn 0.0000 0.0000 -1.0000 +vn 1.0000 -0.0008 -0.0000 +vn 1.0000 0.0000 -0.0002 +vn -0.0399 0.9985 0.0373 +vn -0.0475 0.9989 0.0000 +vn 0.0000 1.0000 0.0000 +usemtl None +s off +f 803/800/802 806/801/802 812/802/802 +f 801/803/803 804/804/803 805/805/803 +f 802/806/804 801/803/804 805/805/804 +f 804/804/803 801/803/803 806/801/803 +f 801/803/805 802/806/805 807/807/805 +f 803/800/806 801/803/806 807/807/806 +f 800/808/807 803/800/807 807/807/807 +f 803/800/808 800/808/808 808/809/808 +f 805/805/809 804/804/809 808/809/809 +f 802/806/805 805/805/805 809/810/805 +f 807/807/805 802/806/805 809/810/805 +f 800/808/810 807/807/810 809/810/810 +f 808/809/811 800/808/811 809/810/811 +f 805/805/809 808/809/809 809/810/809 +f 806/801/812 803/800/812 810/811/812 +f 804/804/813 806/801/813 810/811/813 +f 803/800/814 808/809/814 810/811/814 +f 810/811/814 808/809/814 811/812/814 +f 808/809/809 804/804/809 811/812/809 +f 804/804/813 810/811/813 811/812/813 +f 801/803/806 803/800/806 812/802/806 +f 806/801/803 801/803/803 812/802/803 +o Cup_hull_33 +v 0.011736 -0.013546 -0.048198 +v 0.004626 -0.020391 0.015036 +v 0.007524 -0.020392 0.007726 +v 0.012262 -0.013282 0.015036 +v 0.012263 -0.020392 -0.048192 +v 0.004626 -0.017231 -0.048198 +v 0.012262 -0.020392 0.015036 +v 0.004626 -0.020391 -0.048198 +v 0.004626 -0.017231 0.014751 +v 0.011999 -0.013282 -0.048192 +v 0.012263 -0.013282 -0.048192 +v 0.011473 -0.013546 0.008289 +v 0.011999 -0.013282 0.015036 +v 0.011473 -0.013546 -0.043420 +v 0.004890 -0.017231 0.015036 +vt 0.000000 0.965446 +vt 0.004503 0.000000 +vt 0.000000 0.034554 +vt 0.000000 0.000000 +vt 0.115603 0.379405 +vt 0.000000 0.999902 +vt 0.000000 0.999902 +vt 0.999902 1.000000 +vt 1.000000 0.000000 +vt 1.000000 0.930991 +vt 1.000000 0.000000 +vt 0.999902 0.965446 +vt 0.999902 1.000000 +vt 0.106695 0.896535 +vt 0.924432 0.896535 +vn -0.4428 0.7971 0.4104 +vn -0.0001 -1.0000 0.0001 +vn 0.0000 0.0000 1.0000 +vn 1.0000 0.0000 0.0000 +vn 0.0000 -1.0000 0.0000 +vn -0.0002 -1.0000 0.0000 +vn 0.0008 -0.0008 -1.0000 +vn -0.0001 -1.0000 -0.0000 +vn -1.0000 0.0000 0.0000 +vn -0.0000 0.0000 -1.0000 +vn -0.0252 0.0485 -0.9985 +vn 0.0000 1.0000 -0.0000 +vn 0.0118 0.0000 -0.9999 +vn 0.0000 0.0235 -0.9997 +vn -0.4740 0.8805 0.0000 +vn -0.4481 0.8940 0.0000 +vn -0.4722 0.8815 0.0024 +vn -0.4722 0.8815 -0.0034 +vn -0.7321 0.0611 0.6785 +usemtl None +s off +f 825/813/815 821/814/815 827/815/815 +f 814/816/816 815/817/816 819/818/816 +f 816/819/817 814/816/817 819/818/817 +f 817/820/818 816/819/818 819/818/818 +f 815/817/819 817/820/819 819/818/819 +f 815/817/820 814/816/820 820/821/820 +f 813/822/821 817/820/821 820/821/821 +f 817/820/822 815/817/822 820/821/822 +f 814/816/823 818/823/823 820/821/823 +f 818/823/824 813/822/824 820/821/824 +f 818/823/823 814/816/823 821/814/823 +f 813/822/825 818/823/825 822/824/825 +f 822/824/826 816/819/826 823/825/826 +f 817/820/827 813/822/827 823/825/827 +f 816/819/818 817/820/818 823/825/818 +f 813/822/828 822/824/828 823/825/828 +f 818/823/829 821/814/829 824/826/829 +f 822/824/830 824/826/830 825/813/830 +f 814/816/817 816/819/817 825/813/817 +f 816/819/826 822/824/826 825/813/826 +f 824/826/831 821/814/831 825/813/831 +f 822/824/832 818/823/832 826/827/832 +f 818/823/829 824/826/829 826/827/829 +f 824/826/830 822/824/830 826/827/830 +f 821/814/833 814/816/833 827/815/833 +f 814/816/817 825/813/817 827/815/817 diff --git a/cram_demos/cram_projection_demos/resource/household/fork.dae b/cram_demos/cram_projection_demos/resource/household/fork.dae new file mode 100644 index 0000000000..0cae89d1f4 --- /dev/null +++ b/cram_demos/cram_projection_demos/resource/household/fork.dae @@ -0,0 +1,109 @@ + + + + + Blender User + Blender 2.79.0 commit date:2017-09-11, commit time:10:43, hash:5bd8ac9abfa + + 2019-02-04T17:22:21 + 2019-02-04T17:22:21 + + Z_UP + + + + + + + + + 0 0 0 1 + + + 0 0 0 1 + + + 0.04899684 0.0305635 0.6392822 1 + + + 0.03125 0.03125 0.03125 1 + + + 50 + + + 1 + + + + + + + + + + + + + + + + 0.04345971 0.001182913 -0.005117952 0.04330712 0.004132747 -0.005115211 0.04346036 0.004129707 -0.005117952 0.04330646 0.001179993 -0.005115211 0.04300516 0.001134932 -0.005109667 0.04300588 0.004177808 -0.005109667 0.0427255 0.001014292 -0.005104541 0.04272621 0.004298508 -0.005104541 0.04264062 0.004365742 -0.005102992 0.04263991 9.47182e-4 -0.005102992 0.04181909 -0.009449481 -0.005054175 0.0426383 -0.006263852 -0.005102992 0.04263758 -0.00944966 -0.005102992 0.04248428 -0.006142914 -0.005093693 0.04230087 -0.005899727 -0.005082845 0.04218578 -0.005617797 -0.005075931 0.04214662 -0.005315721 -0.005073606 0.04214781 -7.92958e-7 -0.005073606 0.042149 0.005313932 -0.005073606 0.04264104 0.006262004 -0.005102992 0.04182326 0.009447991 -0.005054175 0.04264175 0.009447813 -0.005102992 0.04248702 0.006141126 -0.005093693 0.0423035 0.005898118 -0.005082845 0.04218828 0.005616009 -0.005075931 0.04248583 8.26274e-4 -0.005093693 0.04248666 0.004486799 -0.005093693 0.04230326 0.004729986 -0.005082845 0.04230231 5.83171e-4 -0.005082845 0.04218709 3.01226e-4 -0.005075931 0.04218816 0.005011975 -0.005075931 0.04263871 -0.004367589 -0.005102992 0.04248547 -8.2805e-4 -0.005093693 0.04263949 -9.4903e-4 -0.005102992 0.04248464 -0.004488527 -0.005093693 0.04230111 -0.004731655 -0.005082845 0.04230207 -5.84867e-4 -0.005082845 0.0421859 -0.005013585 -0.005075931 0.04218697 -3.02874e-4 -0.005075931 0.04272621 0.004298508 -0.003528177 0.04264074 0.004365682 -0.003526508 0.04248666 0.004486799 -0.003517031 0.04300588 0.004177808 -0.003533899 0.04330712 0.004132747 -0.003540098 0.04616165 0.00407648 -0.005112051 0.04886102 0.004023432 -0.005007147 0.05155473 0.003970384 -0.004803657 0.05423921 0.003917574 -0.004501819 0.05691081 0.003865122 -0.00410223 0.04346036 0.004129707 -0.003543257 0.05956602 0.003812909 -0.003604888 0.04614973 0.004076719 -0.003500282 0.06220138 0.003761053 -0.003011047 0.04883641 0.004023909 -0.003371715 0.0515176 0.003971159 -0.003157436 0.05419057 0.003918528 -0.002857863 0.06481313 0.003709793 -0.002321064 0.05685263 0.003866255 -0.002473115 0.05950105 0.003814101 -0.002003669 0.06739795 0.00365889 -0.00153613 0.06213319 0.003762423 -0.001449942 0.06995236 0.003608584 -6.57183e-4 0.06474637 0.003711044 -8.12665e-4 0.06733787 0.003660082 -9.23284e-5 0.07247287 0.003558993 3.14593e-4 0.0699051 0.003609538 7.10249e-4 0.07495611 0.003510177 0.00137788 0.07244539 0.003559589 0.001594305 0.07873994 0.00343579 0.003080546 0.07495611 0.003510177 0.002558946 0.07873994 0.00343579 0.003883242 0.04616105 0.001234829 -0.005112051 0.05956554 0.0014925 -0.003604888 0.04614913 0.001234591 -0.003500282 0.04345971 0.001182913 -0.003543257 0.0622009 0.001543164 -0.003011047 0.04883581 0.001286268 -0.003371715 0.051517 0.001337766 -0.003157436 0.05418998 0.001389145 -0.002857863 0.06481266 0.00159341 -0.002321064 0.05685204 0.001440346 -0.002473115 0.05950057 0.001491248 -0.002003669 0.06739747 0.001643061 -0.00153613 0.06213271 0.001541852 -0.001449942 0.06995189 0.001692175 -6.57183e-4 0.0647459 0.001592099 -8.12665e-4 0.06733739 0.001641869 -9.23284e-5 0.07247251 0.001740574 3.14593e-4 0.06990468 0.001691281 7.10249e-4 0.07495576 0.001788377 0.00137788 0.07244497 0.001740038 0.001594305 0.07873958 0.001861095 0.003080546 0.07495576 0.001788377 0.002558946 0.07873958 0.001861095 0.003883242 0.04330646 0.001179993 -0.003540098 0.04886043 0.001286745 -0.005007147 0.05155414 0.001338481 -0.004803657 0.05423861 0.001390099 -0.004501819 0.05691027 0.001441478 -0.00410223 0.04300516 0.001134932 -0.003533899 0.0427255 0.001014292 -0.003528177 0.04264003 9.47328e-4 -0.003526508 0.04248583 8.26274e-4 -0.003517031 0.0434609 0.00649774 -0.005117952 0.04330825 0.009447693 -0.005115211 0.04346156 0.009444653 -0.005117952 0.0433076 0.006494879 -0.005115211 0.04300636 0.006449818 -0.005109667 0.04272669 0.006329178 -0.005104541 0.04272669 0.006329178 -0.003528177 0.04264116 0.006262123 -0.003526508 0.04248702 0.006141126 -0.003517031 0.0423035 0.005898118 -0.003505825 0.04218828 0.005616009 -0.003498733 0.042149 0.005313932 -0.003496229 0.04218816 0.005011975 -0.003498733 0.04230326 0.004729986 -0.003505825 0.04230231 5.83171e-4 -0.003505825 0.04218709 3.01226e-4 -0.003498733 0.04214781 -7.92958e-7 -0.003496229 0.04218697 -3.02874e-4 -0.003498733 0.04230207 -5.84869e-4 -0.003505825 0.04248547 -8.2805e-4 -0.003517031 0.04272502 -0.001016199 -0.003528177 0.04272502 -0.001016199 -0.005104541 0.04263961 -9.49172e-4 -0.003526508 0.04330527 -0.004134833 -0.005115211 0.04345923 -0.001185119 -0.005117952 0.04345858 -0.004131913 -0.005117952 0.04330593 -0.001182079 -0.005115211 0.04300469 -0.001136898 -0.005109667 0.04300403 -0.004179894 -0.005109667 0.04272431 -0.004300534 -0.005104541 0.04272431 -0.004300534 -0.003528177 0.04263883 -0.00436753 -0.003526508 0.04248464 -0.004488527 -0.003517031 0.04230111 -0.004731655 -0.003505825 0.0421859 -0.005013585 -0.003498733 0.04214662 -0.005315721 -0.003496229 0.04218578 -0.005617797 -0.003498733 0.04230087 -0.005899727 -0.003505825 0.04248428 -0.006142914 -0.003517031 0.04272383 -0.006331086 -0.003528177 0.04272383 -0.006331086 -0.005104541 0.04263842 -0.006263971 -0.003526508 0.04330408 -0.009449779 -0.005115211 0.04345804 -0.006500124 -0.005117952 0.04345738 -0.009446859 -0.005117952 0.04330474 -0.006497025 -0.005115211 0.04300349 -0.006451785 -0.005109667 0.04330408 -0.009449779 -0.003540098 0.04100334 -0.009449303 -0.004971683 0.04019176 -0.009449124 -0.004855513 0.03938555 -0.009448945 -0.004706263 0.03858613 -0.009448766 -0.004523813 0.03779506 -0.009448587 -0.00430864 0.03701341 -0.009448409 -0.004060983 0.03624254 -0.00944823 -0.003781437 0.03548407 -0.009448051 -0.003470301 0.0426377 -0.00944966 -0.003526508 0.04181957 -0.009449481 -0.003476321 0.04100406 -0.009449303 -0.003392815 0.03473883 -0.009447872 -0.003128349 0.0401926 -0.009449124 -0.003276109 0.03938674 -0.009448945 -0.003126263 0.0340085 -0.009447693 -0.00275582 0.03858757 -0.009448766 -0.002943694 0.03779649 -0.009448587 -0.0027287 0.03385514 -0.009447693 -0.002679228 0.03701478 -0.009448409 -0.002481579 0.03624403 -0.00944823 -0.002202808 0.03548508 -0.009448051 -0.001892745 0.03473955 -0.009447872 -0.001551985 0.03385514 -0.009447693 -0.001104414 0.0340085 -0.009447693 -0.001181066 0.04100751 0.00944817 -0.004971683 0.04330825 0.009447693 -0.003540098 0.04019594 0.009448349 -0.004855513 0.03938972 0.009448528 -0.004706263 0.03859031 0.009448707 -0.004523813 0.03779923 0.009448885 -0.00430864 0.03701758 0.009449064 -0.004060983 0.03624671 0.009449243 -0.003781437 0.03548824 0.009449422 -0.003470301 0.04264187 0.009447813 -0.003526508 0.04182374 0.009447991 -0.003476321 0.04100823 0.00944817 -0.003392815 0.03474301 0.009449601 -0.003128349 0.04019677 0.009448349 -0.003276109 0.03939092 0.009448528 -0.003126263 0.03401267 0.009449779 -0.00275582 0.03859174 0.009448707 -0.002943694 0.03780066 0.009448885 -0.0027287 0.03385931 0.009449779 -0.002679228 0.03701895 0.009449064 -0.002481579 0.0362482 0.009449243 -0.002202808 0.03548926 0.009449422 -0.001892745 0.03474372 0.009449601 -0.001551985 0.03385931 0.009449779 -0.001104414 0.03401267 0.009449779 -0.001181066 0.0788933 0.003405153 0.003936886 0.07889294 0.001891672 0.003936886 0.0788933 0.003405153 0.003149449 0.08267664 0.002647519 0.005117952 0.07889294 0.001891672 0.003149449 0.04616224 0.006549775 -0.005112051 0.04616284 0.009391486 -0.005112051 0.05956667 0.006807327 -0.003604888 0.04615026 0.006549477 -0.003500282 0.0434609 0.00649774 -0.003543257 0.06220209 0.006857991 -0.003011047 0.048837 0.006601095 -0.003371715 0.0515182 0.006652593 -0.003157436 0.05419117 0.006703972 -0.002857863 0.06481385 0.006908237 -0.002321064 0.05685323 0.006755232 -0.002473115 0.05950176 0.006806135 -0.002003669 0.06739866 0.006957948 -0.00153613 0.0621339 0.006856799 -0.001449942 0.06995308 0.007007062 -6.57183e-4 0.06474709 0.006906926 -8.12665e-4 0.06733858 0.006956756 -9.23284e-5 0.07247364 0.00705558 3.14593e-4 0.06990581 0.007006168 7.10249e-4 0.07495695 0.007103323 0.00137788 0.07244616 0.007054984 0.001594305 0.07874077 0.007176041 0.003080546 0.07495695 0.007103323 0.002558946 0.07874077 0.007176041 0.003883242 0.0433076 0.006494879 -0.003540098 0.04886162 0.006601631 -0.005007147 0.05155533 0.006653487 -0.004803657 0.0542398 0.006704926 -0.004501819 0.0569114 0.006756365 -0.00410223 0.04300636 0.006449818 -0.003533899 0.04886221 0.009338438 -0.005007147 0.05155593 0.00928539 -0.004803657 0.0542404 0.009232699 -0.004501819 0.05691194 0.009180128 -0.00410223 0.04346156 0.009444653 -0.003543257 0.05956721 0.009127855 -0.003604888 0.04615092 0.009391665 -0.003500282 0.06220257 0.009075999 -0.003011047 0.0488376 0.009338855 -0.003371715 0.05151879 0.009286105 -0.003157436 0.05419176 0.009233534 -0.002857863 0.06481432 0.009024739 -0.002321064 0.05685377 0.009181201 -0.002473115 0.05950224 0.009129106 -0.002003669 0.06739914 0.008973836 -0.00153613 0.06213438 0.009077429 -0.001449942 0.0699535 0.008923709 -6.57183e-4 0.06474757 0.00902599 -8.12665e-4 0.06733906 0.008975028 -9.23284e-5 0.07247406 0.008873999 3.14593e-4 0.06990629 0.008924484 7.10249e-4 0.07495731 0.008825182 0.00137788 0.07244652 0.008874595 0.001594305 0.07874113 0.008750796 0.003080546 0.07495731 0.008825182 0.002558946 0.07874113 0.008750796 0.003883242 0.04345923 -0.001185119 -0.003543257 0.04330527 -0.004134833 -0.003540098 0.04345858 -0.004131913 -0.003543257 0.04330593 -0.001182079 -0.003540098 0.04300403 -0.004179894 -0.003533899 0.04300469 -0.001136898 -0.003533899 0.04616051 -0.001238286 -0.005112051 0.04885983 -0.001291334 -0.005007147 0.05155354 -0.001344323 -0.004803657 0.05423802 -0.001397132 -0.004501819 0.05690962 -0.001449644 -0.00410223 0.05956482 -0.001501917 -0.003604888 0.04614853 -0.001238048 -0.003500282 0.06220018 -0.001553714 -0.003011047 0.04883521 -0.001290857 -0.003371715 0.05151641 -0.001343607 -0.003157436 0.05418938 -0.001396179 -0.002857863 0.06481194 -0.001605033 -0.002321064 0.05685144 -0.001448512 -0.002473115 0.05949991 -0.001500606 -0.002003669 0.06739675 -0.001655876 -0.00153613 0.062132 -0.001552343 -0.001449942 0.06995117 -0.001706123 -6.57183e-4 0.06474518 -0.001603722 -8.12665e-4 0.06733667 -0.001654744 -9.23284e-5 0.07247173 -0.001755714 3.14593e-4 0.06990391 -0.001705169 7.10249e-4 0.07495492 -0.00180453 0.00137788 0.0724442 -0.001755177 0.001594305 0.07873874 -0.001878976 0.003080546 0.07495492 -0.00180453 0.002558946 0.07873874 -0.001878976 0.003883242 0.04615986 -0.004079878 -0.005112051 0.05956435 -0.003822267 -0.003604888 0.04614794 -0.004080116 -0.003500282 0.06219971 -0.003771603 -0.003011047 0.04883462 -0.004028499 -0.003371715 0.05151581 -0.003977 -0.003157436 0.05418878 -0.003925681 -0.002857863 0.06481146 -0.003721415 -0.002321064 0.05685091 -0.00387448 -0.002473115 0.05949938 -0.003823578 -0.002003669 0.06739634 -0.003671705 -0.00153613 0.06213152 -0.003772854 -0.001449942 0.06995075 -0.003622591 -6.57183e-4 0.06474471 -0.003722667 -8.12665e-4 0.0673362 -0.003672897 -9.23284e-5 0.07247132 -0.003574192 3.14593e-4 0.06990349 -0.003623425 7.10249e-4 0.07495456 -0.003526508 0.00137788 0.07244378 -0.003574669 0.001594305 0.07873839 -0.003453612 0.003080546 0.07495456 -0.003526508 0.002558946 0.07873839 -0.003453612 0.003883242 0.04885923 -0.004028022 -0.005007147 0.05155295 -0.003976345 -0.004803657 0.05423748 -0.003924727 -0.004501819 0.05690908 -0.003873288 -0.00410223 0.04330474 -0.006497025 -0.003540098 0.04345738 -0.009446859 -0.003543257 0.04345804 -0.006500124 -0.003543257 0.04300349 -0.006451785 -0.003533899 0.04615932 -0.006553173 -0.005112051 0.04615867 -0.009394884 -0.005112051 0.05956315 -0.009137213 -0.003604888 0.04614675 -0.009395062 -0.003500282 0.06219851 -0.009086549 -0.003011047 0.04883342 -0.009343445 -0.003371715 0.05151462 -0.009291946 -0.003157436 0.05418765 -0.009240627 -0.002857863 0.06481027 -0.009036362 -0.002321064 0.05684971 -0.009189486 -0.002473115 0.05949819 -0.009138584 -0.002003669 0.06739515 -0.008986651 -0.00153613 0.06213033 -0.00908786 -0.001449942 0.06994956 -0.008937656 -6.57183e-4 0.06474351 -0.009037613 -8.12665e-4 0.06733506 -0.008987843 -9.23284e-5 0.07247012 -0.008889198 3.14593e-4 0.0699023 -0.00893855 7.10249e-4 0.07495337 -0.008841454 0.00137788 0.07244259 -0.008889675 0.001594305 0.07873719 -0.008768737 0.003080546 0.07495337 -0.008841454 0.002558946 0.07873719 -0.008768737 0.003883242 0.04885804 -0.009343028 -0.005007147 0.05155175 -0.009291291 -0.004803657 0.05423629 -0.009239673 -0.004501819 0.05690789 -0.009188294 -0.00410223 0.04885864 -0.006606221 -0.005007147 0.05155235 -0.006659269 -0.004803657 0.05423682 -0.006712019 -0.004501819 0.05690842 -0.00676459 -0.00410223 0.05956369 -0.006816804 -0.003604888 0.0461474 -0.006552875 -0.003500282 0.06219899 -0.006868541 -0.003011047 0.04883402 -0.006605684 -0.003371715 0.05151522 -0.006658494 -0.003157436 0.05418819 -0.006711125 -0.002857863 0.06481075 -0.00691986 -0.002321064 0.05685025 -0.006763398 -0.002473115 0.05949872 -0.006815493 -0.002003669 0.06739556 -0.006970763 -0.00153613 0.06213086 -0.006867229 -0.001449942 0.06994998 -0.007021009 -6.57183e-4 0.06474399 -0.006918668 -8.12665e-4 0.06733548 -0.006969571 -9.23284e-5 0.07247054 -0.00707066 3.14593e-4 0.06990271 -0.007020056 7.10249e-4 0.07495379 -0.007119476 0.00137788 0.072443 -0.007070064 0.001594305 0.07873755 -0.007193863 0.003080546 0.07495379 -0.007119476 0.002558946 0.07873755 -0.007193863 0.003883242 0.03328692 0.009432733 -8.18209e-4 0.03328275 -0.009430408 -8.18209e-4 0.03271222 -0.009379029 -5.32985e-4 0.03271639 0.009381592 -5.32985e-4 0.03214585 -0.009293615 -2.49803e-4 0.03214997 0.009296357 -2.49803e-4 0.03158569 -0.009174346 3.02786e-5 0.03158974 0.009177505 3.02786e-5 0.03103756 0.009025394 3.06368e-4 0.03103357 -0.009021997 3.06368e-4 0.03086292 0.008965849 3.93689e-4 0.03085893 -0.008962452 3.93689e-4 0.03328275 -0.009430408 -0.002392947 0.03328692 0.009432733 -0.002392947 0.03271222 -0.009379029 -0.002107739 0.03271639 0.009381592 -0.002107739 0.03214585 -0.009293615 -0.001824557 0.03214997 0.009296357 -0.001824557 0.03158569 -0.009174346 -0.001544475 0.03158974 0.009177505 -0.001544475 0.03103357 -0.009021997 -0.001268386 0.03103756 0.009025394 -0.001268386 0.03085893 -0.008962452 -0.001181066 0.03086292 0.008965849 -0.001181066 0.07889413 0.007206559 0.003149449 0.08267784 0.007962465 0.005117952 0.07889413 0.007206559 0.003936886 0.07889449 0.008720099 0.003936886 0.07889449 0.008720099 0.003149449 0.07889211 -0.001909673 0.003936886 0.07889175 -0.003423094 0.003936886 0.07889211 -0.001909673 0.003149449 0.08267545 -0.002667129 0.005117952 0.07889175 -0.003423094 0.003149449 0.07889091 -0.0072245 0.003149449 0.07889062 -0.00873804 0.003149449 0.08267426 -0.007982075 0.005117952 0.07889062 -0.00873804 0.003936886 0.07889091 -0.0072245 0.003936886 0.03049546 0.00884056 5.69582e-4 0.03049153 -0.008836925 5.69582e-4 0.02996528 0.0086236 8.232e-4 0.02996146 -0.008619785 8.232e-4 0.02969181 0.008491992 9.54092e-4 0.02968806 -0.008488178 9.54092e-4 0.03049153 -0.008836925 -0.001005172 0.03049546 0.00884056 -0.001005172 0.02996146 -0.008619785 -7.51481e-4 0.02996528 0.0086236 -7.51481e-4 0.02968806 -0.008488178 -6.20547e-4 0.02969181 0.008491992 -6.20547e-4 0.02944922 0.008375346 0.001060187 0.02944552 -0.008371233 0.001060187 0.02894884 0.008096754 0.001278817 0.02894526 -0.008092522 0.001278817 0.0285021 0.007811665 0.001474082 0.02849864 -0.007807314 0.001474082 0.02944552 -0.008371233 -5.14513e-4 0.02944922 0.008375346 -5.14513e-4 0.02894526 -0.008092522 -2.95815e-4 0.02894884 0.008096754 -2.95815e-4 0.0285021 0.007811665 -1.00613e-4 0.02849864 -0.007807314 -1.00613e-4 0.02846598 0.007788717 0.001488387 0.02846252 -0.007784247 0.001488387 0.02800244 0.007452368 0.001672327 0.0279991 -0.007447659 0.001672327 0.02755975 0.007088899 0.001847922 0.02755659 -0.007083952 0.001847922 0.02729207 -0.006872296 0.001952886 0.02729517 0.006877362 0.001952886 0.02846252 -0.007784247 -8.62484e-5 0.02846598 0.007788717 -8.62484e-5 0.0279991 -0.007447659 9.76316e-5 0.02800244 0.007452368 9.76316e-5 0.02755659 -0.007083952 2.73228e-4 0.02755975 0.007088899 2.73228e-4 0.02729517 0.006877362 3.78132e-4 0.02729207 -0.006872296 3.78132e-4 0.02607238 0.005899488 8.15094e-4 0.02483552 0.004910349 0.001209795 0.02362221 0.003940105 0.001551508 0.02362221 0.003940105 0.003126204 0.02607238 0.005899488 0.002389848 0.02483552 0.004910349 0.00278449 0.02606976 -0.005894064 0.002389848 0.02606976 -0.005894064 8.15094e-4 0.02483332 -0.00490421 0.001209795 0.02362048 -0.003933608 0.001551508 0.02362048 -0.003933608 0.003126204 0.02483332 -0.00490421 0.00278449 0.02358561 0.003913164 0.00156176 0.0230624 0.003527998 0.001689672 0.0230624 0.003527998 0.003264605 0.02358561 0.003913164 0.003136456 0.02358388 -0.003906548 0.003136456 0.02358388 -0.003906548 0.00156176 0.02306085 -0.003521144 0.001689672 0.02306085 -0.003521144 0.003264605 0.02247178 0.003161668 0.001834392 0.02247178 0.003161668 0.003409266 0.02247035 -0.003154516 0.003409266 0.02232432 0.003085732 0.003445386 0.02232295 -0.00307852 0.003445386 0.02247035 -0.003154516 0.001834392 0.02232432 0.003085732 0.001870512 0.02232295 -0.00307852 0.001870512 0.02185386 0.002843379 0.001968681 0.02185386 0.002843379 0.003543436 0.02185261 -0.002835988 0.003543436 0.02121251 0.002575218 0.003677308 0.02121138 -0.002567529 0.003677308 0.02105212 -0.002515256 0.003710567 0.02105325 0.002523064 0.003710567 0.02185261 -0.002835988 0.001968681 0.02121138 -0.002567529 0.002102434 0.02121251 0.002575218 0.002102434 0.02105212 -0.002515256 0.002135694 0.02105325 0.002523064 0.002135694 0.02055197 0.002358913 0.003797292 0.0205509 -0.002350866 0.003797292 0.0198763 0.002195715 0.003914237 0.01987534 -0.00218743 0.003914237 0.01977396 0.002179443 0.003931939 0.019773 -0.002171039 0.003931939 0.0205509 -0.002350866 0.002222418 0.02055197 0.002358913 0.002222418 0.0198763 0.002195715 0.002339422 0.01987534 -0.00218743 0.002339422 0.01977396 0.002179443 0.002357065 0.019773 -0.002171039 0.002357065 0.01918882 -0.002078235 0.004012405 0.01918977 0.002086699 0.004012405 0.01848685 -0.002023875 0.004109203 0.01848775 0.002032756 0.004109203 0.01918882 -0.002078235 0.00243771 0.01918977 0.002086699 0.00243771 0.01848685 -0.002023875 0.002534329 0.01848775 0.002032756 0.002534329 0.01780176 0.002033829 0.004179775 0.01780086 -0.00202471 0.004179775 0.01719629 0.002083182 0.004242062 0.01719534 -0.002073705 0.004242062 0.01780086 -0.00202471 0.00260508 0.01780176 0.002033829 0.00260508 0.01719629 0.002083182 0.002667427 0.01719534 -0.002073705 0.002667427 0.01710802 -0.002080798 0.004248082 0.01710897 0.002090334 0.004248082 0.01642185 -0.002191781 0.004294931 0.01642286 0.002201616 0.004294931 0.01590007 -0.002319455 0.004330635 0.01590108 0.002329528 0.004330635 0.01710802 -0.002080798 0.002673327 0.01710897 0.002090334 0.002673327 0.01642185 -0.002191781 0.002720236 0.01642286 0.002201616 0.002720236 0.01590007 -0.002319455 0.00275582 0.01590108 0.002329528 0.00275582 0.01574677 -0.002357006 0.004337131 0.01574778 0.002367198 0.004337131 0.01524245 -0.002399325 0.004358589 0.01524353 0.002409756 0.004358589 0.01574677 -0.002357006 0.002762258 0.01574778 0.002367198 0.002762258 0.01524245 -0.002399325 0.002783894 0.01524353 0.002409756 0.002783894 0.01458567 0.002465248 0.004375576 0.01458454 -0.002454578 0.004375576 0.01458454 -0.002454578 0.002800762 0.0139265 -0.002509891 0.002806603 0.008025884 -0.003005445 0.003936886 0.008677244 -0.002950727 0.004030346 0.009330153 -0.002895891 0.00411278 0.009984433 -0.002840995 0.004184305 0.01063972 -0.002785921 0.004244744 0.01129597 -0.002730846 0.004294216 0.01195293 -0.002675592 0.004332602 0.01261055 -0.002620458 0.00436002 0.01326847 -0.002565145 0.004376232 0.0139265 -0.002509891 0.004381477 -0.0589044 -0.008626818 -0.004330515 -0.05905765 -0.008639633 -0.002770125 -0.05905765 -0.008639633 -0.004344701 0.008025884 -0.003005445 0.002362072 -0.0589044 -0.008626818 -0.00275582 0.008677244 -0.002950727 0.002455532 0.009330153 -0.002895891 0.002538084 0.009984433 -0.002840995 0.00260961 0.01063972 -0.002785921 0.00266999 0.01129597 -0.002730846 0.002719461 0.01195293 -0.002675592 0.002757906 0.01261055 -0.002620458 0.002785086 0.01326847 -0.002565145 0.002801477 -0.05905383 0.008682966 -0.002770125 -0.05890059 0.008669972 -0.004330515 -0.05905383 0.008682966 -0.004344701 0.008027195 0.003018975 0.002362072 -0.05890059 0.008669972 -0.00275582 0.008027195 0.003018975 0.003936886 0.008678555 0.002964019 0.002455532 0.009331464 0.002908945 0.002538084 0.009985685 0.002853572 0.00260961 0.01064097 0.002798259 0.00266999 0.01129722 0.002742946 0.002719461 0.01195412 0.002687454 0.002757906 0.01261168 0.002631843 0.002785086 0.0132696 0.00257641 0.002801477 0.01392763 0.002520799 0.002806603 0.01458567 0.002465248 0.002800762 0.008678555 0.002964019 0.004030346 0.009331464 0.002908945 0.00411278 0.009985685 0.002853572 0.004184305 0.01064097 0.002798259 0.004244744 0.01129722 0.002742946 0.004294216 0.01195412 0.002687454 0.004332602 0.01261168 0.002631843 0.00436002 0.0132696 0.00257641 0.004376232 0.01392763 0.002520799 0.004381477 -0.0608797 -0.008726298 -0.002939581 -0.06087583 0.008770346 -0.002939581 -0.06088066 -0.008726298 -0.004511713 -0.06121915 -0.008742392 -0.002966463 -0.06121915 -0.008742392 -0.004537105 -0.06087672 0.008770465 -0.004511713 -0.06121528 0.008786678 -0.002966463 -0.06121528 0.008786678 -0.004537105 -0.06285738 -0.008701264 -0.003095924 -0.06285351 0.008746385 -0.003095924 -0.06285959 -0.008701264 -0.004659771 -0.0633825 -0.008688151 -0.003130137 -0.0633825 -0.008688151 -0.004690349 -0.06285572 0.008746206 -0.004659771 -0.06337863 0.008733332 -0.003130137 -0.06337863 0.008733332 -0.004690349 -0.06483691 -0.008545637 -0.003224849 -0.0648331 0.008591592 -0.003224849 -0.06484085 -0.008545279 -0.004775285 -0.06553614 -0.008477091 -0.003260672 -0.06553614 -0.008477091 -0.004804074 -0.06483703 0.008591234 -0.004775285 -0.06553232 0.008523404 -0.003260672 -0.06553232 0.008523404 -0.004804074 -0.06681811 -0.008256793 -0.003326177 -0.06681442 0.008303582 -0.003326177 -0.0668236 -0.008255779 -0.004857599 -0.06766873 -0.008110523 -0.003358125 -0.06766873 -0.008110523 -0.00487858 -0.0668199 0.008302688 -0.004857599 -0.06766515 0.00815773 -0.003358125 -0.06766515 0.00815773 -0.00487858 -0.0688005 -0.007830321 -0.003400325 -0.06879705 0.007877945 -0.003400325 -0.06880742 -0.007828533 -0.004907071 -0.06976926 -0.007590293 -0.003423213 -0.06976926 -0.007590293 -0.004915058 -0.06880396 0.007876276 -0.004907071 -0.06976592 0.007638454 -0.003423213 -0.06976592 0.007638454 -0.004915058 -0.07078361 -0.007259309 -0.003446877 -0.07078039 0.007307887 -0.003446877 -0.07182639 -0.006919145 -0.004914879 -0.07079172 -0.007256686 -0.004923582 -0.07182639 -0.006919145 -0.003457009 -0.0707885 0.007305145 -0.004923582 -0.07182329 0.006968021 -0.004914879 -0.07182329 0.006968021 -0.003457009 -0.07276707 -0.006534636 -0.003466069 -0.07276415 0.006584048 -0.003466069 -0.07277601 -0.00653094 -0.004907071 -0.07382947 -0.006100475 -0.004880785 -0.07382947 -0.006100475 -0.003461539 -0.07277309 0.006580471 -0.004907071 -0.07382678 0.006150424 -0.003461539 -0.07382678 0.006150424 -0.004880785 -0.07475072 -0.005643486 -0.003457605 -0.07474815 0.005693793 -0.003457605 -0.07475972 -0.005638957 -0.004857599 -0.07576799 -0.005138754 -0.004815697 -0.07576799 -0.005138754 -0.003439247 -0.07475715 0.005689322 -0.004857599 -0.07576566 0.005189538 -0.004815697 -0.07576566 0.005189538 -0.003439247 -0.07673394 -0.004568696 -0.003421843 -0.07673192 0.004620015 -0.003421843 -0.07674247 -0.004563808 -0.004775285 -0.07763171 -0.004038989 -0.004723429 -0.07763171 -0.004038989 -0.003393113 -0.07674044 0.004615068 -0.004775285 -0.07762992 0.004090666 -0.004723429 -0.07762992 0.004090666 -0.003393113 -0.07871502 0.003339886 -0.003358542 -0.07871645 -0.003287732 -0.003358542 -0.07872325 -0.003283083 -0.004659771 -0.07941079 -0.00280708 -0.004608333 -0.07941079 -0.00280708 -0.003326773 -0.07872182 0.003335118 -0.004659771 -0.07940948 0.002859413 -0.004608333 -0.07940948 0.002859413 -0.003326773 -0.08069711 0.001822829 -0.003267824 -0.08069795 -0.0017699 -0.003267824 -0.08070194 -0.001766681 -0.004511713 -0.08109575 -0.001449346 -0.004475593 -0.08109575 -0.001449346 -0.003243982 -0.08070117 0.00181961 -0.004511713 -0.08109509 0.001502513 -0.004475593 -0.08109509 0.001502513 -0.003243982 -0.08267784 2.69535e-5 -0.003149569 -0.08267784 2.69535e-5 -0.004330515 + + + + + + + + + + 0.007873892 -0.704777 -0.7093853 0.04452794 0.6901073 -0.7223359 0.008240103 0.7056317 -0.708531 0.04434418 -0.6900665 -0.7223863 0.1712746 -0.6516795 -0.7389038 0.1713663 0.6516195 -0.7389355 0.3326954 -0.584239 -0.7402558 0.3329977 0.5839591 -0.7403408 0.4067649 0.5614991 -0.7205977 0.4062717 -0.5618281 -0.7206196 -0.05713224 -0.7024948 -0.7093921 0.4067059 0.5616546 -0.7205098 -0.0278638 -0.7024853 -0.7111527 0.4473266 0.4859339 -0.7508445 0.5586311 0.3449937 -0.7542618 0.6287958 0.1790586 -0.756673 0.6532686 -1.22078e-4 -0.7571263 0.6532686 -9.15583e-5 -0.7571263 0.4063316 -0.5618266 -0.7205871 -0.05682682 0.7025224 -0.7093892 -0.02752834 0.7024918 -0.7111592 0.4471682 -0.4861413 -0.7508044 0.558465 -0.3451685 -0.7543047 0.6287567 -0.1792393 -0.7566627 0.4471957 -0.486077 -0.7508298 0.4474965 0.4858586 -0.7507919 0.558624 0.3449589 -0.7542828 0.5585058 -0.3452054 -0.7542576 0.6285446 -0.1793313 -0.7568171 0.6286309 0.1790551 -0.7568108 0.4060576 -0.5618275 -0.7207407 0.4474167 0.4859018 -0.7508115 0.4065752 0.5616122 -0.7206166 0.4472681 -0.4860283 -0.7508183 0.5585268 -0.3451995 -0.7542447 0.5586579 0.3449609 -0.7542569 0.6285116 -0.1793305 -0.7568446 0.6286159 0.179029 -0.7568295 0.3589363 0.5767213 0.7338646 0.4670121 0.5506361 0.6918812 0.5170523 0.460348 0.7216209 0.2009369 0.647277 0.7352938 0.07349038 0.6888808 0.7211397 0.02823036 0.7026776 -0.7109482 0.05423223 0.7024865 -0.7096279 0.08011156 0.7022046 -0.7074538 0.105871 0.7019109 -0.7043525 0.1315373 0.7016645 -0.7002606 0.01574784 0.7113092 0.7027029 0.1570219 0.7014868 -0.6951693 -0.008301258 0.7101886 0.7039626 0.1822632 0.7011885 -0.6892858 -0.03073328 0.7111995 0.7023183 -0.05313372 0.7111862 0.7009929 -0.07547473 0.7113792 0.6987441 0.2072861 0.7009944 -0.6823778 -0.09775197 0.7117614 0.6955864 -0.1199114 0.7118385 0.6920313 0.2320693 0.7007555 -0.6746003 -0.1419753 0.7121351 0.6875367 0.2564844 0.7004491 -0.6660232 -0.1638561 0.7124034 0.6823728 -0.185588 0.7125958 0.6765829 0.2805923 0.7002295 -0.6564652 -0.2071002 0.7127653 0.6701306 0.2977162 0.7020974 -0.6468574 -0.2284666 0.7130199 0.6628769 0.3379043 0.7103561 -0.6174262 -0.2318238 0.7060005 0.6691944 -0.1384962 0.7339875 0.6648919 0.02792543 -0.7027449 -0.7108936 0.1566844 -0.7015398 -0.6951919 -0.008636891 -0.7109154 0.7032245 0.01544272 -0.7112216 0.7027983 0.1819564 -0.701274 -0.6892799 -0.03103762 -0.7108135 0.7026955 -0.05343908 -0.7113111 0.700843 -0.07577973 -0.7114384 0.6986508 0.2069808 -0.7010552 -0.682408 -0.09805864 -0.7116195 0.6956884 -0.1202447 -0.7118549 0.6919565 0.2317322 -0.7008122 -0.6746573 -0.1422804 -0.7121042 0.6875057 0.2561825 -0.7005802 -0.6660014 -0.1641607 -0.7122482 0.6824617 -0.1858909 -0.7124956 0.6766052 0.2802868 -0.7003813 -0.6564339 -0.2074396 -0.7126557 0.6701424 0.2974125 -0.702223 -0.6468606 -0.2287708 -0.7129251 0.6628739 0.3376912 -0.7105095 -0.617366 -0.2321275 -0.7059046 0.6691902 -0.1387987 -0.7339424 0.6648787 0.07330816 -0.6888589 0.7211792 0.05389636 -0.702484 -0.709656 0.07980662 -0.7022679 -0.7074255 0.105567 -0.7020408 -0.7042688 0.1312317 -0.7017236 -0.7002587 0.2008163 -0.6473429 0.7352687 0.3585157 -0.5771594 0.7337259 0.4663654 -0.5509649 0.6920556 0.5168786 -0.4605701 0.7216035 0.007965445 -0.7122839 -0.7018464 -0.005615472 0.7092592 -0.7049255 0.008209586 0.7049282 -0.7092313 0.3327151 -0.5842199 -0.7402621 0.3585736 -0.5770931 0.7337498 0.466423 -0.5509609 0.6920201 0.5168418 -0.4606255 0.7215947 0.6157302 -0.3232927 0.7185808 0.6776756 -0.1664204 0.7162821 0.6978764 -1.22076e-4 0.7162183 0.6781118 0.1661784 0.7159254 0.615906 0.3230447 0.7185417 0.6157566 -0.323321 0.7185454 0.6780131 -0.1664819 0.7159484 0.6756265 -1.52594e-4 0.7372441 0.6781004 0.1661451 0.7159439 0.5170933 0.4603269 0.721605 0.3587254 0.5770004 0.7337483 0.3329001 0.5840706 -0.7402967 0.4666431 0.5507243 0.6920601 0.008209586 0.7051423 -0.7090183 0.00790441 -0.7054501 -0.7087156 0.04464972 0.6900412 -0.7223917 0.1715188 0.6516494 -0.7388737 0.3325408 -0.5844489 -0.7401596 0.3584765 -0.5772064 0.733708 0.4662682 -0.5510193 0.6920778 0.5168522 -0.4605432 0.7216397 0.615789 -0.323322 0.7185171 0.6780165 -0.1664522 0.715952 0.6777083 0.1661462 0.716315 0.6158809 0.323078 0.7185481 0.5170003 0.4603866 0.7216336 0.3588473 0.5768475 0.7338089 0.4667862 0.5507741 0.6919239 -0.005920648 -0.709258 -0.7049243 0.008118033 0.6974511 -0.7165865 0.00790441 -0.7053583 -0.7088069 0.04471057 0.6900081 -0.7224195 0.171578 0.6516426 -0.738866 0.02108871 -0.7091739 0.7047181 -0.08636957 -0.7024626 -0.7064607 -0.1153327 -0.702495 -0.7022814 -0.1441398 -0.7024489 -0.696986 -0.172769 -0.7024599 -0.6904354 -0.2010295 -0.7024589 -0.6827435 -0.2289544 -0.7024588 -0.6738929 -0.2565722 -0.7024225 -0.6639077 -0.2836762 -0.7024611 -0.6527452 0.02850461 -0.7117918 0.7018121 0.05713218 -0.7117418 0.700114 0.08563649 -0.7117353 0.6972082 -0.3103208 -0.702403 -0.6405708 0.1140202 -0.7117722 0.6930944 0.1422487 -0.7117623 0.687866 -0.3184356 -0.70795 -0.6304012 0.170204 -0.7117623 0.6814875 0.1978582 -0.7117767 0.673963 -0.3217352 -0.708324 -0.6283023 0.2251986 -0.7117912 0.665311 0.2521854 -0.7117835 0.655566 0.2787303 -0.7117954 0.6447146 0.3048267 -0.7118015 0.6327871 0.302228 -0.7131338 0.6325335 0.3184728 -0.7068052 0.6316658 -0.08603453 0.7024984 -0.706466 0.02139425 0.7091541 0.7047288 -0.1150266 0.7025507 -0.702276 -0.1438347 0.7025106 -0.6969867 -0.1724655 0.7025582 -0.6904113 -0.2007237 0.7025483 -0.6827415 -0.2286505 0.7025542 -0.6738966 -0.2562705 0.7025238 -0.6639169 -0.2833712 0.7025837 -0.6527457 0.0288102 0.7117401 0.7018519 0.05743765 0.7117143 0.7001169 0.08594131 0.7117016 0.6972052 -0.3100118 0.7025468 -0.6405628 0.1143565 0.7117148 0.6930979 0.1425838 0.7116982 0.6878631 -0.3180995 0.7081018 -0.6304004 0.1705114 0.7116801 0.6814965 0.1981643 0.7116885 0.6739662 -0.3214337 0.7084543 -0.6283095 0.2255369 0.7116772 0.6653186 0.2524876 0.7116835 0.6555582 0.279036 0.7116746 0.6447157 0.3051643 0.7116533 0.632791 0.3025382 0.7129929 0.6325439 0.3185291 0.7067337 0.6317174 0 0 1 -0.08633911 0.7184551 0.6901942 -0.08859604 -0.7145059 0.6939973 0.4285139 0.6592968 -0.6178217 0.9248619 1.22078e-4 0.380303 0.4283471 -0.659383 -0.6178454 0.02789491 -0.7027148 -0.7109246 0.02823036 0.7027082 -0.7109179 0.1566877 -0.7015547 -0.6951761 -0.008606433 -0.7105209 0.7036235 0.01501572 -0.7177035 0.696187 -0.03103816 -0.7111927 0.7023116 0.2069807 -0.7010853 -0.6823771 -0.09805876 -0.711529 0.6957809 -0.1202473 -0.7118398 0.6919716 -0.1422806 -0.7120442 0.6875677 0.2561823 -0.7006101 -0.6659702 -0.1641637 -0.7123525 0.682352 -0.1858912 -0.7124658 0.6766365 0.2802931 -0.7003362 -0.6564793 -0.2074347 -0.7127003 0.6700963 -0.2287712 -0.7128957 0.6629054 0.3376047 -0.7104897 -0.6174363 -0.1388317 -0.7339252 0.6648907 0.07330656 -0.6888437 0.7211938 0.05392795 -0.7025287 -0.7096092 0.07977795 -0.7021622 -0.7075336 0.105567 -0.7020713 -0.7042382 0.1312018 -0.7016959 -0.7002921 0.2008496 -0.6473212 0.7352787 0.05423343 0.7025017 -0.7096127 0.08008295 0.7021602 -0.7075012 0.1058711 0.7020027 -0.7042611 0.1315373 0.701695 -0.7002301 0.01574784 0.7110969 0.7029178 0.1822593 0.7011737 -0.6893019 -0.07547301 0.7114547 0.6986674 -0.09775203 0.711701 0.6956481 -0.1199088 0.7118536 0.6920163 0.2320361 0.7006861 -0.6746839 -0.1419751 0.7121951 0.6874746 0.2564839 0.7005086 -0.6659607 -0.1638566 0.7123138 0.6824662 -0.1855844 0.7125514 0.6766308 -0.2071047 0.7127504 0.6701452 -0.2284663 0.7130494 0.6628453 0.3379982 0.7103608 -0.6173693 -0.1384333 0.7340078 0.6648827 0.01574784 0.7111879 0.7028257 0.07361328 0.6888274 0.7211782 0.2010631 0.6472902 0.7352477 0.05420184 0.7024877 -0.7096291 0.08011329 0.7022199 -0.7074386 0.1058711 0.7019415 -0.704322 0.1569922 0.7014294 -0.695234 -0.008301258 0.7105835 0.703564 0.1822593 0.701204 -0.689271 0.2072862 0.7009643 -0.6824086 -0.09775412 0.7117161 0.6956323 -0.1199086 0.7119137 0.6919544 0.2320407 0.7007305 -0.6746362 -0.1419456 0.7121083 0.6875707 0.2564842 0.7004788 -0.665992 -0.1638563 0.7123736 0.6824039 -0.2071334 0.712805 0.6700782 0.2977157 0.7021268 -0.6468258 -0.228467 0.7129905 0.6629084 -0.2318232 0.7060599 0.6691318 -0.1384632 0.7340046 0.6648798 -0.008606433 -0.7101867 0.7039607 0.1819565 -0.7012437 -0.6893106 -0.07580995 -0.7115274 0.6985568 0.2069851 -0.7010698 -0.6823917 -0.1202147 -0.7118576 0.6919591 -0.1422807 -0.7120141 0.6875988 -0.164164 -0.7122929 0.6824143 0.280259 -0.7003577 -0.6564709 -0.2074398 -0.712626 0.6701737 0.2974051 -0.7022972 -0.6467835 -0.2288004 -0.7128613 0.6629323 0.3376317 -0.7104824 -0.6174299 -0.2321021 -0.7060726 0.6690218 -0.1388018 -0.7339283 0.6648936 0.0538659 -0.7024545 -0.7096874 0.1312017 -0.7017569 -0.7002309 0.0736739 0.6887931 0.7212047 0.01541227 -0.7111006 0.7029215 0.01614469 0.7045383 0.7094824 0.2011217 0.6472823 0.7352387 0.02819925 0.7027242 -0.7109032 -0.09805637 -0.7116948 0.6956115 -0.1202172 -0.7118726 0.6919432 0.2317324 -0.7007823 -0.6746883 -0.1422477 -0.7120323 0.6875868 0.2561771 -0.7005958 -0.6659871 -0.1641643 -0.7122331 0.6824765 -0.1859245 -0.7124766 0.6766161 0.2802872 -0.7003517 -0.6564653 -0.207439 -0.7127149 0.6700796 0.297412 -0.7022524 -0.646829 -0.2287719 -0.7128369 0.6629685 0.3378518 -0.7105265 -0.6172586 -0.232127 -0.705964 0.6691277 -0.1387086 -0.7339807 0.6648553 0.1312345 -0.7017996 -0.7001821 0.05423223 0.7025172 -0.7095975 0.08011329 0.7021892 -0.7074689 0.1569923 0.701399 -0.6952646 -0.008331716 0.7116453 0.7024896 0.1822592 0.7012342 -0.6892403 -0.03073257 0.7112146 0.702303 -0.05313378 0.7110347 0.7011466 -0.07547312 0.711364 0.6987597 -0.1199112 0.7118986 0.6919694 0.2805984 0.700214 -0.6564793 -0.2071042 0.7128095 0.6700825 -0.2284331 0.7130104 0.6628986 0.2691169 0.7222333 0.6371462 0.2687818 -0.7223569 0.6371476 0.228954 -0.7280324 0.6461803 0.2292295 0.7279435 0.6461827 0.1883026 -0.731298 0.6555497 0.1886391 0.7312092 0.6555522 0.1472223 -0.7319919 0.6652169 0.1475604 0.7319422 0.6651967 0.1059031 0.7300906 0.6750943 0.1055664 -0.730145 0.6750881 0.08685803 0.7268486 0.6812832 0.08661341 -0.7269669 0.6811882 -0.3460894 -0.7041729 -0.61997 -0.3457835 0.7043241 -0.6199688 -0.3830182 -0.6919964 -0.6119135 -0.3827424 0.6921775 -0.6118813 -0.4190854 -0.677794 -0.6041215 -0.4188156 0.6779546 -0.6041285 -0.4539681 -0.6616796 -0.5967354 -0.4536374 0.6619005 -0.596742 -0.4874008 -0.6439368 -0.5897337 -0.4871243 0.644148 -0.5897315 -0.5051868 -0.6279662 -0.5919838 -0.5049144 0.6281827 -0.5919865 0.428213 -0.6594864 -0.6178279 0.9247993 5.49349e-4 0.380455 -0.08673501 -0.7183259 0.6902789 -0.08810907 0.7148222 0.6937335 0.4286481 0.6591932 -0.6178392 -0.08826124 0.7144218 0.6941266 -0.08655297 -0.7184569 0.6901654 0.42864 0.6591808 -0.6178581 0.9248771 -1.52595e-4 0.3802663 0.428489 0.6593054 -0.6178298 0.4286156 -0.6591597 -0.6178974 0.9248771 -1.83114e-4 0.3802663 -0.09180217 -0.7076826 0.7005411 -0.08633774 0.7182605 0.6903968 0.05194377 0.7231851 0.6886983 0.0516687 -0.7232099 0.6886929 0.009369194 0.7153885 0.6986643 0.009033739 -0.7154059 0.6986507 -0.005646049 0.6996867 0.7144275 -0.01376384 -0.707909 0.7061695 -0.5111896 -0.6257266 -0.5891956 -0.5109276 0.6259557 -0.5891796 -0.542573 -0.6047714 -0.5829805 -0.5423933 0.6049583 -0.5829537 -0.5556324 -0.5894477 -0.5863652 -0.5553316 0.589605 -0.586492 -0.0563997 0.698557 0.7133283 -0.05673432 -0.6985129 0.713345 -0.09872913 0.6841154 0.722661 -0.0990355 -0.6840623 0.7226693 -0.09347969 0.6483764 0.7555592 -0.1177434 -0.6704479 0.7325546 -0.5565118 -0.5853216 -0.5896553 -0.5560875 0.5857215 -0.5896584 -0.5856999 -0.5617421 -0.5842959 -0.5854791 0.5619794 -0.5842888 -0.59662 0.5451341 -0.5889597 -0.5974527 -0.5448063 -0.5884188 -0.1639198 0.6592499 0.7338393 -0.1642266 -0.659165 0.7338468 -0.2042353 0.638159 0.7423214 -0.2045397 -0.6380649 0.7423185 -0.2083831 0.6264007 0.7511315 -0.2086286 -0.6263132 0.7511364 -0.2111607 -0.6253948 0.7511941 -0.2109818 0.6256208 0.7510563 -0.598571 -0.5400659 -0.5916432 -0.5978343 0.5408861 -0.591639 -0.6254023 -0.5136405 -0.5874058 -0.6251654 0.5139211 -0.5874125 -0.6362403 -0.4928901 -0.593513 -0.6360175 0.4931882 -0.5935044 -0.6295503 0.501919 -0.5930799 -0.6297661 -0.5016461 -0.5930819 -0.6142001 0.5059788 -0.6055938 -0.5983405 0.5102299 -0.6177816 -0.5758697 0.5148311 -0.6350773 -0.256116 0.6114801 0.7486633 -0.2330726 0.6167864 0.7518324 -0.2554156 0.6087675 0.7511093 -0.2337482 -0.6170721 0.751388 -0.6144507 -0.5057399 -0.605539 -0.5985482 -0.5099197 -0.6178366 -0.5765973 -0.5143994 -0.6347668 -0.2564547 -0.611365 0.7486413 -0.2544699 -0.6075781 0.7523922 -0.5624129 0.532809 -0.6323025 -0.5295488 0.5400476 -0.6541611 -0.2349406 0.6237921 0.7454437 -0.2558115 0.6191115 0.7424699 -0.2355175 -0.5979037 0.7661872 -0.5631108 -0.531859 -0.632481 -0.5297617 -0.5398027 -0.6541908 -0.2352127 -0.6236631 0.7454659 -0.4891597 0.5717748 -0.6586321 -0.1821397 0.6489338 0.7387219 -0.1824125 -0.648866 0.7387142 -0.1736525 0.6647933 0.7265636 -0.171061 -0.6606223 0.7309694 -0.4894713 -0.5715687 -0.6585797 -0.4612045 0.6017755 -0.6520404 -0.4615203 -0.6014841 -0.6520859 -0.4256244 0.6049262 -0.6729846 -0.1526259 0.6638205 0.7321528 -0.1529633 -0.6637672 0.7321307 -0.09778314 0.6803619 0.7263237 -0.09808945 -0.6803088 0.7263322 -0.08588254 -0.6886168 0.7200216 -0.08557581 0.6886046 0.7200699 -0.4258964 -0.6047394 -0.6729804 -0.3796893 -0.6299162 -0.6775262 -0.3793843 0.6300997 -0.6775265 -0.3457188 -0.6563408 -0.6705932 -0.3454155 0.656497 -0.6705968 -0.06753873 0.6886633 0.7219291 -0.06784391 -0.688633 0.7219293 -0.01208567 0.6968501 0.7171149 -0.012299 -0.6968331 0.7171279 0.001648008 0.6971485 0.7169249 0.002410948 -0.6940619 0.7199115 -0.308704 -0.6548554 -0.6898307 -0.3083971 0.6550042 -0.6898266 -0.2574018 0.6724066 -0.693984 -0.257708 -0.6722869 -0.6939864 -0.2180295 0.6936721 -0.6865 -0.2182423 -0.6935473 -0.6865584 0.01843345 -0.6990072 0.7148771 0.01876944 0.6989255 0.7149482 0.0621066 -0.6953199 0.716012 0.06241202 0.6953219 0.7159835 -0.1805207 -0.6870774 -0.7038019 -0.1802472 0.6870819 -0.7038675 -0.1138665 -0.6996485 -0.7053555 -0.1135001 0.6997701 -0.705294 0.1037969 0.6956624 0.7108306 0.1035209 -0.6957446 0.7107905 0.1167041 0.699431 0.7051075 0.1165834 -0.6904057 0.7139666 -0.04669475 -0.6988958 -0.7136977 -0.04638922 0.6988597 -0.7137531 -0.001342833 0.7111536 -0.7030355 -0.001434385 -0.7109713 -0.7032195 0.1333389 -0.6898281 0.7115884 0.1337042 0.6897624 0.7115836 0.1874822 -0.6790317 0.709765 0.1878139 0.6789561 0.7097497 0.2030446 -0.6742621 0.7100307 0.2033491 0.6740766 0.7101197 0.03448635 -0.6958309 -0.7173773 0.0346387 0.6957963 -0.7174035 0.08945196 -0.6890031 -0.7192171 0.08978688 0.6889663 -0.7192106 0.1323603 -0.6938772 -0.7078243 0.1326658 0.6938174 -0.7078257 0.1439926 -0.7123639 0.6868798 0.1443246 0.7122845 0.6868926 0.08273762 -0.7012099 0.7081378 0.08307301 0.7015736 0.7077384 0.08920717 -0.7164045 -0.6919587 0.08951193 0.7163701 -0.6919549 0.03552448 -0.7075603 -0.7057596 0.03583008 0.7075372 -0.7057671 0.07123219 0.7020068 0.708599 0.07089638 -0.7014256 0.709208 0.04751849 -0.7069792 -0.7056363 0.05926829 -0.7064892 -0.7052379 -0.02456784 -0.7129557 0.7007787 -0.03622633 -0.7067953 0.7064901 -0.02432364 -0.7063939 0.707401 -0.01242125 -0.7058457 0.7082567 -4.8831e-4 -0.7051508 0.7090572 0.01141422 -0.704814 0.7093004 0.02325534 -0.7037038 0.7101128 0.03524923 -0.7044054 0.7089222 0.04718202 -0.703031 0.7095925 0.05905479 -0.7027069 0.7090244 0.1261068 -0.7010038 -0.7019194 -0.01773166 -0.7117103 0.7022494 0.1098364 -0.7075127 -0.698113 0.1432272 -0.6963899 -0.7032262 -0.007873892 -0.7124661 0.7016623 0.1530532 -0.7026104 -0.6949197 0.1414866 -0.7030994 -0.6968736 0.1297687 -0.7036259 -0.6986207 0.1180791 -0.7040497 -0.7002654 0.1064813 -0.7046262 -0.7015438 0.09458041 -0.7049739 -0.7028985 0.08289009 -0.7055732 -0.7037726 0.07110995 -0.7060945 -0.7045381 -0.01739609 0.7117145 0.7022535 0.1265326 0.7008739 -0.7019726 0.1102656 0.7074944 -0.698064 0.1435322 0.696328 -0.7032254 -0.008759021 0.704297 0.7098515 -0.0242623 0.712976 0.7007686 0.1533909 0.7025279 -0.6949286 0.1418845 0.7030745 -0.696818 0.1301343 0.7035312 -0.698648 0.1182924 0.7038642 -0.7004156 0.1067876 0.7045726 -0.7015511 0.09500586 0.7051128 -0.7027019 0.083072 0.7052881 -0.7040368 0.07141512 0.7060639 -0.7045379 0.05957365 0.7064611 -0.7052403 0.04782402 0.7069536 -0.7056412 -0.03592073 0.7068183 0.7064826 -0.02398765 0.7064149 0.7073915 -0.01214659 0.7049916 0.7091117 -2.13631e-4 0.7050438 0.7091639 0.01174992 0.7057903 0.7083234 0.02359139 0.7036829 0.7101225 0.03549349 0.7028207 0.710481 0.04767072 0.7055395 0.7070655 0.05935895 0.7026636 0.709042 -0.02676564 -0.7092756 0.704423 -0.02646011 0.7092966 0.7044135 0.09201705 -0.7030531 -0.705159 -0.04580932 -0.7153705 0.6972422 0.05899363 -0.7147909 -0.6968456 0.09223085 0.703085 -0.7050993 -0.04547333 0.7153964 0.6972376 0.0592066 0.7147216 -0.6968986 -0.06845533 -0.7077485 0.7031401 -0.06830191 0.7079232 0.7029791 0.02951222 -0.7056381 -0.7079576 -0.08804869 -0.7124471 0.6961801 -0.004120051 -0.714946 -0.6991676 0.0298171 0.7056317 -0.7079512 -0.08774209 0.712466 0.6961994 -0.003753781 0.7149318 -0.6991841 -0.1100522 -0.7032846 0.7023386 -0.1097182 0.7033869 0.7022882 -0.03320449 -0.7036125 -0.7098078 -0.1299185 -0.7064495 0.6957373 -0.06738632 -0.7105475 -0.7004152 -0.0328387 0.7036516 -0.7097859 -0.1296157 0.706523 0.6957191 -0.06708103 0.7105772 -0.7004144 -0.1512528 -0.6957752 0.7021536 -0.150915 0.6957963 0.7022053 -0.09558653 -0.697092 -0.7105816 -0.1714874 -0.697425 0.695838 -0.1299223 -0.7015864 -0.7006403 -0.09528005 0.6971436 -0.710572 -0.1712099 0.6975049 0.6958263 -0.1296166 0.7016452 -0.7006381 -0.1918741 -0.6852778 0.7025516 -0.1915386 0.6853395 0.7025829 -0.1571429 -0.6861004 -0.7103326 -0.2123826 -0.6853985 0.6965075 -0.1915047 -0.6881659 -0.699824 -0.1568388 0.6861966 -0.7103069 -0.2120778 0.6854915 0.6965089 -0.1912321 0.6882342 -0.6998314 -0.2317613 -0.6717232 0.7036156 -0.2314875 0.6718785 0.7035574 -0.2516901 -0.6704411 -0.6979692 -0.2169613 -0.6685853 -0.7112817 -0.2525146 -0.6703203 0.6977874 -0.2167157 0.6687027 -0.7112463 -0.2513548 0.6705338 -0.698001 -0.2522417 0.670386 0.6978228 -0.2709174 -0.6553353 0.7050812 -0.270613 0.6554591 0.7050831 -0.2763822 -0.6511279 -0.7068561 -0.3098915 -0.6486236 -0.6951653 -0.2916742 -0.6522307 0.6996579 -0.2760792 0.6513163 -0.7068008 -0.2913659 0.6523765 0.6996506 -0.3095911 0.6487556 -0.695176 -0.309062 -0.6359775 0.7071163 -0.3087619 0.6361101 0.7071281 -0.3330273 -0.6276307 -0.703685 -0.3657459 -0.6229643 -0.6914806 -0.3298202 -0.631166 0.7020314 -0.3327855 0.6277877 -0.7036594 -0.3654731 0.6231203 -0.6914843 -0.3295436 0.631315 0.7020274 -0.3460596 -0.6136538 0.7096984 -0.3457596 0.6138461 0.7096784 -0.3872242 -0.6004601 -0.6996466 -0.4191208 -0.5936909 -0.6869272 -0.3666249 -0.6071758 0.7049282 -0.3869552 0.6006214 -0.6996567 -0.4188827 0.5938826 -0.6869066 -0.3663796 0.6073265 0.704926 -0.3814933 0.5885984 0.7127516 -0.3816743 -0.588412 0.7128087 -0.4385961 -0.5698301 -0.6949296 -0.4693841 -0.5612466 -0.6816751 -0.4020698 -0.5802452 0.7082765 -0.4383778 0.5700072 -0.6949222 -0.4691454 0.5614364 -0.6816831 -0.4018208 0.5803908 0.7082984 -0.4155743 0.5605385 0.7163063 -0.415826 -0.5603351 0.7163195 -0.48691 -0.5361992 -0.6894993 -0.5165979 -0.5258147 -0.6757555 -0.4358211 -0.550331 0.7121769 -0.4866935 0.5364402 -0.6894646 -0.5163526 0.5260577 -0.6757539 -0.435572 0.5505384 0.7121689 -0.7997472 1.83113e-4 0.6003369 -0.8465446 1.83116e-4 -0.5323178 + + + + + + + + + + 0.007652521 0.03637266 0.004921257 0.03651458 0.004923999 0.03637266 0.004921257 0.03651458 0.007652521 0.03637266 0.007655203 0.03651458 0.004921257 0.03651458 0.007655203 0.03651458 0.007696986 0.03679347 0.004921257 0.03651458 0.007696986 0.03679347 0.004879415 0.03679347 0.004879415 0.03679347 0.007696986 0.03679347 0.007808685 0.03705257 0.004879415 0.03679347 0.007808685 0.03705257 0.004767656 0.03705257 0.004767656 0.03705257 0.007808685 0.03705257 0.004705488 0.0371316 0.004705488 0.0371316 0.007808685 0.03705257 0.007870972 0.0371316 0.01749753 0.03798186 0.014548 0.03722298 0.01749753 0.03722298 0.014548 0.03722298 0.01749753 0.03798186 0.01443576 0.03736579 0.01443576 0.03736579 0.01749753 0.03798186 0.01421082 0.03753596 0.01421082 0.03753596 0.01749753 0.03798186 0.01394981 0.03764253 0.01394981 0.03764253 0.01749753 0.03798186 0.0136699 0.03767919 0.0136699 0.03767919 0.01749753 0.03798186 0.008748888 0.03767919 0.008748888 0.03767919 0.01749753 0.03798186 0.003827631 0.03767919 0.002949655 0.03722298 0 0.03798186 0 0.03722298 0 0.03798186 0.002949655 0.03722298 0.003061652 0.03736579 0 0.03798186 0.003061652 0.03736579 0.003286838 0.03753596 0 0.03798186 0.003286838 0.03753596 0.003547966 0.03764253 0 0.03798186 0.003547966 0.03764253 0.003827631 0.03767919 0 0.03798186 0.003827631 0.03767919 0.01749753 0.03798186 0.007982969 0.03736579 0.004705488 0.03722298 0.007870972 0.03722298 0.004705488 0.03722298 0.007982969 0.03736579 0.004593491 0.03736579 0.004593491 0.03736579 0.007982969 0.03736579 0.004368305 0.03753596 0.004368305 0.03753596 0.007982969 0.03736579 0.008208096 0.03753596 0.004368305 0.03753596 0.008208096 0.03753596 0.008469223 0.03764253 0.004368305 0.03753596 0.008469223 0.03764253 0.004107296 0.03764253 0.004107296 0.03764253 0.008469223 0.03764253 0.008748888 0.03767919 0.004107296 0.03764253 0.008748888 0.03767919 0.003827631 0.03767919 0.01279217 0.03722298 0.009514749 0.03736579 0.009626746 0.03722298 0.009514749 0.03736579 0.01279217 0.03722298 0.01290398 0.03736579 0.009514749 0.03736579 0.01290398 0.03736579 0.01312935 0.03753596 0.009514749 0.03736579 0.01312935 0.03753596 0.009289622 0.03753596 0.009289622 0.03753596 0.01312935 0.03753596 0.01339048 0.03764253 0.009289622 0.03753596 0.01339048 0.03764253 0.009028553 0.03764253 0.009028553 0.03764253 0.01339048 0.03764253 0.0136699 0.03767919 0.009028553 0.03764253 0.0136699 0.03767919 0.008748888 0.03767919 0.02624577 0.003659248 0.02614504 0.005117297 0.02614504 0.003657758 0.02614504 0.005117297 0.02624577 0.003659248 0.02642703 0.003667712 0.02614504 0.005117297 0.02642703 0.003667712 0.02624553 0.005118966 0.02624553 0.005118966 0.02642703 0.003667712 0.02642703 0.005127668 0.03207719 0.003657758 0.03179514 0.005112111 0.03179514 0.003653109 0.03179514 0.005112111 0.03207719 0.003657758 0.03207719 0.005117297 0.035604 0.003653109 0.03532207 0.005106389 0.03532207 0.003647983 0.03532207 0.005106389 0.035604 0.003653109 0.035604 0.005112111 0.0363512 0.003647983 0.03370738 0.003650844 0.03620898 0.00364536 0.03370738 0.003650844 0.0363512 0.003647983 0.0363512 0.005106389 0.03370738 0.003650844 0.0363512 0.005106389 0.03120756 0.00374794 0.03120756 0.00374794 0.0363512 0.005106389 0.02871268 0.00393635 0.02871268 0.00393635 0.0363512 0.005106389 0.02622658 0.004215717 0.02622658 0.004215717 0.0363512 0.005106389 0.02375257 0.004585981 0.02375257 0.004585981 0.0363512 0.005106389 0.03620898 0.005103528 0.02375257 0.004585981 0.03620898 0.005103528 0.02129358 0.005046308 0.02129358 0.005046308 0.03371828 0.005143225 0.01885277 0.00559628 0.03371828 0.005143225 0.02129358 0.005046308 0.03620898 0.005103528 0.01885277 0.00559628 0.03371828 0.005143225 0.03123039 0.005262315 0.01885277 0.00559628 0.03123039 0.005262315 0.02874732 0.005460739 0.01885277 0.00559628 0.02874732 0.005460739 0.02627182 0.005738139 0.01885277 0.00559628 0.02627182 0.005738139 0.01643419 0.006235122 0.01643419 0.006235122 0.02627182 0.005738139 0.02380651 0.006094396 0.01643419 0.006235122 0.02380651 0.006094396 0.02135372 0.006529033 0.01643419 0.006235122 0.02135372 0.006529033 0.01404041 0.006962001 0.01404041 0.006962001 0.02135372 0.006529033 0.01891607 0.007041752 0.01404041 0.006962001 0.01891607 0.007041752 0.01167476 0.007775843 0.01167476 0.007775843 0.01891607 0.007041752 0.01649606 0.007631838 0.01167476 0.007775843 0.01649606 0.007631838 0.01409602 0.008298873 0.01167476 0.007775843 0.01409602 0.008298873 0.009340465 0.008675634 0.009340465 0.008675634 0.01409602 0.008298873 0.01171857 0.009042024 0.009340465 0.008675634 0.01171857 0.009042024 0.007040679 0.009660243 0.007040679 0.009660243 0.01171857 0.009042024 0.009365975 0.009860634 0.007040679 0.009660243 0.009365975 0.009860634 0.003536522 0.01123654 0.003536522 0.01123654 0.009365975 0.009860634 0.007040679 0.01075381 0.003536522 0.01123654 0.007040679 0.01075381 0.003536522 0.01197981 -0.007652521 -0.03630352 -0.004972577 -0.03380227 -0.007603824 -0.03380227 -0.004972577 -0.03380227 -0.007652521 -0.03630352 -0.004923999 -0.03630352 -0.02153784 0.005046308 -0.03396302 0.005143225 -0.03645372 0.005103528 -0.03396302 0.005143225 -0.02153784 0.005046308 -0.01909726 0.00559628 -0.03396302 0.005143225 -0.01909726 0.00559628 -0.03147464 0.005262315 -0.03147464 0.005262315 -0.01909726 0.00559628 -0.02899158 0.005460739 -0.02899158 0.005460739 -0.01909726 0.00559628 -0.02651613 0.005738139 -0.02651613 0.005738139 -0.01909726 0.00559628 -0.01667869 0.006235122 -0.02651613 0.005738139 -0.01667869 0.006235122 -0.02405101 0.006094396 -0.02405101 0.006094396 -0.01667869 0.006235122 -0.02159816 0.006529033 -0.02159816 0.006529033 -0.01667869 0.006235122 -0.01428467 0.006962001 -0.02159816 0.006529033 -0.01428467 0.006962001 -0.01916033 0.007041752 -0.01916033 0.007041752 -0.01428467 0.006962001 -0.01191926 0.007775843 -0.01916033 0.007041752 -0.01191926 0.007775843 -0.01674056 0.007631838 -0.01674056 0.007631838 -0.01191926 0.007775843 -0.01434046 0.008298873 -0.01434046 0.008298873 -0.01191926 0.007775843 -0.009584963 0.008675634 -0.01434046 0.008298873 -0.009584963 0.008675634 -0.01196295 0.009042024 -0.01196295 0.009042024 -0.009584963 0.008675634 -0.007285118 0.009660243 -0.01196295 0.009042024 -0.007285118 0.009660243 -0.009610474 0.009860634 -0.009610474 0.009860634 -0.007285118 0.009660243 -0.00378108 0.01123654 -0.009610474 0.009860634 -0.00378108 0.01123654 -0.007285118 0.01075381 -0.007285118 0.01075381 -0.00378108 0.01123654 -0.00378108 0.01197981 -0.03395169 0.003650844 -0.0365957 0.003647983 -0.03645372 0.00364536 -0.0365957 0.003647983 -0.03395169 0.003650844 -0.0365957 0.005106389 -0.0365957 0.005106389 -0.03395169 0.003650844 -0.031452 0.00374794 -0.0365957 0.005106389 -0.031452 0.00374794 -0.02895718 0.00393635 -0.0365957 0.005106389 -0.02895718 0.00393635 -0.02647107 0.004215717 -0.0365957 0.005106389 -0.02647107 0.004215717 -0.02399682 0.004585981 -0.0365957 0.005106389 -0.02399682 0.004585981 -0.03645372 0.005103528 -0.03645372 0.005103528 -0.02399682 0.004585981 -0.02153784 0.005046308 -0.03718549 0.005106389 -0.03746747 0.003653109 -0.03718549 0.003647983 -0.03746747 0.003653109 -0.03718549 0.005106389 -0.03746747 0.005112111 -0.0367769 0.005112111 -0.03705883 0.003657758 -0.0367769 0.003653109 -0.03705883 0.003657758 -0.0367769 0.005112111 -0.03705883 0.005117297 -0.03391379 0.005117297 -0.03401452 0.003659248 -0.03391379 0.003657758 -0.03401452 0.003659248 -0.03391379 0.005117297 -0.03419584 0.003667712 -0.03419584 0.003667712 -0.03391379 0.005117297 -0.03401434 0.005118966 -0.03419584 0.003667712 -0.03401434 0.005118966 -0.03419584 0.005127668 0.002731204 0.03637266 0 0.03651458 2.76001e-6 0.03637266 0 0.03651458 0.002731204 0.03637266 0.002734005 0.03651458 0 0.03651458 0.002734005 0.03651458 0 0.0371316 0 0.0371316 0.002734005 0.03651458 0.002775788 0.03679347 0 0.0371316 0.002775788 0.03679347 0.002887487 0.03705257 0 0.0371316 0.002887487 0.03705257 0.002949655 0.0371316 -0.03087383 0.005117297 -0.03097432 0.003659248 -0.03087383 0.003657758 -0.03097432 0.003659248 -0.03087383 0.005117297 -0.03115588 0.003667712 -0.03115588 0.003667712 -0.03087383 0.005117297 -0.03097414 0.005118966 -0.03115588 0.003667712 -0.03097414 0.005118966 -0.03115588 0.005127668 -0.02514028 0.005138099 -0.02485823 0.003667712 -0.02485823 0.005127668 -0.02485823 0.003667712 -0.02514028 0.005138099 -0.02514028 0.003677845 -0.01746273 0.005144715 -0.01718068 0.003677845 -0.01718068 0.005138099 -0.01718068 0.003677845 -0.01746273 0.005144715 -0.01746273 0.003684282 -0.008633553 0.00514692 -0.008351504 0.003684282 -0.008351504 0.005144715 -0.008351504 0.003684282 -0.008633553 0.00514692 -0.008633553 0.003686428 7.60149e-4 0.005144715 0.001042068 0.003686428 0.001042068 0.00514692 0.001042068 0.003686428 7.60149e-4 0.005144715 7.60149e-4 0.003684282 0.01037573 0.005144715 0.01009368 0.003677845 0.01037573 0.003684282 0.01009368 0.003677845 0.01037573 0.005144715 0.01009368 0.005138099 0.0190292 0.005138099 0.01874727 0.003667712 0.0190292 0.003677845 0.01874727 0.003667712 0.0190292 0.005138099 0.01874727 0.005127668 -0.02906847 0.005138099 -0.02878654 0.003667712 -0.02878654 0.005127668 -0.02878654 0.003667712 -0.02906847 0.005138099 -0.02906847 0.003677845 -0.02173644 0.005138099 -0.02201843 0.003684282 -0.02173644 0.003677845 -0.02201843 0.003684282 -0.02173644 0.005138099 -0.02201843 0.005144715 -0.01351374 0.00514692 -0.01323175 0.003684282 -0.01323175 0.005144715 -0.01323175 0.003684282 -0.01351374 0.00514692 -0.01351374 0.003686428 -0.004119992 0.005144715 -0.003837943 0.003686428 -0.003837943 0.00514692 -0.003837943 0.003686428 -0.004119992 0.005144715 -0.004119992 0.003684282 0.005538225 0.005138099 0.005820155 0.003684282 0.005820155 0.005144715 0.005820155 0.003684282 0.005538225 0.005138099 0.005538225 0.003677845 0.01510071 0.005138099 0.01481866 0.003667712 0.01510071 0.003677845 0.01481866 0.003667712 0.01510071 0.005138099 0.01481866 0.005127668 0.02320557 0.003659248 0.02310508 0.005117297 0.02310508 0.003657758 0.02310508 0.005117297 0.02320557 0.003659248 0.02338707 0.003667712 0.02310508 0.005117297 0.02338707 0.003667712 0.02320533 0.005118966 0.02320533 0.005118966 0.02338707 0.003667712 0.02338707 0.005127668 0.01257652 0.03651458 0.009845256 0.03637266 0.01257354 0.03637266 0.009845256 0.03637266 0.01257652 0.03651458 0.009842514 0.03651458 0.009842514 0.03651458 0.01257652 0.03651458 0.009800672 0.03679347 0.009800672 0.03679347 0.01257652 0.03651458 0.0126183 0.03679347 0.009800672 0.03679347 0.0126183 0.03679347 0.009688973 0.03705257 0.009688973 0.03705257 0.0126183 0.03679347 0.01273006 0.03705257 0.009688973 0.03705257 0.01273006 0.03705257 0.01279217 0.0371316 0.009688973 0.03705257 0.01279217 0.0371316 0.009626746 0.0371316 -0.0369535 0.005117297 -0.0370543 0.003659248 -0.0369535 0.003657758 -0.0370543 0.003659248 -0.0369535 0.005117297 -0.03723555 0.003667712 -0.03723555 0.003667712 -0.0369535 0.005117297 -0.0370543 0.005118966 -0.03723555 0.003667712 -0.0370543 0.005118966 -0.03723555 0.005127668 -0.03299713 0.005138099 -0.03271514 0.003667712 -0.03271514 0.005127668 -0.03271514 0.003667712 -0.03299713 0.005138099 -0.03299713 0.003677845 -0.02657419 0.005144715 -0.0262922 0.003677845 -0.0262922 0.005138099 -0.0262922 0.003677845 -0.02657419 0.005144715 -0.02657419 0.003684282 -0.01839393 0.00514692 -0.01811194 0.003684282 -0.01811194 0.005144715 -0.01811194 0.003684282 -0.01839393 0.00514692 -0.01839393 0.003686428 -0.009000182 0.005144715 -0.008718192 0.003686428 -0.008718192 0.00514692 -0.008718192 0.003686428 -0.009000182 0.005144715 -0.009000182 0.003684282 9.82474e-4 0.005138099 0.001264393 0.003684282 0.001264393 0.005144715 0.001264393 0.003684282 9.82474e-4 0.005138099 9.82474e-4 0.003677845 0.01089048 0.005127668 0.01117247 0.003677845 0.01117247 0.005138099 0.01117247 0.003677845 0.01089048 0.005127668 0.01089048 0.003667712 0.02016586 0.003659248 0.02006489 0.005117297 0.02006489 0.003657758 0.02006489 0.005117297 0.02016586 0.003659248 0.02034687 0.003667712 0.02006489 0.005117297 0.02034687 0.003667712 0.02016562 0.005118966 0.02016562 0.005118966 0.02034687 0.003667712 0.02034687 0.005127668 0.01749753 0.03651458 0.01476651 0.03637266 0.01749503 0.03637266 0.01476651 0.03637266 0.01749753 0.03651458 0.01476377 0.03651458 0.01476377 0.03651458 0.01749753 0.03651458 0.01472193 0.03679347 0.01472193 0.03679347 0.01749753 0.03651458 0.01749753 0.0371316 0.01472193 0.03679347 0.01749753 0.0371316 0.01461023 0.03705257 0.01461023 0.03705257 0.01749753 0.0371316 0.014548 0.0371316 -0.03645372 0.005106389 -0.03707087 0.003659248 -0.03645372 0.003647983 -0.03707087 0.003659248 -0.03645372 0.005106389 -0.03782868 0.003704488 -0.03782868 0.003704488 -0.03645372 0.005106389 -0.03858399 0.003780782 -0.03858399 0.003780782 -0.03645372 0.005106389 -0.03933537 0.003888309 -0.03933537 0.003888309 -0.03645372 0.005106389 -0.04008173 0.004026532 -0.04008173 0.004026532 -0.03645372 0.005106389 -0.0408219 0.004195511 -0.0408219 0.004195511 -0.03645372 0.005106389 -0.04155457 0.004394769 -0.04155457 0.004394769 -0.03645372 0.005106389 -0.04227823 0.004624009 -0.04227823 0.004624009 -0.03645372 0.005106389 -0.04299205 0.004882872 -0.04299205 0.004882872 -0.03645372 0.005106389 -0.04369425 0.005170941 -0.04369425 0.005170941 -0.03645372 0.005106389 -0.03707069 0.005118966 -0.04369425 0.005170941 -0.03707069 0.005118966 -0.03782802 0.005165398 -0.04369425 0.005170941 -0.03782802 0.005165398 -0.03858315 0.005242824 -0.04369425 0.005170941 -0.03858315 0.005242824 -0.04438436 0.00548768 -0.04438436 0.00548768 -0.03858315 0.005242824 -0.03933465 0.005350828 -0.04438436 0.00548768 -0.03933465 0.005350828 -0.0400809 0.005489528 -0.04438436 0.00548768 -0.0400809 0.005489528 -0.04506069 0.005832493 -0.04506069 0.005832493 -0.0400809 0.005489528 -0.04082065 0.005658507 -0.04506069 0.005832493 -0.04082065 0.005658507 -0.04155313 0.005857706 -0.04506069 0.005832493 -0.04155313 0.005857706 -0.04520267 0.005903542 -0.04520267 0.005903542 -0.04155313 0.005857706 -0.04227685 0.006086468 -0.04520267 0.005903542 -0.04227685 0.006086468 -0.04299086 0.006344676 -0.04520267 0.005903542 -0.04299086 0.006344676 -0.04369348 0.006631672 -0.04520267 0.005903542 -0.04369348 0.006631672 -0.04438382 0.006947219 -0.04520267 0.005903542 -0.04438382 0.006947219 -0.04520267 0.00736171 -0.04520267 0.00736171 -0.04438382 0.006947219 -0.04506069 0.007290661 0.01749753 0.03876847 0 0.03800946 0.01749753 0.03800946 0 0.03800946 0.01749753 0.03876847 0 0.03876847 0.03707087 0.003659248 0.03645372 0.005106389 0.03645372 0.003647983 0.03645372 0.005106389 0.03707087 0.003659248 0.03782868 0.003704488 0.03645372 0.005106389 0.03782868 0.003704488 0.03858399 0.003780782 0.03645372 0.005106389 0.03858399 0.003780782 0.03933537 0.003888309 0.03645372 0.005106389 0.03933537 0.003888309 0.04008173 0.004026532 0.03645372 0.005106389 0.04008173 0.004026532 0.0408219 0.004195511 0.03645372 0.005106389 0.0408219 0.004195511 0.04155457 0.004394769 0.03645372 0.005106389 0.04155457 0.004394769 0.04227823 0.004624009 0.03645372 0.005106389 0.04227823 0.004624009 0.04299205 0.004882872 0.03645372 0.005106389 0.04299205 0.004882872 0.04369425 0.005170941 0.03645372 0.005106389 0.04369425 0.005170941 0.03707069 0.005118966 0.03707069 0.005118966 0.04369425 0.005170941 0.03782802 0.005165398 0.03782802 0.005165398 0.04369425 0.005170941 0.03858315 0.005242824 0.03858315 0.005242824 0.04369425 0.005170941 0.04438436 0.00548768 0.03858315 0.005242824 0.04438436 0.00548768 0.03933465 0.005350828 0.03933465 0.005350828 0.04438436 0.00548768 0.0400809 0.005489528 0.0400809 0.005489528 0.04438436 0.00548768 0.04506069 0.005832493 0.0400809 0.005489528 0.04506069 0.005832493 0.04082065 0.005658507 0.04082065 0.005658507 0.04506069 0.005832493 0.04155313 0.005857706 0.04155313 0.005857706 0.04506069 0.005832493 0.04520267 0.005903542 0.04155313 0.005857706 0.04520267 0.005903542 0.04227685 0.006086468 0.04227685 0.006086468 0.04520267 0.005903542 0.04299086 0.006344676 0.04299086 0.006344676 0.04520267 0.005903542 0.04369348 0.006631672 0.04369348 0.006631672 0.04520267 0.005903542 0.04438382 0.006947219 0.04438382 0.006947219 0.04520267 0.005903542 0.04520267 0.00736171 0.04438382 0.006947219 0.04520267 0.00736171 0.04506069 0.007290661 -0.004593491 0.03745728 -0.007870852 0.03731447 -0.004705548 0.03731447 -0.007870852 0.03731447 -0.004593491 0.03745728 -0.007982969 0.03745728 -0.007982969 0.03745728 -0.004593491 0.03745728 -0.008208096 0.03762745 -0.008208096 0.03762745 -0.004593491 0.03745728 -0.004368305 0.03762745 -0.008208096 0.03762745 -0.004368305 0.03762745 -0.004107296 0.03773432 -0.008208096 0.03762745 -0.004107296 0.03773432 -0.008469223 0.03773432 -0.008469223 0.03773432 -0.004107296 0.03773432 -0.008748888 0.03777074 -0.008748888 0.03777074 -0.004107296 0.03773432 -0.003827631 0.03777074 0 0.03731447 -0.003061652 0.03745728 -0.002949595 0.03731447 -0.003061652 0.03745728 0 0.03731447 0 0.03807348 -0.003061652 0.03745728 0 0.03807348 -0.003286838 0.03762745 -0.003286838 0.03762745 0 0.03807348 -0.003547966 0.03773432 -0.003547966 0.03773432 0 0.03807348 -0.003827631 0.03777074 -0.003827631 0.03777074 0 0.03807348 -0.0136699 0.03777074 -0.0136699 0.03777074 0 0.03807348 -0.01749753 0.03807348 -0.01454818 0.03731447 -0.01749753 0.03807348 -0.01749753 0.03731447 -0.01749753 0.03807348 -0.01454818 0.03731447 -0.01443576 0.03745728 -0.01749753 0.03807348 -0.01443576 0.03745728 -0.01421082 0.03762745 -0.01749753 0.03807348 -0.01421082 0.03762745 -0.01394981 0.03773432 -0.01749753 0.03807348 -0.01394981 0.03773432 -0.0136699 0.03777074 -0.009514749 0.03745728 -0.01279211 0.03731447 -0.009626865 0.03731447 -0.01279211 0.03731447 -0.009514749 0.03745728 -0.01290398 0.03745728 -0.01290398 0.03745728 -0.009514749 0.03745728 -0.009289622 0.03762745 -0.01290398 0.03745728 -0.009289622 0.03762745 -0.01312935 0.03762745 -0.01312935 0.03762745 -0.009289622 0.03762745 -0.009028553 0.03773432 -0.01312935 0.03762745 -0.009028553 0.03773432 -0.01339048 0.03773432 -0.01339048 0.03773432 -0.009028553 0.03773432 -0.008748888 0.03777074 -0.01339048 0.03773432 -0.008748888 0.03777074 -0.0136699 0.03777074 -0.0136699 0.03777074 -0.008748888 0.03777074 -0.003827631 0.03777074 -0.004921257 0.0365504 -0.007652521 0.03640842 -0.004923999 0.03640842 -0.007652521 0.03640842 -0.004921257 0.0365504 -0.007655203 0.0365504 -0.007655203 0.0365504 -0.004921257 0.0365504 -0.004879415 0.03682935 -0.007655203 0.0365504 -0.004879415 0.03682935 -0.007696986 0.03682935 -0.007696986 0.03682935 -0.004879415 0.03682935 -0.004767656 0.03708839 -0.007696986 0.03682935 -0.004767656 0.03708839 -0.007808685 0.03708839 -0.007808685 0.03708839 -0.004767656 0.03708839 -0.004705548 0.03716737 -0.007808685 0.03708839 -0.004705548 0.03716737 -0.007870852 0.03716737 0.004923999 -0.03622555 0.007604062 -0.03373527 0.004972398 -0.03373527 0.007604062 -0.03373527 0.004923999 -0.03622555 0.007652521 -0.03622555 0.004972398 -0.03353691 0.007555723 -0.03104639 0.005020797 -0.03104639 0.007555723 -0.03104639 0.004972398 -0.03353691 0.007604062 -0.03353691 0.005069077 -0.02832466 0.007555723 -0.03081518 0.007507443 -0.02832466 0.007555723 -0.03081518 0.005069077 -0.02832466 0.005020797 -0.03081518 0.005069077 -0.02806311 0.007459342 -0.02557289 0.005117118 -0.02557289 0.007459342 -0.02557289 0.005069077 -0.02806311 0.007507443 -0.02806311 0.005117118 -0.02528429 0.007411301 -0.02279371 0.0051651 -0.02279371 0.007411301 -0.02279371 0.005117118 -0.02528429 0.007459342 -0.02528429 0.005212724 -0.0199902 0.007411301 -0.02248072 0.007363677 -0.0199902 0.007411301 -0.02248072 0.005212724 -0.0199902 0.0051651 -0.02248072 0.005260169 -0.01716506 0.007363677 -0.01965558 0.007316291 -0.01716506 0.007363677 -0.01965558 0.005260169 -0.01716506 0.005212724 -0.01965558 0.005307257 -0.01432096 0.007316291 -0.01681149 0.007269263 -0.01432096 0.007316291 -0.01681149 0.005307257 -0.01432096 0.005260169 -0.01681149 0.005353868 -0.01146125 0.007269263 -0.01395177 0.007222533 -0.01146125 0.007269263 -0.01395177 0.005353868 -0.01146125 0.005307257 -0.01395177 0.005353868 -0.01107937 0.007176399 -0.00858885 0.005400121 -0.00858885 0.007176399 -0.00858885 0.005353868 -0.01107937 0.007222533 -0.01107937 0.005400121 -0.008196711 0.007130563 -0.005706191 0.005445778 -0.005706191 0.007130563 -0.005706191 0.005400121 -0.008196711 0.007176399 -0.008196711 0.005491018 -0.002816379 0.007130563 -0.005306959 0.007085442 -0.002816379 0.007130563 -0.005306959 0.005491018 -0.002816379 0.005445778 -0.005306959 0.005587518 6.67286e-4 0.007017314 5.169e-4 0.006988942 6.67286e-4 0.007017314 5.169e-4 0.005587518 6.67286e-4 0.005559146 5.169e-4 0.007017314 5.169e-4 0.005559146 5.169e-4 0.005491018 -0.003194868 0.007017314 5.169e-4 0.005491018 -0.003194868 0.007085442 -0.003194868 0.002484202 0.01197981 0.002339482 0.01130062 0.002484202 0.01123654 0.002339482 0.01130062 0.002484202 0.01197981 -0.00123322 0.01312333 -0.00123322 0.01312333 0.002484202 0.01197981 0.002339482 0.01202946 -0.007017314 0.001286864 -0.005587518 0.001442492 -0.006988942 0.001442492 -0.005587518 0.001442492 -0.007017314 0.001286864 -0.005559146 0.001286864 -0.005559146 0.001286864 -0.007017314 0.001286864 -0.007085442 -0.002554893 -0.005559146 0.001286864 -0.007085442 -0.002554893 -0.005491018 -0.002554893 -0.007130146 -0.005270481 -0.005491018 -0.002769172 -0.007085442 -0.002769172 -0.005491018 -0.002769172 -0.007130146 -0.005270481 -0.005446255 -0.005270481 -0.007175505 -0.008195936 -0.005446255 -0.005694568 -0.007130146 -0.005694568 -0.005446255 -0.005694568 -0.007175505 -0.008195936 -0.005400955 -0.008195936 -0.00722146 -0.01111203 -0.005400955 -0.008610725 -0.007175505 -0.008610725 -0.005400955 -0.008610725 -0.00722146 -0.01111203 -0.005354881 -0.01111203 -0.007268071 -0.01401484 -0.005354881 -0.01151365 -0.00722146 -0.01151365 -0.005354881 -0.01151365 -0.007268071 -0.01401484 -0.005308449 -0.01401484 -0.007315099 -0.01690059 -0.005308449 -0.01439929 -0.007268071 -0.01439929 -0.005308449 -0.01439929 -0.007315099 -0.01690059 -0.005261421 -0.01690059 -0.007315099 -0.01726442 -0.005213916 -0.01976573 -0.005261421 -0.01726442 -0.005213916 -0.01976573 -0.007315099 -0.01726442 -0.007362544 -0.01976573 -0.007410347 -0.02260589 -0.005213916 -0.02010434 -0.007362544 -0.02010434 -0.005213916 -0.02010434 -0.007410347 -0.02260589 -0.005166113 -0.02260589 -0.007458448 -0.0254172 -0.005166113 -0.02291589 -0.007410347 -0.02291589 -0.005166113 -0.02291589 -0.007458448 -0.0254172 -0.005118072 -0.0254172 -0.007506728 -0.02819669 -0.005118072 -0.02569544 -0.007458448 -0.02569544 -0.005118072 -0.02569544 -0.007506728 -0.02819669 -0.005069732 -0.02819669 -0.007555246 -0.03093969 -0.005069732 -0.02843838 -0.007506728 -0.02843838 -0.005069732 -0.02843838 -0.007555246 -0.03093969 -0.005021214 -0.03093969 -0.007603824 -0.03364342 -0.005021214 -0.03114211 -0.007555246 -0.03114211 -0.005021214 -0.03114211 -0.007603824 -0.03364342 -0.004972577 -0.03364342 -0.004805982 0.01130062 -0.004950702 0.01197981 -0.004950702 0.01123654 -0.004950702 0.01197981 -0.004805982 0.01130062 -0.00123322 0.01312333 -0.004950702 0.01197981 -0.00123322 0.01312333 -0.004805982 0.01202946 -0.002682626 -0.03380227 -2.76001e-6 -0.03630352 -5.13962e-5 -0.03380227 -2.76001e-6 -0.03630352 -0.002682626 -0.03380227 -0.002731204 -0.03630352 -0.02144241 0.005046308 -0.03386718 0.005143225 -0.03635782 0.005103528 -0.03386718 0.005143225 -0.02144241 0.005046308 -0.01900184 0.00559628 -0.03386718 0.005143225 -0.01900184 0.00559628 -0.03137922 0.005262315 -0.03137922 0.005262315 -0.01900184 0.00559628 -0.02889615 0.005460739 -0.02889615 0.005460739 -0.01900184 0.00559628 -0.02642071 0.005738139 -0.02642071 0.005738139 -0.01900184 0.00559628 -0.01658302 0.006235122 -0.02642071 0.005738139 -0.01658302 0.006235122 -0.02395528 0.006094396 -0.02395528 0.006094396 -0.01658302 0.006235122 -0.02150255 0.006529033 -0.02150255 0.006529033 -0.01658302 0.006235122 -0.01418924 0.006962001 -0.02150255 0.006529033 -0.01418924 0.006962001 -0.0190649 0.007041752 -0.0190649 0.007041752 -0.01418924 0.006962001 -0.01182359 0.007775843 -0.0190649 0.007041752 -0.01182359 0.007775843 -0.01664489 0.007631838 -0.01664489 0.007631838 -0.01182359 0.007775843 -0.01424485 0.008298873 -0.01424485 0.008298873 -0.01182359 0.007775843 -0.009489297 0.008675634 -0.01424485 0.008298873 -0.009489297 0.008675634 -0.01186734 0.009042024 -0.01186734 0.009042024 -0.009489297 0.008675634 -0.007189512 0.009660243 -0.01186734 0.009042024 -0.007189512 0.009660243 -0.009514808 0.009860634 -0.009514808 0.009860634 -0.007189512 0.009660243 -0.003685355 0.01123654 -0.009514808 0.009860634 -0.003685355 0.01123654 -0.007189512 0.01075381 -0.007189512 0.01075381 -0.003685355 0.01123654 -0.003685355 0.01197981 -0.03385627 0.003650844 -0.03649979 0.003647983 -0.03635782 0.00364536 -0.03649979 0.003647983 -0.03385627 0.003650844 -0.03649979 0.005106389 -0.03649979 0.005106389 -0.03385627 0.003650844 -0.03135639 0.00374794 -0.03649979 0.005106389 -0.03135639 0.00374794 -0.02886176 0.00393635 -0.03649979 0.005106389 -0.02886176 0.00393635 -0.02637565 0.004215717 -0.03649979 0.005106389 -0.02637565 0.004215717 -0.0239014 0.004585981 -0.03649979 0.005106389 -0.0239014 0.004585981 -0.03635782 0.005103528 -0.03635782 0.005103528 -0.0239014 0.004585981 -0.02144241 0.005046308 -0.03645622 0.005106389 -0.03673851 0.003653109 -0.03645622 0.003647983 -0.03673851 0.003653109 -0.03645622 0.005106389 -0.03673851 0.005112111 -0.03482753 0.005112111 -0.03510946 0.003657758 -0.03482753 0.003653109 -0.03510946 0.003657758 -0.03482753 0.005112111 -0.03510946 0.005117297 0.03644675 0.003647983 0.0338031 0.003650844 0.03630489 0.00364536 0.0338031 0.003650844 0.03644675 0.003647983 0.03644675 0.005106389 0.0338031 0.003650844 0.03644675 0.005106389 0.03130298 0.00374794 0.03130298 0.00374794 0.03644675 0.005106389 0.02880859 0.00393635 0.02880859 0.00393635 0.03644675 0.005106389 0.02632248 0.004215717 0.02632248 0.004215717 0.03644675 0.005106389 0.02384823 0.004585981 0.02384823 0.004585981 0.03644675 0.005106389 0.03630489 0.005103528 0.02384823 0.004585981 0.03630489 0.005103528 0.02138924 0.005046308 0.02138924 0.005046308 0.03381425 0.005143225 0.01894867 0.00559628 0.03381425 0.005143225 0.02138924 0.005046308 0.03630489 0.005103528 0.01894867 0.00559628 0.03381425 0.005143225 0.03132605 0.005262315 0.01894867 0.00559628 0.03132605 0.005262315 0.02884298 0.005460739 0.01894867 0.00559628 0.02884298 0.005460739 0.02636754 0.005738139 0.01894867 0.00559628 0.02636754 0.005738139 0.01652967 0.006235122 0.01652967 0.006235122 0.02636754 0.005738139 0.02390193 0.006094396 0.01652967 0.006235122 0.02390193 0.006094396 0.02144914 0.006529033 0.01652967 0.006235122 0.02144914 0.006529033 0.01413583 0.006962001 0.01413583 0.006962001 0.02144914 0.006529033 0.01901179 0.007041752 0.01413583 0.006962001 0.01901179 0.007041752 0.01177018 0.007775843 0.01177018 0.007775843 0.01901179 0.007041752 0.01659148 0.007631838 0.01177018 0.007775843 0.01659148 0.007631838 0.0141915 0.008298873 0.01177018 0.007775843 0.0141915 0.008298873 0.00943619 0.008675634 0.00943619 0.008675634 0.0141915 0.008298873 0.01181399 0.009042024 0.00943619 0.008675634 0.01181399 0.009042024 0.007136285 0.009660243 0.007136285 0.009660243 0.01181399 0.009042024 0.009461641 0.009860634 0.007136285 0.009660243 0.009461641 0.009860634 0.003632247 0.01123654 0.003632247 0.01123654 0.009461641 0.009860634 0.007136285 0.01075381 0.003632247 0.01123654 0.007136285 0.01075381 0.003632247 0.01197981 0 0.0365504 -0.002731204 0.03640842 -2.76001e-6 0.03640842 -0.002731204 0.03640842 0 0.0365504 -0.002734005 0.0365504 -0.002734005 0.0365504 0 0.0365504 0 0.03716737 -0.002734005 0.0365504 0 0.03716737 -0.002775788 0.03682935 -0.002775788 0.03682935 0 0.03716737 -0.002887487 0.03708839 -0.002887487 0.03708839 0 0.03716737 -0.002949595 0.03716737 -0.009845256 0.03640842 -0.01257652 0.0365504 -0.01257354 0.03640842 -0.01257652 0.0365504 -0.009845256 0.03640842 -0.009842514 0.0365504 -0.01257652 0.0365504 -0.009842514 0.0365504 -0.0126183 0.03682935 -0.0126183 0.03682935 -0.009842514 0.0365504 -0.009800672 0.03682935 -0.0126183 0.03682935 -0.009800672 0.03682935 -0.01273006 0.03708839 -0.01273006 0.03708839 -0.009800672 0.03682935 -0.009688973 0.03708839 -0.01273006 0.03708839 -0.009688973 0.03708839 -0.01279211 0.03716737 -0.01279211 0.03716737 -0.009688973 0.03708839 -0.009626865 0.03716737 0.03012782 0.003657758 0.02984577 0.005112111 0.02984577 0.003653109 0.02984577 0.005112111 0.03012782 0.003657758 0.03012782 0.005117297 0.03487473 0.003653109 0.03459268 0.005106389 0.03459268 0.003647983 0.03459268 0.005106389 0.03487473 0.003653109 0.03487473 0.005112111 0.0362553 0.003647983 0.03361177 0.003650844 0.03611356 0.00364536 0.03361177 0.003650844 0.0362553 0.003647983 0.0362553 0.005106389 0.03361177 0.003650844 0.0362553 0.005106389 0.03111189 0.00374794 0.03111189 0.00374794 0.0362553 0.005106389 0.02861726 0.00393635 0.02861726 0.00393635 0.0362553 0.005106389 0.02613115 0.004215717 0.02613115 0.004215717 0.0362553 0.005106389 0.0236569 0.004585981 0.0236569 0.004585981 0.0362553 0.005106389 0.03611356 0.005103528 0.0236569 0.004585981 0.03611356 0.005103528 0.02119791 0.005046308 0.02119791 0.005046308 0.03362286 0.005143225 0.01875734 0.00559628 0.03362286 0.005143225 0.02119791 0.005046308 0.03611356 0.005103528 0.01875734 0.00559628 0.03362286 0.005143225 0.03113472 0.005262315 0.01875734 0.00559628 0.03113472 0.005262315 0.02865165 0.005460739 0.01875734 0.00559628 0.02865165 0.005460739 0.02617621 0.005738139 0.01875734 0.00559628 0.02617621 0.005738139 0.01633828 0.006235122 0.01633828 0.006235122 0.02617621 0.005738139 0.02371054 0.006094396 0.01633828 0.006235122 0.02371054 0.006094396 0.02125805 0.006529033 0.01633828 0.006235122 0.02125805 0.006529033 0.01394474 0.006962001 0.01394474 0.006962001 0.02125805 0.006529033 0.0188204 0.007041752 0.01394474 0.006962001 0.0188204 0.007041752 0.01157885 0.007775843 0.01157885 0.007775843 0.0188204 0.007041752 0.01640015 0.007631838 0.01157885 0.007775843 0.01640015 0.007631838 0.01400011 0.008298873 0.01157885 0.007775843 0.01400011 0.008298873 0.009244799 0.008675634 0.009244799 0.008675634 0.01400011 0.008298873 0.0116226 0.009042024 0.009244799 0.008675634 0.0116226 0.009042024 0.006944954 0.009660243 0.006944954 0.009660243 0.0116226 0.009042024 0.00927031 0.009860634 0.006944954 0.009660243 0.00927031 0.009860634 0.003440916 0.01123654 0.003440916 0.01123654 0.00927031 0.009860634 0.006944954 0.01075381 0.003440916 0.01123654 0.006944954 0.01075381 0.003440916 0.01197981 -0.01257354 -0.03630352 -0.009893894 -0.03380227 -0.01252514 -0.03380227 -0.009893894 -0.03380227 -0.01257354 -0.03630352 -0.009845256 -0.03630352 -0.02163374 0.005046308 -0.03405869 0.005143225 -0.03654927 0.005103528 -0.03405869 0.005143225 -0.02163374 0.005046308 -0.01919317 0.00559628 -0.03405869 0.005143225 -0.01919317 0.00559628 -0.03157061 0.005262315 -0.03157061 0.005262315 -0.01919317 0.00559628 -0.02908754 0.005460739 -0.02908754 0.005460739 -0.01919317 0.00559628 -0.02661204 0.005738139 -0.02661204 0.005738139 -0.01919317 0.00559628 -0.01677441 0.006235122 -0.02661204 0.005738139 -0.01677441 0.006235122 -0.02414667 0.006094396 -0.02414667 0.006094396 -0.01677441 0.006235122 -0.02169388 0.006529033 -0.02169388 0.006529033 -0.01677441 0.006235122 -0.01438057 0.006962001 -0.02169388 0.006529033 -0.01438057 0.006962001 -0.01925629 0.007041752 -0.01925629 0.007041752 -0.01438057 0.006962001 -0.01201468 0.007775843 -0.01925629 0.007041752 -0.01201468 0.007775843 -0.01683622 0.007631838 -0.01683622 0.007631838 -0.01201468 0.007775843 -0.01443624 0.008298873 -0.01443624 0.008298873 -0.01201468 0.007775843 -0.009680688 0.008675634 -0.01443624 0.008298873 -0.009680688 0.008675634 -0.01205873 0.009042024 -0.01205873 0.009042024 -0.009680688 0.008675634 -0.007380843 0.009660243 -0.01205873 0.009042024 -0.007380843 0.009660243 -0.009706139 0.009860634 -0.009706139 0.009860634 -0.007380843 0.009660243 -0.003876686 0.01123654 -0.009706139 0.009860634 -0.003876686 0.01123654 -0.007380843 0.01075381 -0.007380843 0.01075381 -0.003876686 0.01123654 -0.003876686 0.01197981 -0.0340476 0.003650844 -0.03669112 0.003647983 -0.03654927 0.00364536 -0.03669112 0.003647983 -0.0340476 0.003650844 -0.03669112 0.005106389 -0.03669112 0.005106389 -0.0340476 0.003650844 -0.03154772 0.00374794 -0.03669112 0.005106389 -0.03154772 0.00374794 -0.02905309 0.00393635 -0.03669112 0.005106389 -0.02905309 0.00393635 -0.02656698 0.004215717 -0.03669112 0.005106389 -0.02656698 0.004215717 -0.02409273 0.004585981 -0.03669112 0.005106389 -0.02409273 0.004585981 -0.03654927 0.005103528 -0.03654927 0.005103528 -0.02409273 0.004585981 -0.02163374 0.005046308 -0.03791487 0.005106389 -0.03819692 0.003653109 -0.03791487 0.003647983 -0.03819692 0.003653109 -0.03791487 0.005106389 -0.03819692 0.005112111 -0.03872627 0.005112111 -0.0390082 0.003657758 -0.03872627 0.003653109 -0.0390082 0.003657758 -0.03872627 0.005112111 -0.0390082 0.005117297 -0.01476377 0.0365504 -0.01749503 0.03640842 -0.01476651 0.03640842 -0.01749503 0.03640842 -0.01476377 0.0365504 -0.01749753 0.0365504 -0.01749753 0.0365504 -0.01476377 0.0365504 -0.01472193 0.03682935 -0.01749753 0.0365504 -0.01472193 0.03682935 -0.01749753 0.03716737 -0.01749753 0.03716737 -0.01472193 0.03682935 -0.01461023 0.03708839 -0.01749753 0.03716737 -0.01461023 0.03708839 -0.01454818 0.03716737 0.02817845 0.003657758 0.0278964 0.005112111 0.0278964 0.003653109 0.0278964 0.005112111 0.02817845 0.003657758 0.02817845 0.005117297 -0.01749503 -0.03630352 -0.01481515 -0.03380227 -0.01744616 -0.03380227 -0.01481515 -0.03380227 -0.01749503 -0.03630352 -0.01476651 -0.03630352 -0.02172935 0.005046308 -0.03415441 0.005143225 -0.03664505 0.005103528 -0.03415441 0.005143225 -0.02172935 0.005046308 -0.01928859 0.00559628 -0.03415441 0.005143225 -0.01928859 0.00559628 -0.0316661 0.005262315 -0.0316661 0.005262315 -0.01928859 0.00559628 -0.02918303 0.005460739 -0.02918303 0.005460739 -0.01928859 0.00559628 -0.02670753 0.005738139 -0.02670753 0.005738139 -0.01928859 0.00559628 -0.01687008 0.006235122 -0.02670753 0.005738139 -0.01687008 0.006235122 -0.02424234 0.006094396 -0.02424234 0.006094396 -0.01687008 0.006235122 -0.02178955 0.006529033 -0.02178955 0.006529033 -0.01687008 0.006235122 -0.01447618 0.006962001 -0.02178955 0.006529033 -0.01447618 0.006962001 -0.01935184 0.007041752 -0.01935184 0.007041752 -0.01447618 0.006962001 -0.01211059 0.007775843 -0.01935184 0.007041752 -0.01211059 0.007775843 -0.01693189 0.007631838 -0.01693189 0.007631838 -0.01211059 0.007775843 -0.01453191 0.008298873 -0.01453191 0.008298873 -0.01211059 0.007775843 -0.009776353 0.008675634 -0.01453191 0.008298873 -0.009776353 0.008675634 -0.0121544 0.009042024 -0.0121544 0.009042024 -0.009776353 0.008675634 -0.007476508 0.009660243 -0.0121544 0.009042024 -0.007476508 0.009660243 -0.009801805 0.009860634 -0.009801805 0.009860634 -0.007476508 0.009660243 -0.003972411 0.01123654 -0.009801805 0.009860634 -0.003972411 0.01123654 -0.007476508 0.01075381 -0.007476508 0.01075381 -0.003972411 0.01123654 -0.003972411 0.01197981 -0.03414309 0.003650844 -0.03678703 0.003647983 -0.03664505 0.00364536 -0.03678703 0.003647983 -0.03414309 0.003650844 -0.03678703 0.005106389 -0.03678703 0.005106389 -0.03414309 0.003650844 -0.03164339 0.00374794 -0.03678703 0.005106389 -0.03164339 0.00374794 -0.02914851 0.00393635 -0.03678703 0.005106389 -0.02914851 0.00393635 -0.0266624 0.004215717 -0.03678703 0.005106389 -0.0266624 0.004215717 -0.02418828 0.004585981 -0.03678703 0.005106389 -0.02418828 0.004585981 -0.03664505 0.005103528 -0.03664505 0.005103528 -0.02418828 0.004585981 -0.02172935 0.005046308 0.03414577 0.003653109 0.03386372 0.005106389 0.03386372 0.003647983 0.03386372 0.005106389 0.03414577 0.003653109 0.03414577 0.005112111 0.03615987 0.003647983 0.03351593 0.003650844 0.03601789 0.00364536 0.03351593 0.003650844 0.03615987 0.003647983 0.03615987 0.005106389 0.03351593 0.003650844 0.03615987 0.005106389 0.03101623 0.00374794 0.03101623 0.00374794 0.03615987 0.005106389 0.02852129 0.00393635 0.02852129 0.00393635 0.03615987 0.005106389 0.02603524 0.004215717 0.02603524 0.004215717 0.03615987 0.005106389 0.02356112 0.004585981 0.02356112 0.004585981 0.03615987 0.005106389 0.03601789 0.005103528 0.02356112 0.004585981 0.03601789 0.005103528 0.02110219 0.005046308 0.02110219 0.005046308 0.03352719 0.005143225 0.01866143 0.00559628 0.03352719 0.005143225 0.02110219 0.005046308 0.03601789 0.005103528 0.01866143 0.00559628 0.03352719 0.005143225 0.03103888 0.005262315 0.01866143 0.00559628 0.03103888 0.005262315 0.02855587 0.005460739 0.01866143 0.00559628 0.02855587 0.005460739 0.02608031 0.005738139 0.01866143 0.00559628 0.02608031 0.005738139 0.01624286 0.006235122 0.01624286 0.006235122 0.02608031 0.005738139 0.02361512 0.006094396 0.01624286 0.006235122 0.02361512 0.006094396 0.02116239 0.006529033 0.01624286 0.006235122 0.02116239 0.006529033 0.01384902 0.006962001 0.01384902 0.006962001 0.02116239 0.006529033 0.01872462 0.007041752 0.01384902 0.006962001 0.01872462 0.007041752 0.01148343 0.007775843 0.01148343 0.007775843 0.01872462 0.007041752 0.01630467 0.007631838 0.01148343 0.007775843 0.01630467 0.007631838 0.01390469 0.008298873 0.01148343 0.007775843 0.01390469 0.008298873 0.009149134 0.008675634 0.009149134 0.008675634 0.01390469 0.008298873 0.01152718 0.009042024 0.009149134 0.008675634 0.01152718 0.009042024 0.006849348 0.009660243 0.006849348 0.009660243 0.01152718 0.009042024 0.009174585 0.009860634 0.006849348 0.009660243 0.009174585 0.009860634 0.003345251 0.01123654 0.003345251 0.01123654 0.009174585 0.009860634 0.006849348 0.01075381 0.003345251 0.01123654 0.006849348 0.01075381 0.003345251 0.01197981 0 0.03815776 -0.01749753 0.03891652 -0.01749753 0.03815776 -0.01749753 0.03891652 0 0.03815776 0 0.03891652 0 0.03969568 -0.01749753 0.03893673 0 0.03893673 -0.01749753 0.03893673 0 0.03969568 -0.01749753 0.03969568 0 0.0396502 -0.01749753 0.04040902 -0.01749753 0.0396502 -0.01749753 0.04040902 0 0.0396502 0 0.04040902 0 0.04029697 -0.01749753 0.04105573 -0.01749753 0.04029697 -0.01749753 0.04105573 0 0.04029697 0 0.04105573 0 0.04163473 -0.01749753 0.04087591 0 0.04087591 -0.01749753 0.04087591 0 0.04163473 -0.01749753 0.04163473 0 0.04214513 -0.01749753 0.04138588 0 0.04138588 -0.01749753 0.04138588 0 0.04214513 -0.01749753 0.04214513 0 0.04258573 -0.01749753 0.04182666 0 0.04182666 -0.01749753 0.04182666 0 0.04258573 -0.01749753 0.04258573 0 0.04295593 -0.01749753 0.04219681 0 0.04219681 -0.01749753 0.04219681 0 0.04295593 -0.01749753 0.04295593 0 0.04325515 -0.01749753 0.04249614 0 0.04249614 -0.01749753 0.04249614 0 0.04325515 -0.01749753 0.04325515 0 0.04348284 -0.01749753 0.04272389 0 0.04272389 -0.01749753 0.04272389 0 0.04348284 -0.01749753 0.04348284 0 0.04372251 -0.01749753 0.04356408 0 0.04356408 -0.01749753 0.04356408 0 0.04372251 -0.01749753 0.04372251 -0.01749753 0.04372251 0 0.04372251 -1.58532e-5 0.04431515 -0.01749753 0.04372251 -1.58532e-5 0.04431515 -0.01748192 0.04431515 -0.01748192 0.04431515 -1.58532e-5 0.04431515 -0.01743417 0.04490596 -0.01743417 0.04490596 -1.58532e-5 0.04431515 -6.3356e-5 0.04490596 -0.01743417 0.04490596 -6.3356e-5 0.04490596 -0.01735544 0.04549229 -0.01735544 0.04549229 -6.3356e-5 0.04490596 -1.42339e-4 0.04549229 -0.01735544 0.04549229 -1.42339e-4 0.04549229 -0.01724529 0.04607224 -0.01724529 0.04607224 -1.42339e-4 0.04549229 -2.52519e-4 0.04607224 -0.01724529 0.04607224 -2.52519e-4 0.04607224 -3.93503e-4 0.04664385 -0.01724529 0.04607224 -3.93503e-4 0.04664385 -0.01710402 0.04664385 -0.01710402 0.04664385 -3.93503e-4 0.04664385 -4.4867e-4 0.04682457 -0.01710402 0.04664385 -4.4867e-4 0.04682457 -0.01704913 0.04682457 -0.04465913 0.00736171 -0.04518949 0.006168544 -0.04465913 0.005903542 -0.04518949 0.006168544 -0.04465913 0.00736171 -0.04518949 0.007626712 0.01749753 0.0429117 0 0.04307061 0 0.0429117 0 0.04307061 0.01749753 0.0429117 0.01749753 0.04307061 0 0.04307061 0.01749753 0.04307061 0.01748192 0.04366332 0 0.04307061 0.01748192 0.04366332 1.58532e-5 0.04366332 1.58532e-5 0.04366332 0.01748192 0.04366332 0.01743417 0.04425358 1.58532e-5 0.04366332 0.01743417 0.04425358 6.3356e-5 0.04425358 6.3356e-5 0.04425358 0.01743417 0.04425358 0.01735544 0.04483991 6.3356e-5 0.04425358 0.01735544 0.04483991 1.42339e-4 0.04483991 1.42339e-4 0.04483991 0.01735544 0.04483991 0.01724529 0.04542011 1.42339e-4 0.04483991 0.01724529 0.04542011 2.52519e-4 0.04542011 2.52519e-4 0.04542011 0.01724529 0.04542011 0.01710402 0.04599148 2.52519e-4 0.04542011 0.01710402 0.04599148 3.93503e-4 0.04599148 3.93503e-4 0.04599148 0.01710402 0.04599148 0.01704913 0.04617244 3.93503e-4 0.04599148 0.01704913 0.04617244 4.4867e-4 0.04617244 0.01749753 0.04279202 0 0.04203259 0.01749753 0.04203259 0 0.04203259 0.01749753 0.04279202 0 0.04279202 0.01749753 0.04262638 0 0.04186695 0.01749753 0.04186695 0 0.04186695 0.01749753 0.04262638 0 0.04262638 0.01749753 0.04238873 0 0.04162985 0.01749753 0.04162985 0 0.04162985 0.01749753 0.04238873 0 0.04238873 0.01749753 0.04208034 0 0.04132091 0.01749753 0.04132091 0 0.04132091 0.01749753 0.04208034 0 0.04208034 0.01749753 0.04170078 0 0.04094171 0.01749753 0.04094171 0 0.04094171 0.01749753 0.04170078 0 0.04170078 0.01749753 0.04049187 0 0.0412513 0 0.04049187 0 0.0412513 0.01749753 0.04049187 0.01749753 0.0412513 0.01749753 0.04073232 0 0.03997308 0.01749753 0.03997308 0 0.03997308 0.01749753 0.04073232 0 0.04073232 0.01749753 0.03938549 0 0.04014486 0 0.03938549 0 0.04014486 0.01749753 0.03938549 0.01749753 0.04014486 0.01749753 0.03873074 0 0.03948992 0 0.03873074 0 0.03948992 0.01749753 0.03873074 0.01749753 0.03948992 0.04571259 0.006168544 0.04518222 0.00736171 0.04518222 0.005903542 0.04518222 0.00736171 0.04571259 0.006168544 0.04571259 0.007626712 0.005587518 2.40273e-4 0.006988942 2.40273e-4 0.00628823 0.003910422 -0.005587518 0.00210762 -0.00628823 0.006056845 -0.006988942 0.00210762 -0.002682626 -0.03364342 -9.99958e-5 -0.03114211 -0.002633929 -0.03114211 -9.99958e-5 -0.03114211 -0.002682626 -0.03364342 -5.13962e-5 -0.03364342 -0.003840804 0.01130062 -0.003985643 0.01197981 -0.003985643 0.01123654 -0.003985643 0.01197981 -0.003840804 0.01130062 -2.68094e-4 0.01312333 -0.003985643 0.01197981 -2.68094e-4 0.01312333 -0.003840804 0.01202946 6.37941e-4 5.169e-4 0.002067685 6.67286e-4 6.6633e-4 6.67286e-4 0.002067685 6.67286e-4 6.37941e-4 5.169e-4 0.002095997 5.169e-4 0.002095997 5.169e-4 6.37941e-4 5.169e-4 0.002164185 -0.003194868 0.002164185 -0.003194868 6.37941e-4 5.169e-4 5.69819e-4 -0.003194868 5.69819e-4 -0.002816379 0.002209365 -0.005306959 0.002164185 -0.002816379 0.002209365 -0.005306959 5.69819e-4 -0.002816379 5.24614e-4 -0.005306959 4.78877e-4 -0.008196711 0.002209365 -0.005706191 5.24614e-4 -0.005706191 0.002209365 -0.005706191 4.78877e-4 -0.008196711 0.002255082 -0.008196711 4.78877e-4 -0.00858885 0.002301335 -0.01107937 0.002255082 -0.00858885 0.002301335 -0.01107937 4.78877e-4 -0.00858885 4.32657e-4 -0.01107937 4.32657e-4 -0.01146125 0.002347946 -0.01395177 0.002301335 -0.01146125 0.002347946 -0.01395177 4.32657e-4 -0.01146125 3.85999e-4 -0.01395177 3.38952e-4 -0.01681149 0.002347946 -0.01432096 3.85999e-4 -0.01432096 0.002347946 -0.01432096 3.38952e-4 -0.01681149 0.002394974 -0.01681149 2.91562e-4 -0.01965558 0.002394974 -0.01716506 3.38952e-4 -0.01716506 0.002394974 -0.01716506 2.91562e-4 -0.01965558 0.002442419 -0.01965558 2.91562e-4 -0.0199902 0.002490103 -0.02248072 0.002442419 -0.0199902 0.002490103 -0.02248072 2.91562e-4 -0.0199902 2.43879e-4 -0.02248072 1.9595e-4 -0.02528429 0.002490103 -0.02279371 2.43879e-4 -0.02279371 0.002490103 -0.02279371 1.9595e-4 -0.02528429 0.002538025 -0.02528429 1.47825e-4 -0.02806311 0.002538025 -0.02557289 1.9595e-4 -0.02557289 0.002538025 -0.02557289 1.47825e-4 -0.02806311 0.002586126 -0.02806311 9.95518e-5 -0.03081518 0.002586126 -0.02832466 1.47825e-4 -0.02832466 0.002586126 -0.02832466 9.95518e-5 -0.03081518 0.002634406 -0.03081518 9.95518e-5 -0.03104639 0.002682805 -0.03353691 0.002634406 -0.03104639 0.002682805 -0.03353691 9.95518e-5 -0.03104639 5.11806e-5 -0.03353691 2.76001e-6 -0.03622555 0.002682805 -0.03373527 5.11806e-5 -0.03373527 0.002682805 -0.03373527 2.76001e-6 -0.03622555 0.002731204 -0.03622555 -0.002633929 -0.03093969 -1.48494e-4 -0.02843838 -0.00258553 -0.02843838 -1.48494e-4 -0.02843838 -0.002633929 -0.03093969 -9.99958e-5 -0.03093969 -0.00258553 -0.02819669 -1.96826e-4 -0.02569544 -0.002537131 -0.02569544 -1.96826e-4 -0.02569544 -0.00258553 -0.02819669 -1.48494e-4 -0.02819669 -0.002537131 -0.0254172 -2.44927e-4 -0.02291589 -0.00248903 -0.02291589 -2.44927e-4 -0.02291589 -0.002537131 -0.0254172 -1.96826e-4 -0.0254172 -0.00248903 -0.02260589 -2.92732e-4 -0.02010434 -0.002441287 -0.02010434 -2.92732e-4 -0.02010434 -0.00248903 -0.02260589 -2.44927e-4 -0.02260589 -0.002393782 -0.01726442 -2.92732e-4 -0.01976573 -3.40178e-4 -0.01726442 -2.92732e-4 -0.01976573 -0.002393782 -0.01726442 -0.002441287 -0.01976573 -0.002393782 -0.01690059 -3.87201e-4 -0.01439929 -0.002346754 -0.01439929 -3.87201e-4 -0.01439929 -0.002393782 -0.01690059 -3.40178e-4 -0.01690059 -0.002346754 -0.01401484 -4.33739e-4 -0.01151365 -0.002300262 -0.01151365 -4.33739e-4 -0.01151365 -0.002346754 -0.01401484 -3.87201e-4 -0.01401484 -0.002300262 -0.01111203 -4.79728e-4 -0.008610725 -0.002254188 -0.008610725 -4.79728e-4 -0.008610725 -0.002300262 -0.01111203 -4.33739e-4 -0.01111203 -0.002254188 -0.008195936 -5.25109e-4 -0.005694568 -0.002208888 -0.005694568 -5.25109e-4 -0.005694568 -0.002254188 -0.008195936 -4.79728e-4 -0.008195936 -0.002208888 -0.005270481 -5.69819e-4 -0.002769172 -0.002164185 -0.002769172 -5.69819e-4 -0.002769172 -0.002208888 -0.005270481 -5.25109e-4 -0.005270481 -0.002095997 0.001286864 -6.6633e-4 0.001442492 -0.002067685 0.001442492 -6.6633e-4 0.001442492 -0.002095997 0.001286864 -6.37941e-4 0.001286864 -6.37941e-4 0.001286864 -0.002095997 0.001286864 -5.69819e-4 -0.002554893 -5.69819e-4 -0.002554893 -0.002095997 0.001286864 -0.002164185 -0.002554893 0.00344944 0.01197981 0.00330466 0.01130062 0.00344944 0.01123654 0.00330466 0.01130062 0.00344944 0.01197981 -2.68094e-4 0.01312333 -2.68094e-4 0.01312333 0.00344944 0.01197981 0.00330466 0.01202946 0.009845256 -0.03622555 0.01252532 -0.03373527 0.009893655 -0.03373527 0.01252532 -0.03373527 0.009845256 -0.03622555 0.01257354 -0.03622555 0.009942054 -0.03104639 0.01252532 -0.03353691 0.01247698 -0.03104639 0.01252532 -0.03353691 0.009942054 -0.03104639 0.009893655 -0.03353691 0.009990334 -0.02832466 0.01247698 -0.03081518 0.0124287 -0.02832466 0.01247698 -0.03081518 0.009990334 -0.02832466 0.009942054 -0.03081518 0.01003819 -0.02557289 0.0124287 -0.02806311 0.01238054 -0.02557289 0.0124287 -0.02806311 0.01003819 -0.02557289 0.009990334 -0.02806311 0.01008611 -0.02279371 0.01238054 -0.02528429 0.01233243 -0.02279371 0.01238054 -0.02528429 0.01008611 -0.02279371 0.01003819 -0.02528429 0.01013404 -0.0199902 0.01233243 -0.02248072 0.01228499 -0.0199902 0.01233243 -0.02248072 0.01013404 -0.0199902 0.01008611 -0.02248072 0.01013404 -0.01965558 0.01223737 -0.01716506 0.01018118 -0.01716506 0.01223737 -0.01716506 0.01013404 -0.01965558 0.01228499 -0.01965558 0.01022851 -0.01432096 0.01223737 -0.01681149 0.01219052 -0.01432096 0.01223737 -0.01681149 0.01022851 -0.01432096 0.01018118 -0.01681149 0.01027488 -0.01146125 0.01219052 -0.01395177 0.01214385 -0.01146125 0.01219052 -0.01395177 0.01027488 -0.01146125 0.01022851 -0.01395177 0.01032114 -0.00858885 0.01214385 -0.01107937 0.01209741 -0.00858885 0.01214385 -0.01107937 0.01032114 -0.00858885 0.01027488 -0.01107937 0.01032114 -0.008196711 0.01205188 -0.005706191 0.01036685 -0.005706191 0.01205188 -0.005706191 0.01032114 -0.008196711 0.01209741 -0.008196711 0.01036685 -0.005306959 0.0120067 -0.002816379 0.01041209 -0.002816379 0.0120067 -0.002816379 0.01036685 -0.005306959 0.01205188 -0.005306959 0.01050859 6.67286e-4 0.01193857 5.169e-4 0.0119102 6.67286e-4 0.01193857 5.169e-4 0.01050859 6.67286e-4 0.01048046 5.169e-4 0.01193857 5.169e-4 0.01048046 5.169e-4 0.01041209 -0.003194868 0.01193857 5.169e-4 0.01041209 -0.003194868 0.0120067 -0.003194868 0.001519024 0.01197981 0.001374423 0.01130062 0.001519024 0.01123654 0.001374423 0.01130062 0.001519024 0.01197981 -0.002198338 0.01312333 -0.002198338 0.01312333 0.001519024 0.01197981 0.001374423 0.01202946 -0.01193857 0.001286864 -0.01050859 0.001442492 -0.0119102 0.001442492 -0.01050859 0.001442492 -0.01193857 0.001286864 -0.01048046 0.001286864 -0.01048046 0.001286864 -0.01193857 0.001286864 -0.0120067 -0.002554893 -0.01048046 0.001286864 -0.0120067 -0.002554893 -0.01041209 -0.002554893 -0.0120514 -0.005270481 -0.01041209 -0.002769172 -0.0120067 -0.002769172 -0.01041209 -0.002769172 -0.0120514 -0.005270481 -0.01036763 -0.005270481 -0.01209682 -0.008195936 -0.01036763 -0.005694568 -0.0120514 -0.005694568 -0.01036763 -0.005694568 -0.01209682 -0.008195936 -0.01032221 -0.008195936 -0.01214253 -0.01111203 -0.01032221 -0.008610725 -0.01209682 -0.008610725 -0.01032221 -0.008610725 -0.01214253 -0.01111203 -0.01027601 -0.01111203 -0.01218909 -0.01401484 -0.01027601 -0.01151365 -0.01214253 -0.01151365 -0.01027601 -0.01151365 -0.01218909 -0.01401484 -0.01022946 -0.01401484 -0.01223611 -0.01690059 -0.01022946 -0.01439929 -0.01218909 -0.01439929 -0.01022946 -0.01439929 -0.01223611 -0.01690059 -0.01018244 -0.01690059 -0.0122838 -0.01976573 -0.01018244 -0.01726442 -0.01223611 -0.01726442 -0.01018244 -0.01726442 -0.0122838 -0.01976573 -0.01013523 -0.01976573 -0.0123316 -0.02260589 -0.01013523 -0.02010434 -0.0122838 -0.02010434 -0.01013523 -0.02010434 -0.0123316 -0.02260589 -0.01008743 -0.02260589 -0.01237946 -0.0254172 -0.01008743 -0.02291589 -0.0123316 -0.02291589 -0.01008743 -0.02291589 -0.01237946 -0.0254172 -0.01003921 -0.0254172 -0.0124278 -0.02819669 -0.01003921 -0.02569544 -0.01237946 -0.02569544 -0.01003921 -0.02569544 -0.0124278 -0.02819669 -0.00999099 -0.02819669 -0.0124765 -0.03093969 -0.00999099 -0.02843838 -0.0124278 -0.02843838 -0.00999099 -0.02843838 -0.0124765 -0.03093969 -0.009942471 -0.03093969 -0.01252514 -0.03364342 -0.009942471 -0.03114211 -0.0124765 -0.03114211 -0.009942471 -0.03114211 -0.01252514 -0.03364342 -0.009893894 -0.03364342 -0.00577116 0.01130062 -0.00591588 0.01197981 -0.00591588 0.01123654 -0.00591588 0.01197981 -0.00577116 0.01130062 -0.002198338 0.01312333 -0.00591588 0.01197981 -0.002198338 0.01312333 -0.00577116 0.01202946 0.01476651 -0.03622555 0.01744639 -0.03373527 0.01481491 -0.03373527 0.01744639 -0.03373527 0.01476651 -0.03622555 0.01749503 -0.03622555 -0.01744616 -0.03364342 -0.01486361 -0.03114211 -0.01739782 -0.03114211 -0.01486361 -0.03114211 -0.01744616 -0.03364342 -0.01481515 -0.03364342 -0.01739782 -0.03093969 -0.014912 -0.02843838 -0.0173493 -0.02843838 -0.014912 -0.02843838 -0.01739782 -0.03093969 -0.01486361 -0.03093969 -0.0173493 -0.02819669 -0.01496034 -0.02569544 -0.01730096 -0.02569544 -0.01496034 -0.02569544 -0.0173493 -0.02819669 -0.014912 -0.02819669 -0.01730096 -0.0254172 -0.01500844 -0.02291589 -0.01725286 -0.02291589 -0.01500844 -0.02291589 -0.01730096 -0.0254172 -0.01496034 -0.0254172 -0.01725286 -0.02260589 -0.01505649 -0.02010434 -0.01720494 -0.02010434 -0.01505649 -0.02010434 -0.01725286 -0.02260589 -0.01500844 -0.02260589 -0.01715761 -0.01726442 -0.01505649 -0.01976573 -0.01510369 -0.01726442 -0.01505649 -0.01976573 -0.01715761 -0.01726442 -0.01720494 -0.01976573 -0.01715761 -0.01690059 -0.01515096 -0.01439929 -0.01711058 -0.01439929 -0.01515096 -0.01439929 -0.01715761 -0.01690059 -0.01510369 -0.01690059 -0.01711058 -0.01401484 -0.01519727 -0.01151365 -0.01706403 -0.01151365 -0.01519727 -0.01151365 -0.01711058 -0.01401484 -0.01515096 -0.01401484 -0.01706403 -0.01111203 -0.01524347 -0.008610725 -0.01701802 -0.008610725 -0.01524347 -0.008610725 -0.01706403 -0.01111203 -0.01519727 -0.01111203 -0.01701802 -0.008195936 -0.01528877 -0.005694568 -0.01697266 -0.005694568 -0.01528877 -0.005694568 -0.01701802 -0.008195936 -0.01524347 -0.008195936 -0.01697266 -0.005270481 -0.01533359 -0.002769172 -0.01692771 -0.002769172 -0.01533359 -0.002769172 -0.01697266 -0.005270481 -0.01528877 -0.005270481 -0.01685971 0.001286864 -0.01543009 0.001442492 -0.01683121 0.001442492 -0.01543009 0.001442492 -0.01685971 0.001286864 -0.01540172 0.001286864 -0.01540172 0.001286864 -0.01685971 0.001286864 -0.01692771 -0.002554893 -0.01540172 0.001286864 -0.01692771 -0.002554893 -0.01533359 -0.002554893 -0.006736278 0.01130062 -0.006881058 0.01197981 -0.006881058 0.01123654 -0.006881058 0.01197981 -0.006736278 0.01130062 -0.003163397 0.01312333 -0.006881058 0.01197981 -0.003163397 0.01312333 -0.006736278 0.01202946 0.01543009 6.67286e-4 0.01685971 5.169e-4 0.01683121 6.67286e-4 0.01685971 5.169e-4 0.01543009 6.67286e-4 0.01540172 5.169e-4 0.01685971 5.169e-4 0.01540172 5.169e-4 0.01533359 -0.003194868 0.01685971 5.169e-4 0.01533359 -0.003194868 0.01692771 -0.003194868 0.01528835 -0.005306959 0.01692771 -0.002816379 0.01533359 -0.002816379 0.01692771 -0.002816379 0.01528835 -0.005306959 0.01697295 -0.005306959 0.01524239 -0.008196711 0.01697295 -0.005706191 0.01528835 -0.005706191 0.01697295 -0.005706191 0.01524239 -0.008196711 0.01701891 -0.008196711 0.01519638 -0.01107937 0.01701891 -0.00858885 0.01524239 -0.00858885 0.01701891 -0.00858885 0.01519638 -0.01107937 0.01706486 -0.01107937 0.01514977 -0.01395177 0.01706486 -0.01146125 0.01519638 -0.01146125 0.01706486 -0.01146125 0.01514977 -0.01395177 0.01711153 -0.01395177 0.01514977 -0.01432096 0.01715886 -0.01681149 0.01711153 -0.01432096 0.01715886 -0.01681149 0.01514977 -0.01432096 0.01510268 -0.01681149 0.01510268 -0.01716506 0.01720625 -0.01965558 0.01715886 -0.01716506 0.01720625 -0.01965558 0.01510268 -0.01716506 0.01505506 -0.01965558 0.01505506 -0.0199902 0.01725393 -0.02248072 0.01720625 -0.0199902 0.01725393 -0.02248072 0.01505506 -0.0199902 0.01500761 -0.02248072 0.01500761 -0.02279371 0.01730161 -0.02528429 0.01725393 -0.02279371 0.01730161 -0.02528429 0.01500761 -0.02279371 0.01495969 -0.02528429 0.01495969 -0.02557289 0.01734972 -0.02806311 0.01730161 -0.02557289 0.01734972 -0.02806311 0.01495969 -0.02557289 0.01491159 -0.02806311 0.01491159 -0.02832466 0.01739799 -0.03081518 0.01734972 -0.02832466 0.01739799 -0.03081518 0.01491159 -0.02832466 0.01486331 -0.03081518 0.01481491 -0.03353691 0.01739799 -0.03104639 0.01486331 -0.03104639 0.01739799 -0.03104639 0.01481491 -0.03353691 0.01744639 -0.03353691 5.54061e-4 0.01197981 4.09307e-4 0.01130062 5.54061e-4 0.01123654 4.09307e-4 0.01130062 5.54061e-4 0.01197981 -0.003163397 0.01312333 -0.003163397 0.01312333 5.54061e-4 0.01197981 4.09307e-4 0.01202946 -5.64787e-4 0.04742926 -0.01704913 0.04705178 -4.4867e-4 0.04705178 -0.01704913 0.04705178 -5.64787e-4 0.04742926 -0.01693302 0.04742926 -0.01693302 0.04742926 -5.64787e-4 0.04742926 -7.65758e-4 0.04797333 -0.01693302 0.04742926 -7.65758e-4 0.04797333 -0.01673179 0.04797333 -0.01673179 0.04797333 -7.65758e-4 0.04797333 -8.87622e-4 0.04825413 -0.01673179 0.04797333 -8.87622e-4 0.04825413 -0.01661014 0.04825413 -0.03972852 0.008668065 -0.03989923 0.007290661 -0.03972852 0.007209897 -0.03989923 0.007290661 -0.03972852 0.008668065 -0.04025882 0.00745362 -0.04025882 0.00745362 -0.03972852 0.008668065 -0.04025882 0.008911728 -0.04025882 0.008911728 -0.03972852 0.008668065 -0.03989923 0.008748888 -0.04101741 0.00841242 -0.04154747 0.007209897 -0.04101741 0.006954193 -0.04154747 0.007209897 -0.04101741 0.00841242 -0.04154747 0.008668065 -0.04215878 0.008153021 -0.04268908 0.006954193 -0.04215878 0.006694853 -0.04268908 0.006954193 -0.04215878 0.008153021 -0.04268908 0.00841242 -0.04314821 0.00789082 -0.04367882 0.006694853 -0.04314821 0.006432712 -0.04367882 0.006694853 -0.04314821 0.00789082 -0.04367882 0.008153021 -0.04398304 0.007626712 -0.04451334 0.006432712 -0.04398304 0.006168544 -0.04451334 0.006432712 -0.04398304 0.007626712 -0.04451334 0.00789082 0.04608047 0.006432712 0.0455501 0.007626712 0.0455501 0.006168544 0.0455501 0.007626712 0.04608047 0.006432712 0.04608047 0.00789082 0.04628479 0.006694853 0.04575443 0.00789082 0.04575443 0.006432712 0.04575443 0.00789082 0.04628479 0.006694853 0.04628479 0.008153021 0.04632443 0.006954193 0.04579401 0.008153021 0.04579401 0.006694853 0.04579401 0.008153021 0.04632443 0.006954193 0.04632443 0.00841242 0.04619938 0.007209897 0.0456689 0.00841242 0.0456689 0.006954193 0.0456689 0.00841242 0.04619938 0.007209897 0.04619938 0.008668065 0.0455507 0.007290661 0.04537963 0.008668065 0.04537963 0.007209897 0.04537963 0.008668065 0.0455507 0.007290661 0.04591012 0.00745362 0.04537963 0.008668065 0.04591012 0.00745362 0.04591012 0.008911728 0.04537963 0.008668065 0.04591012 0.008911728 0.0455507 0.008748888 0.01693302 0.0467996 4.4867e-4 0.04642242 0.01704913 0.04642242 4.4867e-4 0.04642242 0.01693302 0.0467996 5.64787e-4 0.0467996 5.64787e-4 0.0467996 0.01693302 0.0467996 0.01673179 0.04734373 5.64787e-4 0.0467996 0.01673179 0.04734373 7.65758e-4 0.04734373 7.65758e-4 0.04734373 0.01673179 0.04734373 0.01661014 0.04762428 7.65758e-4 0.04734373 0.01661014 0.04762428 8.87622e-4 0.04762428 -6.6633e-4 0.00210762 -0.001366913 0.006056845 -0.002067685 0.00210762 0.002067685 2.40273e-4 0.001366913 0.003910422 6.6633e-4 2.40273e-4 0.01050859 2.40273e-4 0.0119102 2.40273e-4 0.01120924 0.003910422 -0.01050859 0.00210762 -0.01120924 0.006056845 -0.0119102 0.00210762 -0.01543009 0.00210762 -0.01613074 0.006056845 -0.01683121 0.00210762 0.01543009 2.40273e-4 0.01683121 2.40273e-4 0.01613074 0.003910422 -9.95699e-4 0.04891163 -0.01661014 0.04866623 -8.87622e-4 0.04866623 -0.01661014 0.04866623 -9.95699e-4 0.04891163 -0.01650208 0.04891163 -0.01650208 0.04891163 -9.95699e-4 0.04891163 -0.001253724 0.04941701 -0.01650208 0.04891163 -0.001253724 0.04941701 -0.01624399 0.04941701 -0.01624399 0.04941701 -0.001253724 0.04941701 -0.001517713 0.04986858 -0.01624399 0.04941701 -0.001517713 0.04986858 -0.01598006 0.04986858 -0.03672695 0.00914669 -0.03700774 0.007809758 -0.03672695 0.007688522 -0.03700774 0.007809758 -0.03672695 0.00914669 -0.03725725 0.007907927 -0.03725725 0.007907927 -0.03672695 0.00914669 -0.03725725 0.009366095 -0.03725725 0.009366095 -0.03672695 0.00914669 -0.03700774 0.009267926 -0.03829658 0.008911728 -0.03882694 0.007688522 -0.03829658 0.00745362 -0.03882694 0.007688522 -0.03829658 0.008911728 -0.03882694 0.00914669 0.04545778 0.007688522 0.04492729 0.008911728 0.04492729 0.00745362 0.04492729 0.008911728 0.04545778 0.007688522 0.04545778 0.00914669 0.0445947 0.007809758 0.04431349 0.00914669 0.04431349 0.007688522 0.04431349 0.00914669 0.0445947 0.007809758 0.04484397 0.007907927 0.04431349 0.00914669 0.04484397 0.007907927 0.04484397 0.009366095 0.04431349 0.00914669 0.04484397 0.009366095 0.0445947 0.009267926 0.01650208 0.04832762 8.87622e-4 0.04808247 0.01661014 0.04808247 8.87622e-4 0.04808247 0.01650208 0.04832762 9.95699e-4 0.04832762 9.95699e-4 0.04832762 0.01650208 0.04832762 0.01624399 0.04883325 9.95699e-4 0.04832762 0.01624399 0.04883325 0.001253724 0.04883325 0.001253724 0.04883325 0.01624399 0.04883325 0.001517713 0.04928439 0.001517713 0.04928439 0.01624399 0.04883325 0.01598006 0.04928439 -0.001538932 0.05025845 -0.01598006 0.05022269 -0.001517713 0.05022269 -0.01598006 0.05022269 -0.001538932 0.05025845 -0.01595842 0.05025845 -0.01595842 0.05025845 -0.001538932 0.05025845 -0.001850605 0.05072045 -0.01595842 0.05025845 -0.001850605 0.05072045 -0.01564717 0.05072045 -0.01564717 0.05072045 -0.001850605 0.05072045 -0.002187192 0.05116117 -0.01564717 0.05072045 -0.002187192 0.05116117 -0.01531034 0.05116117 -0.01531034 0.05116117 -0.002187192 0.05116117 -0.01511436 0.05142486 -0.01511436 0.05142486 -0.002187192 0.05116117 -0.002383172 0.05142486 -0.03319668 0.009568572 -0.03368759 0.008291244 -0.03319668 0.008110463 -0.03368759 0.008291244 -0.03319668 0.009568572 -0.03372704 0.008304476 -0.03372704 0.008304476 -0.03319668 0.009568572 -0.03372704 0.009762644 -0.03372704 0.009762644 -0.03319668 0.009568572 -0.03368759 0.009749352 -0.035025 0.009366095 -0.0355553 0.008110463 -0.035025 0.007907927 -0.0355553 0.008110463 -0.035025 0.009366095 -0.0355553 0.009568572 0.04407078 0.008110463 0.04354017 0.009366095 0.04354017 0.007907927 0.04354017 0.009366095 0.04407078 0.008110463 0.04407078 0.009568572 0.04310125 0.008291244 0.04261064 0.009568572 0.04261064 0.008110463 0.04261064 0.009568572 0.04310125 0.008291244 0.0431407 0.008304476 0.04261064 0.009568572 0.0431407 0.008304476 0.0431407 0.009762644 0.04261064 0.009568572 0.0431407 0.009762644 0.04310125 0.009749352 0.01595842 0.049721 0.001517713 0.049685 0.01598006 0.049685 0.001517713 0.049685 0.01595842 0.049721 0.001538932 0.049721 0.001538932 0.049721 0.01595842 0.049721 0.01564717 0.0501827 0.001538932 0.049721 0.01564717 0.0501827 0.001850605 0.0501827 0.001850605 0.0501827 0.01564717 0.0501827 0.01531034 0.05062335 0.001850605 0.0501827 0.01531034 0.05062335 0.002187192 0.05062335 0.002187192 0.05062335 0.01531034 0.05062335 0.002383172 0.05088686 0.002383172 0.05088686 0.01531034 0.05062335 0.01511436 0.05088686 0.04205787 0.008474767 0.04152745 0.009762644 0.04152745 0.008304476 0.04152745 0.009762644 0.04205787 0.008474767 0.04205787 0.009932935 0.04082518 0.008637368 0.04029512 0.009932935 0.04029512 0.008474767 0.04029512 0.009932935 0.04082518 0.008637368 0.04082518 0.01009523 0.04153186 0.008734524 0.04121816 0.01009523 0.04121816 0.008637368 0.04121816 0.01009523 0.04153186 0.008734524 0.0429815 0.00913912 0.04121816 0.01009523 0.0429815 0.00913912 0.04444789 0.009504616 0.04121816 0.01009523 0.04444789 0.009504616 0.04588633 0.009820938 0.04121816 0.01009523 0.04588633 0.009820938 0.04588633 0.01127886 0.04121816 0.01009523 0.04588633 0.01127886 0.04153186 0.01019269 0.04153186 0.01019269 0.04588633 0.01127886 0.0429815 0.01059705 0.0429815 0.01059705 0.04588633 0.01127886 0.04444789 0.01096278 -0.002383172 0.05171883 -0.01420903 0.05292075 -0.01511436 0.05171883 -0.01420903 0.05292075 -0.002383172 0.05171883 -0.003288686 0.05292075 -0.03028738 0.01009523 -0.03060108 0.008734524 -0.03028738 0.008637368 -0.03060108 0.008734524 -0.03028738 0.01009523 -0.03205049 0.00913912 -0.03205049 0.00913912 -0.03028738 0.01009523 -0.03351736 0.009504616 -0.03351736 0.009504616 -0.03028738 0.01009523 -0.03495568 0.009820938 -0.03495568 0.009820938 -0.03028738 0.01009523 -0.03495568 0.01127886 -0.03495568 0.01127886 -0.03028738 0.01009523 -0.03060108 0.01019269 -0.03495568 0.01127886 -0.03060108 0.01019269 -0.03205049 0.01059705 -0.03495568 0.01127886 -0.03205049 0.01059705 -0.03351736 0.01096278 -0.02918893 0.009932935 -0.02971929 0.008637368 -0.02918893 0.008474767 -0.02971929 0.008637368 -0.02918893 0.009932935 -0.02971929 0.01009523 -0.03124928 0.009762644 -0.03177934 0.008474767 -0.03124928 0.008304476 -0.03177934 0.008474767 -0.03124928 0.009762644 -0.03177934 0.009932935 0.01420903 0.05243015 0.002383172 0.0512278 0.01511436 0.0512278 0.002383172 0.0512278 0.01420903 0.05243015 0.003288686 0.05243015 0.04709208 0.009830474 0.04704993 0.01127886 0.04704993 0.009820938 0.04704993 0.01127886 0.04709208 0.009830474 0.04769361 0.009949028 0.04704993 0.01127886 0.04769361 0.009949028 0.04769361 0.01140695 0.04704993 0.01127886 0.04769361 0.01140695 0.04709208 0.01128864 -0.004204869 0.05452358 -0.01239413 0.05569076 -0.01329267 0.05452358 -0.01239413 0.05569076 -0.004204869 0.05452358 -0.005103528 0.05569076 -0.01239413 0.05569076 -0.005103528 0.05569076 -0.01236927 0.05572599 -0.01236927 0.05572599 -0.005103528 0.05569076 -0.005128443 0.05572599 -0.003288686 0.05315285 -0.01329267 0.05435526 -0.01420903 0.05315285 -0.01329267 0.05435526 -0.003288686 0.05315285 -0.004204869 0.05435526 0.01329267 0.05391192 0.003288686 0.05270957 0.01420903 0.05270957 0.003288686 0.05270957 0.01329267 0.05391192 0.004204869 0.05391192 0.01239413 0.05529522 0.004204869 0.05412834 0.01329267 0.05412834 0.004204869 0.05412834 0.01239413 0.05529522 0.005103528 0.05529522 0.005103528 0.05529522 0.01239413 0.05529522 0.01236927 0.05533069 0.005103528 0.05529522 0.01236927 0.05533069 0.005128443 0.05533069 -0.0366714 0.01127886 -0.03671354 0.009830474 -0.0366714 0.009820938 -0.03671354 0.009830474 -0.0366714 0.01127886 -0.03731501 0.009949028 -0.03731501 0.009949028 -0.0366714 0.01127886 -0.03731501 0.01140695 -0.03731501 0.01140695 -0.0366714 0.01127886 -0.03671354 0.01128864 0.05043751 0.01008296 0.04979377 0.01140695 0.04979377 0.009949028 0.04979377 0.01140695 0.05043751 0.01008296 0.05043751 0.01154088 -0.005128443 0.05582916 -0.01201254 0.05632776 -0.01236927 0.05582916 -0.01201254 0.05632776 -0.005128443 0.05582916 -0.005485236 0.05632776 -0.01201254 0.05632776 -0.005485236 0.05632776 -0.01167315 0.05689096 -0.01167315 0.05689096 -0.005485236 0.05632776 -0.005824625 0.05689096 -0.01167315 0.05689096 -0.005824625 0.05689096 -0.005894899 0.05703151 -0.01167315 0.05689096 -0.005894899 0.05703151 -0.01160264 0.05703151 0.01236927 0.05548232 0.005485236 0.05598104 0.005128443 0.05548232 0.005485236 0.05598104 0.01236927 0.05548232 0.01201254 0.05598104 0.005485236 0.05598104 0.01201254 0.05598104 0.01167315 0.05654418 0.005485236 0.05598104 0.01167315 0.05654418 0.005824625 0.05654418 0.005824625 0.05654418 0.01167315 0.05654418 0.005894899 0.05668473 0.005894899 0.05668473 0.01167315 0.05654418 0.01160264 0.05668473 -0.04056739 0.01140695 -0.041211 0.01008296 -0.04056739 0.009949028 -0.041211 0.01008296 -0.04056739 0.01140695 -0.041211 0.01154088 0.05237436 0.01011615 0.05222082 0.01154088 0.05222082 0.01008296 0.05222082 0.01154088 0.05237436 0.01011615 0.05286437 0.01020705 0.05222082 0.01154088 0.05286437 0.01020705 0.05286437 0.01166546 0.05222082 0.01154088 0.05286437 0.01166546 0.05237436 0.01157432 -0.00611943 0.05751293 -0.01160264 0.05706799 -0.005894899 0.05706799 -0.01160264 0.05706799 -0.00611943 0.05751293 -0.0113781 0.05751293 -0.0113781 0.05751293 -0.00611943 0.05751293 -0.006367862 0.05811965 -0.0113781 0.05751293 -0.006367862 0.05811965 -0.01112967 0.05811965 -0.01112967 0.05811965 -0.006367862 0.05811965 -0.01108133 0.05827033 -0.01108133 0.05827033 -0.006367862 0.05811965 -0.006416201 0.05827033 -0.04420495 0.01154088 -0.04435873 0.01011615 -0.04420495 0.01008296 -0.04435873 0.01011615 -0.04420495 0.01154088 -0.04484874 0.01020705 -0.04484874 0.01020705 -0.04420495 0.01154088 -0.04484874 0.01166546 -0.04484874 0.01166546 -0.04420495 0.01154088 -0.04435873 0.01157432 0.01160264 0.05677032 0.00611943 0.05721527 0.005894899 0.05677032 0.00611943 0.05721527 0.01160264 0.05677032 0.0113781 0.05721527 0.00611943 0.05721527 0.0113781 0.05721527 0.01112967 0.05782181 0.00611943 0.05721527 0.01112967 0.05782181 0.006367862 0.05782181 0.006367862 0.05782181 0.01112967 0.05782181 0.01108133 0.05797243 0.006367862 0.05782181 0.01108133 0.05797243 0.006416201 0.05797243 0.05495882 0.01033121 0.05431509 0.01166546 0.05431509 0.01020705 0.05431509 0.01166546 0.05495882 0.01033121 0.05495882 0.01178932 -0.006568312 0.0587098 -0.01108133 0.0582388 -0.006416201 0.0582388 -0.01108133 0.0582388 -0.006568312 0.0587098 -0.01092922 0.0587098 -0.01092922 0.0587098 -0.006568312 0.0587098 -0.006719529 0.05934453 -0.01092922 0.0587098 -0.006719529 0.05934453 -0.010778 0.05934453 -0.010778 0.05934453 -0.006719529 0.05934453 -0.006734609 0.05944097 -0.010778 0.05934453 -0.006734609 0.05944097 -0.01076292 0.05944097 -0.05061388 0.01178932 -0.05076915 0.01036185 -0.05061388 0.01033121 -0.05076915 0.01036185 -0.05061388 0.01178932 -0.05125761 0.01044207 -0.05125761 0.01044207 -0.05061388 0.01178932 -0.05125761 0.01190042 -0.05125761 0.01190042 -0.05061388 0.01178932 -0.05076915 0.01181989 -0.04756093 0.01166546 -0.04820466 0.01033121 -0.04756093 0.01020705 -0.04820466 0.01033121 -0.04756093 0.01166546 -0.04820466 0.01178932 0.05621916 0.01036185 0.05606395 0.01178932 0.05606395 0.01033121 0.05606395 0.01178932 0.05621916 0.01036185 0.05670756 0.01044207 0.05606395 0.01178932 0.05670756 0.01044207 0.05670756 0.01190042 0.05606395 0.01178932 0.05670756 0.01190042 0.05621916 0.01181989 0.01108133 0.05799019 0.006568312 0.05846107 0.006416201 0.05799019 0.006568312 0.05846107 0.01108133 0.05799019 0.01092922 0.05846107 0.006568312 0.05846107 0.01092922 0.05846107 0.006719529 0.05909585 0.006719529 0.05909585 0.01092922 0.05846107 0.010778 0.05909585 0.006719529 0.05909585 0.010778 0.05909585 0.006734609 0.05919224 0.006734609 0.05919224 0.010778 0.05909585 0.01076292 0.05919224 -0.006734609 0.05933988 -0.01067698 0.05988574 -0.01076292 0.05933988 -0.01067698 0.05988574 -0.006734609 0.05933988 -0.006820559 0.05988574 -0.01067698 0.05988574 -0.006820559 0.05988574 -0.01062703 0.06054174 -0.01062703 0.06054174 -0.006820559 0.05988574 -0.006870746 0.06054174 -0.055736 0.01200848 -0.05583178 0.01056689 -0.055736 0.01055032 -0.05583178 0.01056689 -0.055736 0.01200848 -0.05637937 0.01064127 -0.05637937 0.01064127 -0.055736 0.01200848 -0.05637937 0.01209962 -0.05637937 0.01209962 -0.055736 0.01200848 -0.05583178 0.01202487 -0.05334454 0.01190042 -0.05398815 0.01055032 -0.05334454 0.01044207 -0.05398815 0.01055032 -0.05334454 0.01190042 -0.05398815 0.01200848 0.05809938 0.01055032 0.05745577 0.01190042 0.05745577 0.01044207 0.05745577 0.01190042 0.05809938 0.01055032 0.05809938 0.01200848 0.05857855 0.01056689 0.05848234 0.01200848 0.05848234 0.01055032 0.05848234 0.01200848 0.05857855 0.01056689 0.0591259 0.01064127 0.05848234 0.01200848 0.0591259 0.01064127 0.0591259 0.01209962 0.05848234 0.01200848 0.0591259 0.01209962 0.05857855 0.01202487 0.01067698 0.05968672 0.006734609 0.0591408 0.01076292 0.0591408 0.006734609 0.0591408 0.01067698 0.05968672 0.006820559 0.05968672 0.006820559 0.05968672 0.01067698 0.05968672 0.01062703 0.06034266 0.006820559 0.05968672 0.01062703 0.06034266 0.006870746 0.06034266 -0.006869733 0.06100857 -0.01062703 0.06036984 -0.006870746 0.06036984 -0.01062703 0.06036984 -0.006869733 0.06100857 -0.01062798 0.06100857 -0.01062798 0.06100857 -0.006869733 0.06100857 -0.006824195 0.06157219 -0.01062798 0.06100857 -0.006824195 0.06157219 -0.01067352 0.06157219 -0.05778825 0.01209962 -0.05844002 0.0107311 -0.05778825 0.01064127 -0.05844002 0.0107311 -0.05778825 0.01209962 -0.05844002 0.01218909 0.05978655 0.0107311 0.05913478 0.01209962 0.05913478 0.01064127 0.05913478 0.01209962 0.05978655 0.0107311 0.05978655 0.01218909 0.01062798 0.06085926 0.006870746 0.06022053 0.01062703 0.06022053 0.006870746 0.06022053 0.01062798 0.06085926 0.006869733 0.06085926 0.006869733 0.06085926 0.01062798 0.06085926 0.006824195 0.06142288 0.006824195 0.06142288 0.01062798 0.06085926 0.01067352 0.06142288 -0.006824195 0.06132817 -0.01067996 0.06140917 -0.01067352 0.06132817 -0.01067996 0.06140917 -0.006824195 0.06132817 -0.006817579 0.06140917 -0.01067996 0.06140917 -0.006817579 0.06140917 -0.01078277 0.06204599 -0.01078277 0.06204599 -0.006817579 0.06140917 -0.006714761 0.06204599 -0.01078277 0.06204599 -0.006714761 0.06204599 -0.01090133 0.06253027 -0.01090133 0.06253027 -0.006714761 0.06204599 -0.006596386 0.06253027 -0.06073278 0.01225441 -0.06129527 0.01085418 -0.06073278 0.01079624 -0.06129527 0.01085418 -0.06073278 0.01225441 -0.06137639 0.01085948 -0.06137639 0.01085948 -0.06073278 0.01225441 -0.06137639 0.01231765 -0.06137639 0.01231765 -0.06073278 0.01225441 -0.06129527 0.01231235 -0.05945003 0.01218909 -0.06008511 0.01079624 -0.05945003 0.0107311 -0.06008511 0.01079624 -0.05945003 0.01218909 -0.06008511 0.01225441 0.06005913 0.01079624 0.05942398 0.01218909 0.05942398 0.0107311 0.05942398 0.01218909 0.06005913 0.01079624 0.06005913 0.01225441 0.05987828 0.01085418 0.05931586 0.01225441 0.05931586 0.01079624 0.05931586 0.01225441 0.05987828 0.01085418 0.05995959 0.01085948 0.05931586 0.01225441 0.05995959 0.01085948 0.05995959 0.01231765 0.05931586 0.01225441 0.05995959 0.01231765 0.05987828 0.01231235 0.01067352 0.06122881 0.006817579 0.06130981 0.006824195 0.06122881 0.006817579 0.06130981 0.01067352 0.06122881 0.01067996 0.06130981 0.006817579 0.06130981 0.01067996 0.06130981 0.01078277 0.06194663 0.006817579 0.06130981 0.01078277 0.06194663 0.006714761 0.06194663 0.006714761 0.06194663 0.01078277 0.06194663 0.01090133 0.06243067 0.006714761 0.06194663 0.01090133 0.06243067 0.006596386 0.06243067 -0.006596386 0.06230098 -0.01093608 0.06244289 -0.01090133 0.06230098 -0.01093608 0.06244289 -0.006596386 0.06230098 -0.006561577 0.06244289 -0.01093608 0.06244289 -0.006561577 0.06244289 -0.01097542 0.06291043 -0.01097542 0.06291043 -0.006561577 0.06244289 -0.006522357 0.06291043 -0.06215018 0.01236104 -0.06264787 0.01093608 -0.06215018 0.01090312 -0.06264787 0.01093608 -0.06215018 0.01236104 -0.06279402 0.01094216 -0.06279402 0.01094216 -0.06215018 0.01236104 -0.06279402 0.01240015 -0.06279402 0.01240015 -0.06215018 0.01236104 -0.06264787 0.01239413 -0.06163758 0.01231765 -0.06228119 0.01090312 -0.06163758 0.01085948 -0.06228119 0.01090312 -0.06163758 0.01231765 -0.06228119 0.01236104 0.05948287 0.01090312 0.05883926 0.01231765 0.05883926 0.01085948 0.05883926 0.01231765 0.05948287 0.01090312 0.05948287 0.01236104 0.05848544 0.01093608 0.05798798 0.01236104 0.05798798 0.01090312 0.05798798 0.01236104 0.05848544 0.01093608 0.05863159 0.01094216 0.05798798 0.01236104 0.05863159 0.01094216 0.05863159 0.01240015 0.05798798 0.01236104 0.05863159 0.01240015 0.05848544 0.01239413 0.01090133 0.06223899 0.006561577 0.06238085 0.006596386 0.06223899 0.006561577 0.06238085 0.01090133 0.06223899 0.01093608 0.06238085 0.006561577 0.06238085 0.01093608 0.06238085 0.01097542 0.06284832 0.006561577 0.06238085 0.01097542 0.06284832 0.006522357 0.06284832 -0.006470978 0.0633468 -0.01097542 0.06273746 -0.006522357 0.06273746 -0.01097542 0.06273746 -0.006470978 0.0633468 -0.01102674 0.0633468 -0.06267052 0.01240015 -0.06313902 0.01096189 -0.06267052 0.01094216 -0.06313902 0.01096189 -0.06267052 0.01240015 -0.06375032 0.01097774 -0.06375032 0.01097774 -0.06267052 0.01240015 -0.06436181 0.01098299 -0.06436181 0.01098299 -0.06267052 0.01240015 -0.0698446 0.01202946 -0.0698446 0.01202946 -0.06267052 0.01240015 -0.06923931 0.01211625 -0.06923931 0.01211625 -0.06267052 0.01240015 -0.06863266 0.01219242 -0.06863266 0.01219242 -0.06267052 0.01240015 -0.06802475 0.01225858 -0.06802475 0.01225858 -0.06267052 0.01240015 -0.06741583 0.01231461 -0.06741583 0.01231461 -0.06267052 0.01240015 -0.06680607 0.01236063 -0.06680607 0.01236063 -0.06267052 0.01240015 -0.0661956 0.01239591 -0.0661956 0.01239591 -0.06267052 0.01240015 -0.06558459 0.01242125 -0.06558459 0.01242125 -0.06267052 0.01240015 -0.06313902 0.01241993 -0.06558459 0.01242125 -0.06313902 0.01241993 -0.06375032 0.01243591 -0.06558459 0.01242125 -0.06375032 0.01243591 -0.06497329 0.01243633 -0.06497329 0.01243633 -0.06375032 0.01243591 -0.06436181 0.01244109 -0.1320354 0.004374444 -0.1321778 0.00581938 -0.1321778 0.004361391 -0.1321778 0.00581938 -0.1320354 0.004374444 -0.06984466 0.01057142 -0.1321778 0.00581938 -0.06984466 0.01057142 -0.1320354 0.005832493 -0.1320354 0.005832493 -0.06984466 0.01057142 -0.0698446 0.01202946 -0.0698446 0.01202946 -0.06984466 0.01057142 -0.06923931 0.01065784 -0.0698446 0.01202946 -0.06923931 0.01065784 -0.06863266 0.01073426 -0.0698446 0.01202946 -0.06863266 0.01073426 -0.06802475 0.0108006 -0.0698446 0.01202946 -0.06802475 0.0108006 -0.06741583 0.01085644 -0.0698446 0.01202946 -0.06741583 0.01085644 -0.06680607 0.01090246 -0.0698446 0.01202946 -0.06680607 0.01090246 -0.0661956 0.01093775 -0.0698446 0.01202946 -0.0661956 0.01093775 -0.06558459 0.01096332 -0.0698446 0.01202946 -0.06558459 0.01096332 -0.06497329 0.0109784 -0.0698446 0.01202946 -0.06497329 0.0109784 -0.06436181 0.01098299 0.1307095 0.00581938 0.1305671 0.004374444 0.1307095 0.004361391 0.1305671 0.004374444 0.1307095 0.00581938 0.06837636 0.01057142 0.06837636 0.01057142 0.1307095 0.00581938 0.1305671 0.005832493 0.06837636 0.01057142 0.1305671 0.005832493 0.06837636 0.01202946 0.06837636 0.01057142 0.06837636 0.01202946 0.06777101 0.01065784 0.06777101 0.01065784 0.06837636 0.01202946 0.06716436 0.01073426 0.06716436 0.01073426 0.06837636 0.01202946 0.06655645 0.0108006 0.06655645 0.0108006 0.06837636 0.01202946 0.06594753 0.01085644 0.06594753 0.01085644 0.06837636 0.01202946 0.06533777 0.01090246 0.06533777 0.01090246 0.06837636 0.01202946 0.0647273 0.01093775 0.0647273 0.01093775 0.06837636 0.01202946 0.06411629 0.01096332 0.06411629 0.01096332 0.06837636 0.01202946 0.06350499 0.0109784 0.06350499 0.0109784 0.06837636 0.01202946 0.0628935 0.01098299 0.06167072 0.01096189 0.06120198 0.01240015 0.06120198 0.01094216 0.06120198 0.01240015 0.06167072 0.01096189 0.06228178 0.01097774 0.06120198 0.01240015 0.06228178 0.01097774 0.0628935 0.01098299 0.06120198 0.01240015 0.0628935 0.01098299 0.06837636 0.01202946 0.06120198 0.01240015 0.06837636 0.01202946 0.06777101 0.01211625 0.06120198 0.01240015 0.06777101 0.01211625 0.06716436 0.01219242 0.06120198 0.01240015 0.06716436 0.01219242 0.06655645 0.01225858 0.06120198 0.01240015 0.06655645 0.01225858 0.06594753 0.01231461 0.06120198 0.01240015 0.06594753 0.01231461 0.06533777 0.01236063 0.06120198 0.01240015 0.06533777 0.01236063 0.0647273 0.01239591 0.06120198 0.01240015 0.0647273 0.01239591 0.06411629 0.01242125 0.06120198 0.01240015 0.06411629 0.01242125 0.06167072 0.01241993 0.06167072 0.01241993 0.06411629 0.01242125 0.06228178 0.01243591 0.06228178 0.01243591 0.06411629 0.01242125 0.06350499 0.01243633 0.06228178 0.01243591 0.06350499 0.01243633 0.0628935 0.01244109 0.01097542 0.06269991 0.006470978 0.06330925 0.006522357 0.06269991 0.006470978 0.06330925 0.01097542 0.06269991 0.01102674 0.06330925 -0.006419718 0.06376534 -0.01102674 0.063156 -0.006470978 0.063156 -0.01102674 0.063156 -0.006419718 0.06376534 -0.011078 0.06376534 0.006419718 -0.06355655 0.01112926 -0.06416589 0.011078 -0.06355655 0.01112926 -0.06416589 0.006419718 -0.06355655 0.006368398 -0.06416589 0.006317138 -0.06454837 0.01112926 -0.06393903 0.006368398 -0.06393903 0.01112926 -0.06393903 0.006317138 -0.06454837 0.01118052 -0.06454837 0.006317138 -0.06430333 0.01123178 -0.06491267 0.01118052 -0.06430333 0.01123178 -0.06491267 0.006317138 -0.06430333 0.006265878 -0.06491267 0.006265878 -0.06464934 0.01128304 -0.06525868 0.01123178 -0.06464934 0.01128304 -0.06525868 0.006265878 -0.06464934 0.006214618 -0.06525868 0.006163418 -0.06558632 0.01128304 -0.06497693 0.006214618 -0.06497693 0.01128304 -0.06497693 0.006163418 -0.06558632 0.0113343 -0.06558632 0.006112337 -0.06589543 0.0113343 -0.06528609 0.006163418 -0.06528609 0.0113343 -0.06528609 0.006112337 -0.06589543 0.01138538 -0.06589543 0.006061375 -0.06618601 0.01138538 -0.06557667 0.006112337 -0.06557667 0.01138538 -0.06557667 0.006061375 -0.06618601 0.0114364 -0.06618601 0.006010413 -0.06645792 0.0114364 -0.06584858 0.006061375 -0.06584858 0.0114364 -0.06584858 0.006010413 -0.06645792 0.01148706 -0.06645792 0.006010413 -0.06610172 0.01153784 -0.06671106 0.01148706 -0.06610172 0.01153784 -0.06671106 0.006010413 -0.06610172 0.00595963 -0.06671106 7.41029e-4 -0.1298606 0.01153784 -0.06758016 0.00595963 -0.06758016 0.01153784 -0.06758016 7.41029e-4 -0.1298606 0.01675677 -0.1298606 7.41029e-4 -0.1299881 0.01676869 -0.1301307 0.01675677 -0.1299881 0.01676869 -0.1301307 7.41029e-4 -0.1299881 7.29076e-4 -0.1301307 0.01676869 -0.1301307 7.29076e-4 -0.1301307 0.01684916 -0.131825 0.01684916 -0.131825 7.29076e-4 -0.1301307 6.48502e-4 -0.131825 -0.133574 0.004206776 -0.1338878 0.005637586 -0.1338878 0.004183292 -0.1338878 0.005637586 -0.133574 0.004206776 -0.131884 0.004361391 -0.1338878 0.005637586 -0.131884 0.004361391 -0.1335731 0.005662441 -0.1335731 0.005662441 -0.131884 0.004361391 -0.131884 0.00581938 -0.01676869 -0.1302883 -7.41029e-4 -0.1301458 -0.01675677 -0.1301458 -7.41029e-4 -0.1301458 -0.01676869 -0.1302883 -7.29076e-4 -0.1302883 -7.29076e-4 -0.1302883 -0.01676869 -0.1302883 -0.01684916 -0.1319833 -7.29076e-4 -0.1302883 -0.01684916 -0.1319833 -6.48459e-4 -0.1319833 -0.01675677 -0.1300058 -0.00595963 -0.06772524 -0.01153784 -0.06772524 -0.00595963 -0.06772524 -0.01675677 -0.1300058 -7.41029e-4 -0.1300058 -0.01148706 -0.06630885 -0.00595963 -0.06691819 -0.006010413 -0.06630885 -0.00595963 -0.06691819 -0.01148706 -0.06630885 -0.01153784 -0.06691819 -0.01148706 -0.06664067 -0.006061375 -0.06603133 -0.0114364 -0.06603133 -0.006061375 -0.06603133 -0.01148706 -0.06664067 -0.006010413 -0.06664067 -0.0114364 -0.06634443 -0.006112337 -0.06573504 -0.01138538 -0.06573504 -0.006112337 -0.06573504 -0.0114364 -0.06634443 -0.006061375 -0.06634443 -0.01138538 -0.06602942 -0.006163418 -0.06542009 -0.0113343 -0.06542009 -0.006163418 -0.06542009 -0.01138538 -0.06602942 -0.006112337 -0.06602942 -0.0113343 -0.06569588 -0.006214618 -0.06508648 -0.01128304 -0.06508648 -0.006214618 -0.06508648 -0.0113343 -0.06569588 -0.006163418 -0.06569588 -0.01128304 -0.06534373 -0.006265878 -0.06473439 -0.01123178 -0.06473439 -0.006265878 -0.06473439 -0.01128304 -0.06534373 -0.006214618 -0.06534373 -0.01123178 -0.06497323 -0.006317138 -0.06436389 -0.01118052 -0.06436389 -0.006317138 -0.06436389 -0.01123178 -0.06497323 -0.006265878 -0.06497323 -0.01112926 -0.06397509 -0.006317138 -0.06458443 -0.006368398 -0.06397509 -0.006317138 -0.06458443 -0.01112926 -0.06397509 -0.01118052 -0.06458443 -0.01112926 -0.06417739 -0.006419718 -0.06356805 -0.011078 -0.06356805 -0.006419718 -0.06356805 -0.01112926 -0.06417739 -0.006368398 -0.06417739 0.011078 0.06375229 0.006470978 0.06314295 0.01102674 0.06314295 0.006470978 0.06314295 0.011078 0.06375229 0.006419718 0.06375229 0.133053 0.005637586 0.1327392 0.004206776 0.133053 0.004183292 0.1327392 0.004206776 0.133053 0.005637586 0.1310493 0.004361391 0.1310493 0.004361391 0.133053 0.005637586 0.1327383 0.005662441 0.1310493 0.004361391 0.1327383 0.005662441 0.1310493 0.00581938 6.33489e-4 -0.1323763 0.01684916 -0.132061 6.48502e-4 -0.132061 0.01684916 -0.132061 6.33489e-4 -0.1323763 0.01686424 -0.1323763 0.01686424 -0.1323763 6.33489e-4 -0.1323763 0.01682657 -0.1338978 0.01682657 -0.1338978 6.33489e-4 -0.1323763 6.71193e-4 -0.1338978 -0.1342942 0.004069507 -0.1347784 0.005486011 -0.1347784 0.004041314 -0.1347784 0.005486011 -0.1342942 0.004069507 -0.1327747 0.004183292 -0.1347784 0.005486011 -0.1327747 0.004183292 -0.134292 0.005517721 -0.134292 0.005517721 -0.1327747 0.004183292 -0.1327747 0.005637586 -0.01686424 -0.1325504 -6.48459e-4 -0.1322361 -0.01684916 -0.1322361 -6.48459e-4 -0.1322361 -0.01686424 -0.1325504 -6.33489e-4 -0.1325504 -6.33489e-4 -0.1325504 -0.01686424 -0.1325504 -0.01682657 -0.1340737 -6.33489e-4 -0.1325504 -0.01682657 -0.1340737 -6.71246e-4 -0.1340737 0.1352131 0.005486011 0.134729 0.004069507 0.1352131 0.004041314 0.134729 0.004069507 0.1352131 0.005486011 0.1332095 0.004183292 0.1332095 0.004183292 0.1352131 0.005486011 0.1347268 0.005517721 0.1332095 0.004183292 0.1347268 0.005517721 0.1332095 0.005637586 6.71193e-4 -0.1341083 0.01681447 -0.1345955 0.01682657 -0.1341083 0.01681447 -0.1345955 6.71193e-4 -0.1341083 6.83279e-4 -0.1345955 0.01681447 -0.1345955 6.83279e-4 -0.1345955 0.01668286 -0.1359451 0.01668286 -0.1359451 6.83279e-4 -0.1345955 8.14909e-4 -0.1359451 -0.1343178 0.003962755 -0.1349647 0.005365133 -0.1349647 0.003935933 -0.1349647 0.005365133 -0.1343178 0.003962755 -0.132961 0.004041314 -0.1349647 0.005365133 -0.132961 0.004041314 -0.1343142 0.005398333 -0.1343142 0.005398333 -0.132961 0.004041314 -0.132961 0.005486011 -0.01681447 -0.1347746 -6.71246e-4 -0.1342898 -0.01682657 -0.1342898 -6.71246e-4 -0.1342898 -0.01681447 -0.1347746 -6.83279e-4 -0.1347746 -6.83279e-4 -0.1347746 -0.01681447 -0.1347746 -0.0166825 -0.1361272 -6.83279e-4 -0.1347746 -0.0166825 -0.1361272 -8.1526e-4 -0.1361272 0.1366667 0.005365133 0.1360199 0.003962755 0.1366667 0.003935933 0.1360199 0.003962755 0.1366667 0.005365133 0.1346631 0.004041314 0.1346631 0.004041314 0.1366667 0.005365133 0.1360163 0.005398333 0.1346631 0.004041314 0.1360163 0.005398333 0.1346631 0.005486011 8.14909e-4 -0.1361296 0.01661962 -0.1367779 0.01668286 -0.1361296 0.01661962 -0.1367779 8.14909e-4 -0.1361296 8.78182e-4 -0.1367779 0.01661962 -0.1367779 8.78182e-4 -0.1367779 0.01641583 -0.1379665 0.01641583 -0.1379665 8.78182e-4 -0.1367779 0.001081943 -0.1379665 -0.1336516 0.003886461 -0.1344456 0.005274832 -0.1344456 0.00386697 -0.1344456 0.005274832 -0.1336516 0.003886461 -0.1324419 0.003935933 -0.1344456 0.005274832 -0.1324419 0.003935933 -0.1336464 0.005304336 -0.1336464 0.005304336 -0.1324419 0.003935933 -0.1324419 0.005365133 -0.0166825 -0.1363061 -8.78182e-4 -0.1369504 -8.1526e-4 -0.1363061 -8.78182e-4 -0.1369504 -0.0166825 -0.1363061 -0.01661962 -0.1369504 -8.78182e-4 -0.1369504 -0.01661962 -0.1369504 -0.001082718 -0.1381435 -0.001082718 -0.1381435 -0.01661962 -0.1369504 -0.01641494 -0.1381435 0.137406 0.005274832 0.1366119 0.003886461 0.137406 0.00386697 0.1366119 0.003886461 0.137406 0.005274832 0.1354023 0.003935933 0.1354023 0.003935933 0.137406 0.005274832 0.1366068 0.005304336 0.1354023 0.003935933 0.1366068 0.005304336 0.1354024 0.005365133 0.001081943 -0.1381247 0.01628059 -0.138913 0.01641583 -0.1381247 0.01628059 -0.138913 0.001081943 -0.1381247 0.001217067 -0.138913 0.01628059 -0.138913 0.001217067 -0.138913 0.01602131 -0.1399616 0.01602131 -0.1399616 0.001217067 -0.138913 0.001476407 -0.1399616 -0.1323065 0.003840625 -0.133224 0.005214691 -0.133224 0.003833234 -0.133224 0.005214691 -0.1323065 0.003840625 -0.1312204 0.00386697 -0.133224 0.005214691 -0.1312204 0.00386697 -0.1322999 0.005235791 -0.1322999 0.005235791 -0.1312204 0.00386697 -0.1312204 0.005274832 -0.01641494 -0.1382845 -0.001217067 -0.1390673 -0.001082718 -0.1382845 -0.001217067 -0.1390673 -0.01641494 -0.1382845 -0.01628059 -0.1390673 -0.001217067 -0.1390673 -0.01628059 -0.1390673 -0.0160197 -0.1401219 -0.001217067 -0.1390673 -0.0160197 -0.1401219 -0.001478016 -0.1401219 0.1374271 0.005214691 0.1365097 0.003840625 0.1374271 0.003833234 0.1365097 0.003840625 0.1374271 0.005214691 0.1354235 0.00386697 0.1354235 0.00386697 0.1374271 0.005214691 0.136503 0.005235791 0.1354235 0.00386697 0.136503 0.005235791 0.1354235 0.005274832 0.001476407 -0.1400932 0.01579934 -0.1409904 0.01602131 -0.1400932 0.01579934 -0.1409904 0.001476407 -0.1400932 0.001698434 -0.1409904 0.01579934 -0.1409904 0.001698434 -0.1409904 0.01549309 -0.1419301 0.01549309 -0.1419301 0.001698434 -0.1409904 0.002004683 -0.1419301 -0.1293026 0.003833234 -0.1313062 0.003833413 -0.1302984 0.003825426 -0.1313062 0.003833413 -0.1293026 0.003833234 -0.1293026 0.005214691 -0.1313062 0.003833413 -0.1293026 0.005214691 -0.1302905 0.005192637 -0.1313062 0.003833413 -0.1302905 0.005192637 -0.1313062 0.005183339 -0.01579934 -0.1411151 -0.001478016 -0.1402245 -0.0160197 -0.1402245 -0.001478016 -0.1402245 -0.01579934 -0.1411151 -0.001698434 -0.1411151 -0.001698434 -0.1411151 -0.01579934 -0.1411151 -0.01549065 -0.1420621 -0.001698434 -0.1411151 -0.01549065 -0.1420621 -0.002007067 -0.1420621 0.13673 0.003833413 0.1347263 0.003833234 0.1357222 0.003825426 0.1347263 0.003833234 0.13673 0.003833413 0.1347263 0.005214691 0.1347263 0.005214691 0.13673 0.003833413 0.1357142 0.005192637 0.1357142 0.005192637 0.13673 0.003833413 0.13673 0.005183339 0.002004683 -0.1420345 0.01517826 -0.1430003 0.01549309 -0.1420345 0.01517826 -0.1430003 0.002004683 -0.1420345 0.002319455 -0.1430003 0.01517826 -0.1430003 0.002319455 -0.1430003 0.01482248 -0.1438714 0.01482248 -0.1438714 0.002319455 -0.1430003 0.002675235 -0.1438714 -0.1266987 0.005183339 -0.1276487 0.003840625 -0.1266987 0.003833413 -0.1276487 0.003840625 -0.1266987 0.005183339 -0.1287024 0.003864884 -0.1287024 0.003864884 -0.1266987 0.005183339 -0.1276397 0.005174875 -0.1287024 0.005179107 -0.1287024 0.003864884 -0.1276397 0.005174875 0.01549065 0.1421256 0.002319455 0.1430838 0.002007067 0.1421256 0.002319455 0.1430838 0.01549065 0.1421256 0.01517826 0.1430838 0.002319455 0.1430838 0.01517826 0.1430838 0.0148189 0.1439632 0.002319455 0.1430838 0.0148189 0.1439632 0.002678573 0.1439632 0.1353182 0.005179107 0.1342555 0.005174875 0.1353182 0.003864884 0.1342644 0.003840625 0.1333145 0.005183339 0.1333145 0.003833413 0.1333145 0.005183339 0.1342644 0.003840625 0.1353182 0.003864884 0.1333145 0.005183339 0.1353182 0.003864884 0.1342555 0.005174875 -0.00307703 0.1449323 -0.01482248 0.1439484 -0.002675235 0.1439484 -0.01482248 0.1439484 -0.00307703 0.1449323 -0.01442044 0.1449323 -0.01442044 0.1449323 -0.00307703 0.1449323 -0.01399773 0.1457853 -0.01399773 0.1457853 -0.00307703 0.1449323 -0.003500044 0.1457853 -0.1234226 0.005179107 -0.1243841 0.003886461 -0.1234226 0.003864884 -0.1243841 0.003886461 -0.1234226 0.005179107 -0.1254262 0.003925204 -0.1254262 0.003925204 -0.1234226 0.005179107 -0.1243748 0.005182683 -0.1254262 0.003925204 -0.1243748 0.005182683 -0.1254262 0.00519973 0.01442044 0.1449631 0.002678573 0.1439872 0.0148189 0.1439872 0.002678573 0.1439872 0.01442044 0.1449631 0.00307703 0.144963 0.00307703 0.144963 0.01442044 0.1449631 0.003504157 0.1458247 0.003504157 0.1458247 0.01442044 0.1449631 0.01399356 0.1458247 0.132157 0.003886461 0.1311956 0.005179107 0.1311956 0.003864884 0.1311956 0.005179107 0.132157 0.003886461 0.1331992 0.003925204 0.1311956 0.005179107 0.1331992 0.003925204 0.1321477 0.005182683 0.1321477 0.005182683 0.1331992 0.003925204 0.1331992 0.00519973 -0.003967106 0.1467769 -0.01399773 0.1458346 -0.003500044 0.1458346 -0.01399773 0.1458346 -0.003967106 0.1467769 -0.01353061 0.1467769 -0.01353061 0.1467769 -0.003967106 0.1467769 -0.01300305 0.1476715 -0.01300305 0.1476715 -0.003967106 0.1467769 -0.004494726 0.1476715 -0.1194913 0.00519973 -0.1205388 0.003962755 -0.1194913 0.003925204 -0.1205388 0.003962755 -0.1194913 0.00519973 -0.121495 0.004010677 -0.121495 0.004010677 -0.1194913 0.00519973 -0.1205298 0.005215883 -0.121495 0.004010677 -0.1205298 0.005215883 -0.121495 0.005242407 0.01399356 0.1458088 0.003967106 0.1467432 0.003504157 0.1458088 0.003967106 0.1467432 0.01399356 0.1458088 0.01353061 0.1467432 0.003967106 0.1467432 0.01353061 0.1467432 0.004499316 0.1476464 0.004499316 0.1476464 0.01353061 0.1467432 0.01299846 0.1476464 0.1294281 0.003962755 0.1283805 0.00519973 0.1283805 0.003925204 0.1283805 0.00519973 0.1294281 0.003962755 0.1303843 0.004010677 0.1283805 0.00519973 0.1303843 0.004010677 0.1294191 0.005215883 0.1294191 0.005215883 0.1303843 0.004010677 0.1303842 0.005242407 -0.004985034 0.1485244 -0.01300305 0.1476926 -0.004494726 0.1476926 -0.01300305 0.1476926 -0.004985034 0.1485244 -0.01251274 0.1485244 -0.01251274 0.1485244 -0.004985034 0.1485244 -0.005680382 0.1495295 -0.01251274 0.1485244 -0.005680382 0.1495295 -0.01181709 0.1495295 -0.1149257 0.005242407 -0.1161551 0.004069507 -0.1149257 0.004010677 -0.1161551 0.004069507 -0.1149257 0.005242407 -0.1169294 0.00411725 -0.1169294 0.00411725 -0.1149257 0.005242407 -0.1161475 0.005274534 -0.1169294 0.00411725 -0.1161475 0.005274534 -0.1169294 0.005303919 0.01251274 0.1484149 0.004499316 0.14759 0.01299846 0.14759 0.004499316 0.14759 0.01251274 0.1484149 0.004985034 0.148415 0.004985034 0.148415 0.01251274 0.1484149 0.005684733 0.1494275 0.005684733 0.1494275 0.01251274 0.1484149 0.01181304 0.1494275 0.1261138 0.004069507 0.1248844 0.005242407 0.1248844 0.004010677 0.1248844 0.005242407 0.1261138 0.004069507 0.126888 0.00411725 0.1248844 0.005242407 0.126888 0.00411725 0.1261062 0.005274534 0.1261062 0.005274534 0.126888 0.00411725 0.126888 0.005303919 -0.005680382 0.1495221 -0.01137214 0.1501657 -0.01181709 0.1495221 -0.01137214 0.1501657 -0.005680382 0.1495221 -0.00612539 0.1501657 -0.01137214 0.1501657 -0.00612539 0.1501657 -0.007085502 0.151359 -0.01137214 0.1501657 -0.007085502 0.151359 -0.01041203 0.151359 -0.1097497 0.005303919 -0.1112851 0.004206776 -0.1097497 0.00411725 -0.1112851 0.004206776 -0.1097497 0.005303919 -0.1117534 0.004240155 -0.1117534 0.004240155 -0.1097497 0.005303919 -0.1112803 0.005358517 -0.1117534 0.004240155 -0.1112803 0.005358517 -0.1117534 0.005380511 0.01181304 0.1493301 0.00612539 0.1499685 0.005684733 0.1493301 0.00612539 0.1499685 0.01181304 0.1493301 0.01137214 0.1499685 0.00612539 0.1499685 0.01137214 0.1499685 0.01040899 0.1511677 0.00612539 0.1499685 0.01040899 0.1511677 0.007088482 0.1511677 0.1222609 0.004206776 0.1207255 0.005303919 0.1207255 0.00411725 0.1207255 0.005303919 0.1222609 0.004206776 0.1227291 0.004240155 0.1207255 0.005303919 0.1227291 0.004240155 0.1222561 0.005358517 0.1222561 0.005358517 0.1227291 0.004240155 0.1227291 0.005380511 -0.007085502 0.1513227 -0.01011556 0.1516917 -0.01041203 0.1513227 -0.01011556 0.1516917 -0.007085502 0.1513227 -0.007382214 0.1516917 -0.01011556 0.1516917 -0.007382214 0.1516917 -0.008748888 0.1531596 -0.1039906 0.005380511 -0.1059942 0.004374444 -0.1039906 0.004240155 -0.1059942 0.004374444 -0.1039906 0.005380511 -0.1059942 0.005467951 0.01011556 0.151395 0.007088482 0.1510288 0.01040899 0.1510288 0.007088482 0.1510288 0.01011556 0.151395 0.007382214 0.151395 0.007382214 0.151395 0.01011556 0.151395 0.008748888 0.1528664 0.1179293 0.004374444 0.1159256 0.005380511 0.1159256 0.004240155 0.1159256 0.005380511 0.1179293 0.004374444 0.1179293 0.005467951 + + + + + + + + + + + + + + +

0 0 0 1 1 1 2 2 2 1 1 3 0 0 4 3 3 5 1 1 6 3 3 7 4 4 8 1 1 9 4 4 10 5 5 11 5 5 12 4 4 13 6 6 14 5 5 15 6 6 16 7 7 17 7 7 18 6 6 19 8 8 20 8 8 21 6 6 22 9 9 23 10 10 24 11 11 25 12 12 26 11 11 27 10 10 28 13 13 29 13 13 30 10 10 31 14 14 32 14 14 33 10 10 34 15 15 35 15 15 36 10 10 37 16 16 38 16 16 39 10 10 40 17 16 41 17 16 42 10 10 43 18 17 44 19 18 45 20 19 46 21 20 47 20 19 48 19 18 49 22 21 50 20 19 51 22 21 52 23 22 53 20 19 54 23 22 55 24 23 56 20 19 57 24 23 58 18 17 59 20 19 60 18 17 61 10 10 62 25 24 63 8 8 64 9 9 65 8 8 66 25 24 67 26 25 68 26 25 69 25 24 70 27 26 71 27 26 72 25 24 73 28 27 74 27 26 75 28 27 76 29 28 77 27 26 78 29 28 79 30 29 80 30 29 81 29 28 82 17 16 83 30 29 84 17 16 85 18 17 86 31 30 87 32 31 88 33 32 89 32 31 90 31 30 91 34 33 92 32 31 93 34 33 94 35 34 95 32 31 96 35 34 97 36 35 98 36 35 99 35 34 100 37 36 101 36 35 102 37 36 103 38 37 104 38 37 105 37 36 106 16 16 107 38 37 108 16 16 109 17 16 110 8 8 111 39 38 112 7 7 113 39 38 114 8 8 115 26 25 116 39 38 117 26 25 118 40 39 119 40 39 120 26 25 121 41 40 122 7 7 123 42 41 124 5 5 125 42 41 126 7 7 127 39 38 128 5 5 129 43 42 130 1 1 131 43 42 132 5 5 133 42 41 134 1 1 135 44 43 136 2 2 137 44 43 138 1 1 139 43 42 140 44 43 141 43 42 142 45 44 143 45 44 144 43 42 145 46 45 146 46 45 147 43 42 148 47 46 149 47 46 150 43 42 151 48 47 152 48 47 153 43 42 154 49 48 155 48 47 156 49 48 157 50 49 158 50 49 159 51 50 160 52 51 161 51 50 162 50 49 163 49 48 164 52 51 165 51 50 166 53 52 167 52 51 168 53 52 169 54 53 170 52 51 171 54 53 172 55 54 173 52 51 174 55 54 175 56 55 176 56 55 177 55 54 178 57 56 179 56 55 180 57 56 181 58 57 182 56 55 183 58 57 184 59 58 185 59 58 186 58 57 187 60 59 188 59 58 189 60 59 190 61 60 191 61 60 192 60 59 193 62 61 194 61 60 195 62 61 196 63 62 197 61 60 198 63 62 199 64 63 200 64 63 201 63 62 202 65 64 203 64 63 204 65 64 205 66 65 206 66 65 207 65 64 208 67 66 209 66 65 210 67 66 211 68 67 212 68 67 213 67 66 214 69 68 215 68 67 216 69 68 217 70 69 218 0 0 219 44 43 220 71 70 221 44 43 222 0 0 223 2 2 224 72 71 225 73 72 226 74 73 227 73 72 228 72 71 229 75 74 230 73 72 231 75 74 232 76 75 233 76 75 234 75 74 235 77 76 236 77 76 237 75 74 238 78 77 239 78 77 240 75 74 241 79 78 242 78 77 243 79 78 244 80 79 245 80 79 246 79 78 247 81 80 248 81 80 249 79 78 250 82 81 251 81 80 252 82 81 253 83 82 254 83 82 255 82 81 256 84 83 257 83 82 258 84 83 259 85 84 260 85 84 261 84 83 262 86 85 263 86 85 264 84 83 265 87 86 266 86 85 267 87 86 268 88 87 269 88 87 270 87 86 271 89 88 272 88 87 273 89 88 274 90 89 275 90 89 276 89 88 277 91 90 278 90 89 279 91 90 280 92 91 281 92 91 282 91 90 283 93 92 284 71 70 285 3 3 286 0 0 287 3 3 288 71 70 289 94 93 290 94 93 291 71 70 292 95 94 293 94 93 294 95 94 295 96 95 296 94 93 297 96 95 298 97 96 299 94 93 300 97 96 301 98 97 302 94 93 303 98 97 304 74 73 305 74 73 306 98 97 307 72 71 308 94 93 309 4 4 310 3 3 311 4 4 312 94 93 313 99 98 314 99 98 315 6 6 316 4 4 317 6 6 318 99 98 319 100 99 320 100 99 321 9 9 322 6 6 323 9 9 324 100 99 325 25 24 326 25 24 327 100 99 328 101 100 329 25 24 330 101 100 331 102 101 332 103 102 333 104 103 334 105 104 335 104 103 336 103 102 337 106 3 338 104 103 339 106 3 340 21 20 341 21 20 342 106 3 343 107 4 344 21 20 345 107 4 346 108 105 347 21 20 348 108 105 349 19 18 350 109 106 351 19 18 352 108 105 353 19 18 354 109 106 355 22 21 356 22 21 357 109 106 358 110 107 359 22 21 360 110 107 361 111 108 362 112 109 363 22 21 364 111 108 365 22 21 366 112 109 367 23 22 368 113 110 369 23 22 370 112 109 371 23 22 372 113 110 373 24 23 374 114 111 375 24 23 376 113 110 377 24 23 378 114 111 379 18 17 380 115 112 381 18 17 382 114 111 383 18 17 384 115 112 385 30 29 386 115 112 387 27 26 388 30 29 389 27 26 390 115 112 391 116 113 392 116 113 393 26 25 394 27 26 395 26 25 396 116 113 397 41 40 398 117 114 399 25 24 400 102 101 401 25 24 402 117 114 403 28 27 404 117 114 405 29 28 406 28 27 407 29 28 408 117 114 409 118 115 410 119 116 411 29 28 412 118 115 413 29 28 414 119 116 415 17 16 416 120 117 417 17 16 418 119 116 419 17 16 420 120 117 421 38 37 422 121 113 423 38 37 424 120 117 425 38 37 426 121 113 427 36 35 428 121 113 429 32 31 430 36 35 431 32 31 432 121 113 433 122 118 434 33 32 435 123 119 436 124 120 437 123 119 438 33 32 439 32 31 440 123 119 441 32 31 442 125 121 443 125 121 444 32 31 445 122 118 446 126 3 447 127 122 448 128 123 449 127 122 450 126 3 451 129 124 452 129 124 453 126 3 454 130 125 455 130 125 456 126 3 457 131 4 458 130 125 459 131 4 460 124 120 461 124 120 462 131 4 463 132 126 464 124 120 465 132 126 466 31 30 467 124 120 468 31 30 469 33 32 470 133 127 471 31 30 472 132 126 473 31 30 474 133 127 475 34 33 476 34 33 477 133 127 478 134 128 479 34 33 480 134 128 481 135 129 482 136 130 483 34 33 484 135 129 485 34 33 486 136 130 487 35 34 488 137 131 489 35 34 490 136 130 491 35 34 492 137 131 493 37 36 494 138 111 495 37 36 496 137 131 497 37 36 498 138 111 499 16 16 500 139 132 501 16 16 502 138 111 503 16 16 504 139 132 505 15 15 506 140 133 507 15 15 508 139 132 509 15 15 510 140 133 511 14 14 512 141 134 513 14 14 514 140 133 515 14 14 516 141 134 517 13 13 518 11 11 519 142 135 520 143 7 521 142 135 522 11 11 523 13 13 524 142 135 525 13 13 526 144 136 527 144 136 528 13 13 529 141 134 530 145 137 531 146 138 532 147 139 533 146 138 534 145 137 535 148 140 536 148 140 537 145 137 538 149 141 539 149 141 540 145 137 541 12 12 542 149 141 543 12 12 544 143 7 545 143 7 546 12 12 547 11 11 548 150 142 549 12 12 550 145 137 551 12 12 552 150 142 553 10 10 554 10 10 555 150 142 556 151 143 557 151 143 558 150 142 559 152 144 560 152 144 561 150 142 562 153 145 563 153 145 564 150 142 565 154 146 566 154 146 567 150 142 568 155 147 569 155 147 570 150 142 571 156 148 572 156 148 573 150 142 574 157 149 575 157 149 576 150 142 577 158 150 578 158 150 579 150 142 580 159 151 581 158 150 582 159 151 583 160 152 584 158 150 585 160 152 586 161 153 587 158 150 588 161 153 589 162 154 590 162 154 591 161 153 592 163 155 593 162 154 594 163 155 595 164 156 596 162 154 597 164 156 598 165 157 599 165 157 600 164 156 601 166 158 602 165 157 603 166 158 604 167 159 605 165 157 606 167 159 607 168 160 608 168 160 609 167 159 610 169 161 611 168 160 612 169 161 613 170 162 614 168 160 615 170 162 616 171 163 617 168 160 618 171 163 619 172 164 620 168 160 621 172 164 622 173 165 623 173 165 624 172 164 625 174 166 626 151 143 627 20 19 628 10 10 629 20 19 630 151 143 631 175 167 632 21 20 633 176 168 634 104 103 635 176 168 636 21 20 637 20 19 638 176 168 639 20 19 640 175 167 641 176 168 642 175 167 643 177 169 644 176 168 645 177 169 646 178 170 647 176 168 648 178 170 649 179 171 650 176 168 651 179 171 652 180 172 653 176 168 654 180 172 655 181 173 656 176 168 657 181 173 658 182 174 659 176 168 660 182 174 661 183 175 662 176 168 663 183 175 664 184 176 665 184 176 666 183 175 667 185 177 668 185 177 669 183 175 670 186 178 671 186 178 672 183 175 673 187 179 674 186 178 675 187 179 676 188 180 677 188 180 678 187 179 679 189 181 680 189 181 681 187 179 682 190 182 683 189 181 684 190 182 685 191 183 686 191 183 687 190 182 688 192 184 689 192 184 690 190 182 691 193 185 692 192 184 693 193 185 694 194 186 695 194 186 696 193 185 697 195 187 698 195 187 699 193 185 700 196 188 701 196 188 702 193 185 703 197 189 704 197 189 705 193 185 706 198 190 707 197 189 708 198 190 709 199 191 710 41 40 711 101 100 712 40 39 713 101 100 714 41 40 715 102 101 716 102 101 717 41 40 718 117 114 719 117 114 720 41 40 721 116 113 722 117 114 723 116 113 724 115 112 725 117 114 726 115 112 727 118 115 728 118 115 729 115 112 730 119 116 731 119 116 732 115 112 733 114 111 734 184 176 735 111 108 736 110 107 737 111 108 738 184 176 739 185 177 740 111 108 741 185 177 742 112 109 743 112 109 744 185 177 745 113 110 746 113 110 747 185 177 748 114 111 749 114 111 750 185 177 751 138 111 752 138 111 753 185 177 754 160 152 755 144 136 756 160 152 757 159 151 758 160 152 759 144 136 760 141 134 761 160 152 762 141 134 763 140 133 764 160 152 765 140 133 766 139 132 767 160 152 768 139 132 769 138 111 770 122 118 771 134 128 772 125 121 773 134 128 774 122 118 775 135 129 776 135 129 777 122 118 778 121 113 779 135 129 780 121 113 781 136 130 782 136 130 783 121 113 784 120 117 785 136 130 786 120 117 787 137 131 788 137 131 789 120 117 790 119 116 791 137 131 792 119 116 793 138 111 794 138 192 795 119 192 796 114 192 797 43 42 798 74 73 799 49 48 800 74 73 801 43 42 802 94 93 803 94 93 804 43 42 805 42 41 806 94 93 807 42 41 808 99 98 809 99 98 810 42 41 811 39 38 812 99 98 813 39 38 814 100 99 815 100 99 816 39 38 817 40 39 818 100 99 819 40 39 820 101 100 821 49 48 822 73 72 823 51 50 824 73 72 825 49 48 826 74 73 827 51 50 828 76 75 829 53 52 830 76 75 831 51 50 832 73 72 833 54 53 834 76 75 835 77 76 836 76 75 837 54 53 838 53 52 839 54 53 840 78 77 841 55 54 842 78 77 843 54 53 844 77 76 845 55 54 846 80 79 847 57 56 848 80 79 849 55 54 850 78 77 851 58 57 852 80 79 853 81 80 854 80 79 855 58 57 856 57 56 857 60 59 858 81 80 859 83 82 860 81 80 861 60 59 862 58 57 863 62 61 864 83 82 865 85 84 866 83 82 867 62 61 868 60 59 869 63 62 870 85 84 871 86 85 872 85 84 873 63 62 874 62 61 875 63 62 876 88 87 877 65 64 878 88 87 879 63 62 880 86 85 881 65 64 882 90 89 883 67 66 884 90 89 885 65 64 886 88 87 887 69 68 888 90 89 889 92 91 890 90 89 891 69 68 892 67 66 893 200 193 894 93 92 895 201 194 896 93 92 897 200 193 898 70 69 899 93 92 900 70 69 901 69 68 902 93 92 903 69 68 904 92 91 905 70 69 906 202 195 907 68 67 908 202 195 909 70 69 910 203 196 911 203 196 912 70 69 913 200 193 914 91 90 915 202 195 916 204 197 917 202 195 918 91 90 919 68 67 920 68 67 921 91 90 922 89 88 923 68 67 924 89 88 925 66 65 926 87 86 927 66 65 928 89 88 929 66 65 930 87 86 931 64 63 932 84 83 933 64 63 934 87 86 935 64 63 936 84 83 937 61 60 938 82 81 939 61 60 940 84 83 941 61 60 942 82 81 943 59 58 944 79 78 945 59 58 946 82 81 947 59 58 948 79 78 949 56 55 950 75 74 951 56 55 952 79 78 953 56 55 954 75 74 955 52 51 956 75 74 957 50 49 958 52 51 959 50 49 960 75 74 961 72 71 962 98 97 963 50 49 964 72 71 965 50 49 966 98 97 967 48 47 968 97 96 969 48 47 970 98 97 971 48 47 972 97 96 973 47 46 974 96 95 975 47 46 976 97 96 977 47 46 978 96 95 979 46 45 980 95 94 981 46 45 982 96 95 983 46 45 984 95 94 985 45 44 986 71 70 987 45 44 988 95 94 989 45 44 990 71 70 991 44 43 992 204 197 993 93 92 994 91 90 995 93 92 996 204 197 997 203 196 998 93 92 999 203 196 1000 201 194 1001 205 198 1002 105 104 1003 206 199 1004 105 104 1005 205 198 1006 103 102 1007 207 200 1008 208 201 1009 209 202 1010 208 201 1011 207 200 1012 210 74 1013 208 201 1014 210 74 1015 211 203 1016 211 203 1017 210 74 1018 212 76 1019 212 76 1020 210 74 1021 213 77 1022 213 77 1023 210 74 1024 214 204 1025 213 77 1026 214 204 1027 215 205 1028 215 205 1029 214 204 1030 216 206 1031 216 206 1032 214 204 1033 217 81 1034 216 206 1035 217 81 1036 218 207 1037 218 207 1038 217 81 1039 219 208 1040 218 207 1041 219 208 1042 220 209 1043 220 209 1044 219 208 1045 221 210 1046 221 210 1047 219 208 1048 222 211 1049 221 210 1050 222 211 1051 223 212 1052 223 212 1053 222 211 1054 224 88 1055 223 212 1056 224 88 1057 225 213 1058 225 213 1059 224 88 1060 226 214 1061 225 213 1062 226 214 1063 227 91 1064 227 91 1065 226 214 1066 228 215 1067 205 198 1068 106 3 1069 103 102 1070 106 3 1071 205 198 1072 229 216 1073 229 216 1074 205 198 1075 230 217 1076 229 216 1077 230 217 1078 231 218 1079 229 216 1080 231 218 1081 232 219 1082 229 216 1083 232 219 1084 233 220 1085 229 216 1086 233 220 1087 209 202 1088 209 202 1089 233 220 1090 207 200 1091 229 216 1092 107 4 1093 106 3 1094 107 4 1095 229 216 1096 234 221 1097 234 221 1098 108 105 1099 107 4 1100 108 105 1101 234 221 1102 109 106 1103 104 103 1104 206 199 1105 105 104 1106 206 199 1107 104 103 1108 176 168 1109 206 199 1110 176 168 1111 235 222 1112 235 222 1113 176 168 1114 236 223 1115 236 223 1116 176 168 1117 237 224 1118 237 224 1119 176 168 1120 238 225 1121 238 225 1122 176 168 1123 239 226 1124 238 225 1125 239 226 1126 240 49 1127 240 49 1128 241 50 1129 242 227 1130 241 50 1131 240 49 1132 239 226 1133 242 227 1134 241 50 1135 243 52 1136 242 227 1137 243 52 1138 244 53 1139 242 227 1140 244 53 1141 245 228 1142 242 227 1143 245 228 1144 246 55 1145 246 55 1146 245 228 1147 247 229 1148 246 55 1149 247 229 1150 248 230 1151 246 55 1152 248 230 1153 249 231 1154 249 231 1155 248 230 1156 250 232 1157 249 231 1158 250 232 1159 251 233 1160 251 233 1161 250 232 1162 252 234 1163 251 233 1164 252 234 1165 253 235 1166 251 233 1167 253 235 1168 254 63 1169 254 63 1170 253 235 1171 255 236 1172 254 63 1173 255 236 1174 256 65 1175 256 65 1176 255 236 1177 257 237 1178 256 65 1179 257 237 1180 258 238 1181 258 238 1182 257 237 1183 259 68 1184 258 238 1185 259 68 1186 260 239 1187 176 168 1188 209 202 1189 239 226 1190 209 202 1191 176 168 1192 229 216 1193 229 216 1194 176 168 1195 184 176 1196 229 216 1197 184 176 1198 234 221 1199 234 221 1200 184 176 1201 109 106 1202 109 106 1203 184 176 1204 110 107 1205 261 240 1206 262 93 1207 263 73 1208 262 93 1209 261 240 1210 264 241 1211 262 93 1212 264 241 1213 265 98 1214 265 98 1215 264 241 1216 266 242 1217 265 98 1218 266 242 1219 133 127 1220 133 127 1221 266 242 1222 123 119 1223 133 127 1224 123 119 1225 134 128 1226 134 128 1227 123 119 1228 125 121 1229 124 120 1230 266 242 1231 130 125 1232 266 242 1233 124 120 1234 123 119 1235 130 125 1236 264 241 1237 129 124 1238 264 241 1239 130 125 1240 266 242 1241 129 124 1242 267 199 1243 127 122 1244 267 199 1245 129 124 1246 264 241 1247 267 199 1248 264 241 1249 268 243 1250 268 243 1251 264 241 1252 269 244 1253 269 244 1254 264 241 1255 270 245 1256 270 245 1257 264 241 1258 271 225 1259 271 225 1260 264 241 1261 261 240 1262 271 225 1263 261 240 1264 272 246 1265 272 246 1266 273 247 1267 274 248 1268 273 247 1269 272 246 1270 261 240 1271 274 248 1272 273 247 1273 275 52 1274 274 248 1275 275 52 1276 276 53 1277 274 248 1278 276 53 1279 277 228 1280 274 248 1281 277 228 1282 278 249 1283 278 249 1284 277 228 1285 279 250 1286 278 249 1287 279 250 1288 280 251 1289 278 249 1290 280 251 1291 281 252 1292 281 252 1293 280 251 1294 282 253 1295 281 252 1296 282 253 1297 283 254 1298 283 254 1299 282 253 1300 284 255 1301 283 254 1302 284 255 1303 285 235 1304 283 254 1305 285 235 1306 286 63 1307 286 63 1308 285 235 1309 287 256 1310 286 63 1311 287 256 1312 288 257 1313 288 257 1314 287 256 1315 289 258 1316 288 257 1317 289 258 1318 290 238 1319 290 238 1320 289 258 1321 291 259 1322 290 238 1323 291 259 1324 292 260 1325 128 123 1326 267 199 1327 293 198 1328 267 199 1329 128 123 1330 127 122 1331 294 200 1332 295 261 1333 263 73 1334 295 261 1335 294 200 1336 296 262 1337 295 261 1338 296 262 1339 297 203 1340 297 203 1341 296 262 1342 298 76 1343 298 76 1344 296 262 1345 299 263 1346 299 263 1347 296 262 1348 300 264 1349 299 263 1350 300 264 1351 301 79 1352 301 79 1353 300 264 1354 302 265 1355 302 265 1356 300 264 1357 303 81 1358 302 265 1359 303 81 1360 304 266 1361 304 266 1362 303 81 1363 305 83 1364 304 266 1365 305 83 1366 306 267 1367 306 267 1368 305 83 1369 307 85 1370 307 85 1371 305 83 1372 308 268 1373 307 85 1374 308 268 1375 309 269 1376 309 269 1377 308 268 1378 310 270 1379 309 269 1380 310 270 1381 311 271 1382 311 271 1383 310 270 1384 312 272 1385 311 271 1386 312 272 1387 313 273 1388 313 273 1389 312 272 1390 314 274 1391 293 198 1392 126 3 1393 128 123 1394 126 3 1395 293 198 1396 262 93 1397 262 93 1398 293 198 1399 315 275 1400 262 93 1401 315 275 1402 316 95 1403 262 93 1404 316 95 1405 317 219 1406 262 93 1407 317 219 1408 318 276 1409 262 93 1410 318 276 1411 263 73 1412 263 73 1413 318 276 1414 294 200 1415 262 93 1416 131 4 1417 126 3 1418 131 4 1419 262 93 1420 265 98 1421 265 98 1422 132 126 1423 131 4 1424 132 126 1425 265 98 1426 133 127 1427 319 277 1428 320 278 1429 321 279 1430 320 278 1431 319 277 1432 150 142 1433 150 142 1434 319 277 1435 322 280 1436 150 142 1437 322 280 1438 159 151 1439 159 151 1440 322 280 1441 142 135 1442 159 151 1443 142 135 1444 144 136 1445 143 7 1446 322 280 1447 149 141 1448 322 280 1449 143 7 1450 142 135 1451 147 139 1452 323 281 1453 324 198 1454 323 281 1455 147 139 1456 146 138 1457 325 200 1458 326 261 1459 320 278 1460 326 261 1461 325 200 1462 327 262 1463 326 261 1464 327 262 1465 328 203 1466 328 203 1467 327 262 1468 329 76 1469 329 76 1470 327 262 1471 330 263 1472 330 263 1473 327 262 1474 331 78 1475 330 263 1476 331 78 1477 332 282 1478 332 282 1479 331 78 1480 333 283 1481 333 283 1482 331 78 1483 334 284 1484 333 283 1485 334 284 1486 335 285 1487 335 285 1488 334 284 1489 336 286 1490 335 285 1491 336 286 1492 337 287 1493 337 287 1494 336 286 1495 338 288 1496 338 288 1497 336 286 1498 339 289 1499 338 288 1500 339 289 1501 340 290 1502 340 290 1503 339 289 1504 341 291 1505 340 290 1506 341 291 1507 342 292 1508 342 292 1509 341 291 1510 343 293 1511 342 292 1512 343 293 1513 344 294 1514 344 294 1515 343 293 1516 345 295 1517 324 198 1518 145 137 1519 147 139 1520 145 137 1521 324 198 1522 150 142 1523 150 142 1524 324 198 1525 346 94 1526 150 142 1527 346 94 1528 347 95 1529 150 142 1530 347 95 1531 348 96 1532 150 142 1533 348 96 1534 349 296 1535 150 142 1536 349 296 1537 320 278 1538 320 278 1539 349 296 1540 325 200 1541 149 141 1542 319 277 1543 148 140 1544 319 277 1545 149 141 1546 322 280 1547 148 140 1548 323 281 1549 146 138 1550 323 281 1551 148 140 1552 319 277 1553 323 281 1554 319 277 1555 350 297 1556 350 297 1557 319 277 1558 351 298 1559 351 298 1560 319 277 1561 352 224 1562 352 224 1563 319 277 1564 353 47 1565 353 47 1566 319 277 1567 321 279 1568 353 47 1569 321 279 1570 354 299 1571 354 299 1572 355 300 1573 356 301 1574 355 300 1575 354 299 1576 321 279 1577 356 301 1578 355 300 1579 357 302 1580 356 301 1581 357 302 1582 358 303 1583 356 301 1584 358 303 1585 359 304 1586 356 301 1587 359 304 1588 360 55 1589 360 55 1590 359 304 1591 361 56 1592 360 55 1593 361 56 1594 362 305 1595 360 55 1596 362 305 1597 363 252 1598 363 252 1599 362 305 1600 364 253 1601 363 252 1602 364 253 1603 365 254 1604 365 254 1605 364 253 1606 366 234 1607 365 254 1608 366 234 1609 367 62 1610 365 254 1611 367 62 1612 368 306 1613 368 306 1614 367 62 1615 369 307 1616 368 306 1617 369 307 1618 370 65 1619 370 65 1620 369 307 1621 371 308 1622 370 65 1623 371 308 1624 372 67 1625 372 67 1626 371 308 1627 373 68 1628 372 67 1629 373 68 1630 374 69 1631 185 177 1632 161 153 1633 160 152 1634 161 153 1635 185 177 1636 186 178 1637 188 180 1638 161 153 1639 186 178 1640 161 153 1641 188 180 1642 163 155 1643 188 180 1644 164 156 1645 163 155 1646 164 156 1647 188 180 1648 189 181 1649 189 181 1650 166 158 1651 164 156 1652 166 158 1653 189 181 1654 191 183 1655 192 184 1656 166 158 1657 191 183 1658 166 158 1659 192 184 1660 167 159 1661 194 186 1662 167 159 1663 192 184 1664 167 159 1665 194 186 1666 169 161 1667 195 187 1668 169 161 1669 194 186 1670 169 161 1671 195 187 1672 170 162 1673 196 188 1674 170 162 1675 195 187 1676 170 162 1677 196 188 1678 171 163 1679 197 189 1680 171 163 1681 196 188 1682 171 163 1683 197 189 1684 172 164 1685 199 191 1686 172 164 1687 197 189 1688 172 164 1689 199 191 1690 174 166 1691 198 190 1692 174 166 1693 199 191 1694 174 166 1695 198 190 1696 173 165 1697 173 165 1698 198 190 1699 375 309 1700 173 165 1701 375 309 1702 376 310 1703 376 310 1704 375 309 1705 377 311 1706 377 311 1707 375 309 1708 378 312 1709 377 311 1710 378 312 1711 379 313 1712 379 313 1713 378 312 1714 380 314 1715 379 313 1716 380 314 1717 381 315 1718 381 315 1719 380 314 1720 382 316 1721 381 315 1722 382 316 1723 383 317 1724 381 315 1725 383 317 1726 384 318 1727 384 318 1728 383 317 1729 385 319 1730 384 318 1731 385 319 1732 386 320 1733 173 165 1734 387 321 1735 168 160 1736 387 321 1737 173 165 1738 376 310 1739 165 157 1740 193 185 1741 190 182 1742 193 185 1743 165 157 1744 168 160 1745 193 185 1746 168 160 1747 387 321 1748 193 185 1749 387 321 1750 388 322 1751 388 322 1752 387 321 1753 389 323 1754 388 322 1755 389 323 1756 390 324 1757 390 324 1758 389 323 1759 391 325 1760 390 324 1761 391 325 1762 392 326 1763 392 326 1764 391 325 1765 393 327 1766 392 326 1767 393 327 1768 394 328 1769 394 328 1770 393 327 1771 395 329 1772 394 328 1773 395 329 1774 396 330 1775 396 330 1776 395 329 1777 397 331 1778 396 330 1779 397 331 1780 398 332 1781 165 157 1782 187 179 1783 162 154 1784 187 179 1785 165 157 1786 190 182 1787 162 154 1788 183 175 1789 158 150 1790 183 175 1791 162 154 1792 187 179 1793 158 150 1794 182 174 1795 157 149 1796 182 174 1797 158 150 1798 183 175 1799 157 149 1800 181 173 1801 156 148 1802 181 173 1803 157 149 1804 182 174 1805 156 148 1806 180 172 1807 155 147 1808 180 172 1809 156 148 1810 181 173 1811 154 146 1812 180 172 1813 179 171 1814 180 172 1815 154 146 1816 155 147 1817 154 146 1818 178 170 1819 153 145 1820 178 170 1821 154 146 1822 179 171 1823 152 144 1824 178 170 1825 177 169 1826 178 170 1827 152 144 1828 153 145 1829 151 143 1830 177 169 1831 175 167 1832 177 169 1833 151 143 1834 152 144 1835 388 322 1836 198 190 1837 193 185 1838 198 190 1839 388 322 1840 375 309 1841 200 193 1842 201 194 1843 203 196 1844 202 195 1845 203 196 1846 204 197 1847 205 198 1848 235 222 1849 230 217 1850 235 222 1851 205 198 1852 206 199 1853 399 333 1854 228 215 1855 226 214 1856 228 215 1857 399 333 1858 400 334 1859 228 215 1860 400 334 1861 401 335 1862 260 239 1863 401 335 1864 402 336 1865 401 335 1866 260 239 1867 228 215 1868 228 215 1869 260 239 1870 227 91 1871 227 91 1872 260 239 1873 259 68 1874 259 68 1875 225 213 1876 227 91 1877 225 213 1878 259 68 1879 257 237 1880 255 236 1881 225 213 1882 257 237 1883 225 213 1884 255 236 1885 223 212 1886 255 236 1887 221 210 1888 223 212 1889 221 210 1890 255 236 1891 253 235 1892 253 235 1893 220 209 1894 221 210 1895 220 209 1896 253 235 1897 252 234 1898 250 232 1899 220 209 1900 252 234 1901 220 209 1902 250 232 1903 218 207 1904 248 230 1905 218 207 1906 250 232 1907 218 207 1908 248 230 1909 216 206 1910 248 230 1911 215 205 1912 216 206 1913 215 205 1914 248 230 1915 247 229 1916 245 228 1917 215 205 1918 247 229 1919 215 205 1920 245 228 1921 213 77 1922 244 53 1923 213 77 1924 245 228 1925 213 77 1926 244 53 1927 212 76 1928 243 52 1929 212 76 1930 244 53 1931 212 76 1932 243 52 1933 211 203 1934 243 52 1935 208 201 1936 211 203 1937 208 201 1938 243 52 1939 241 50 1940 239 226 1941 208 201 1942 241 50 1943 208 201 1944 239 226 1945 209 202 1946 230 217 1947 236 223 1948 231 218 1949 236 223 1950 230 217 1951 235 222 1952 231 218 1953 237 224 1954 232 219 1955 237 224 1956 231 218 1957 236 223 1958 232 219 1959 238 225 1960 233 220 1961 238 225 1962 232 219 1963 237 224 1964 233 220 1965 240 49 1966 207 200 1967 240 49 1968 233 220 1969 238 225 1970 210 74 1971 240 49 1972 242 227 1973 240 49 1974 210 74 1975 207 200 1976 210 74 1977 246 55 1978 214 204 1979 246 55 1980 210 74 1981 242 227 1982 214 204 1983 249 231 1984 217 81 1985 249 231 1986 214 204 1987 246 55 1988 217 81 1989 251 233 1990 219 208 1991 251 233 1992 217 81 1993 249 231 1994 219 208 1995 254 63 1996 222 211 1997 254 63 1998 219 208 1999 251 233 2000 222 211 2001 256 65 2002 224 88 2003 256 65 2004 222 211 2005 254 63 2006 226 214 2007 403 337 2008 399 333 2009 403 337 2010 226 214 2011 258 238 2012 258 238 2013 226 214 2014 256 65 2015 256 65 2016 226 214 2017 224 88 2018 260 239 2019 403 337 2020 258 238 2021 403 337 2022 260 239 2023 400 334 2024 400 334 2025 260 239 2026 402 336 2027 261 240 2028 295 261 2029 273 247 2030 295 261 2031 261 240 2032 263 73 2033 275 52 2034 295 261 2035 297 203 2036 295 261 2037 275 52 2038 273 247 2039 276 53 2040 297 203 2041 298 76 2042 297 203 2043 276 53 2044 275 52 2045 277 228 2046 298 76 2047 299 263 2048 298 76 2049 277 228 2050 276 53 2051 279 250 2052 299 263 2053 301 79 2054 299 263 2055 279 250 2056 277 228 2057 280 251 2058 301 79 2059 302 265 2060 301 79 2061 280 251 2062 279 250 2063 280 251 2064 304 266 2065 282 253 2066 304 266 2067 280 251 2068 302 265 2069 284 255 2070 304 266 2071 306 267 2072 304 266 2073 284 255 2074 282 253 2075 285 235 2076 306 267 2077 307 85 2078 306 267 2079 285 235 2080 284 255 2081 287 256 2082 307 85 2083 309 269 2084 307 85 2085 287 256 2086 285 235 2087 287 256 2088 311 271 2089 289 258 2090 311 271 2091 287 256 2092 309 269 2093 289 258 2094 313 273 2095 291 259 2096 313 273 2097 289 258 2098 311 271 2099 404 338 2100 314 274 2101 405 339 2102 314 274 2103 404 338 2104 292 260 2105 314 274 2106 292 260 2107 291 259 2108 314 274 2109 291 259 2110 313 273 2111 292 260 2112 406 340 2113 290 238 2114 406 340 2115 292 260 2116 407 341 2117 407 341 2118 292 260 2119 404 338 2120 312 272 2121 406 340 2122 408 333 2123 406 340 2124 312 272 2125 290 238 2126 290 238 2127 312 272 2128 310 270 2129 290 238 2130 310 270 2131 288 257 2132 308 268 2133 288 257 2134 310 270 2135 288 257 2136 308 268 2137 286 63 2138 305 83 2139 286 63 2140 308 268 2141 286 63 2142 305 83 2143 283 254 2144 303 81 2145 283 254 2146 305 83 2147 283 254 2148 303 81 2149 281 252 2150 300 264 2151 281 252 2152 303 81 2153 281 252 2154 300 264 2155 278 249 2156 296 262 2157 278 249 2158 300 264 2159 278 249 2160 296 262 2161 274 248 2162 294 200 2163 274 248 2164 296 262 2165 274 248 2166 294 200 2167 272 246 2168 318 276 2169 272 246 2170 294 200 2171 272 246 2172 318 276 2173 271 225 2174 317 219 2175 271 225 2176 318 276 2177 271 225 2178 317 219 2179 270 245 2180 316 95 2181 270 245 2182 317 219 2183 270 245 2184 316 95 2185 269 244 2186 315 275 2187 269 244 2188 316 95 2189 269 244 2190 315 275 2191 268 243 2192 293 198 2193 268 243 2194 315 275 2195 268 243 2196 293 198 2197 267 199 2198 408 333 2199 314 274 2200 312 272 2201 314 274 2202 408 333 2203 407 341 2204 314 274 2205 407 341 2206 405 339 2207 321 279 2208 326 261 2209 355 300 2210 326 261 2211 321 279 2212 320 278 2213 324 198 2214 350 297 2215 346 94 2216 350 297 2217 324 198 2218 323 281 2219 346 94 2220 351 298 2221 347 95 2222 351 298 2223 346 94 2224 350 297 2225 347 95 2226 352 224 2227 348 96 2228 352 224 2229 347 95 2230 351 298 2231 348 96 2232 353 47 2233 349 296 2234 353 47 2235 348 96 2236 352 224 2237 349 296 2238 354 299 2239 325 200 2240 354 299 2241 349 296 2242 353 47 2243 327 262 2244 354 299 2245 356 301 2246 354 299 2247 327 262 2248 325 200 2249 327 262 2250 360 55 2251 331 78 2252 360 55 2253 327 262 2254 356 301 2255 331 78 2256 363 252 2257 334 284 2258 363 252 2259 331 78 2260 360 55 2261 334 284 2262 365 254 2263 336 286 2264 365 254 2265 334 284 2266 363 252 2267 336 286 2268 368 306 2269 339 289 2270 368 306 2271 336 286 2272 365 254 2273 339 289 2274 370 65 2275 341 291 2276 370 65 2277 339 289 2278 368 306 2279 343 293 2280 409 342 2281 410 343 2282 409 342 2283 343 293 2284 372 67 2285 372 67 2286 343 293 2287 341 291 2288 372 67 2289 341 291 2290 370 65 2291 410 343 2292 345 295 2293 343 293 2294 345 295 2295 410 343 2296 411 344 2297 345 295 2298 411 344 2299 412 345 2300 413 346 2301 345 295 2302 412 345 2303 345 295 2304 413 346 2305 374 69 2306 345 295 2307 374 69 2308 373 68 2309 345 295 2310 373 68 2311 344 294 2312 371 308 2313 344 294 2314 373 68 2315 344 294 2316 371 308 2317 342 292 2318 369 307 2319 342 292 2320 371 308 2321 342 292 2322 369 307 2323 340 290 2324 367 62 2325 340 290 2326 369 307 2327 340 290 2328 367 62 2329 338 288 2330 366 234 2331 338 288 2332 367 62 2333 338 288 2334 366 234 2335 337 287 2336 366 234 2337 335 285 2338 337 287 2339 335 285 2340 366 234 2341 364 253 2342 364 253 2343 333 283 2344 335 285 2345 333 283 2346 364 253 2347 362 305 2348 362 305 2349 332 282 2350 333 283 2351 332 282 2352 362 305 2353 361 56 2354 361 56 2355 330 263 2356 332 282 2357 330 263 2358 361 56 2359 359 304 2360 359 304 2361 329 76 2362 330 263 2363 329 76 2364 359 304 2365 358 303 2366 358 303 2367 328 203 2368 329 76 2369 328 203 2370 358 303 2371 357 302 2372 355 300 2373 328 203 2374 357 302 2375 328 203 2376 355 300 2377 326 261 2378 374 69 2379 409 342 2380 372 67 2381 409 342 2382 374 69 2383 411 344 2384 411 344 2385 374 69 2386 413 346 2387 414 347 2388 386 320 2389 385 319 2390 386 320 2391 414 347 2392 415 348 2393 415 348 2394 414 347 2395 416 349 2396 415 348 2397 416 349 2398 417 350 2399 417 350 2400 416 349 2401 418 351 2402 417 350 2403 418 351 2404 419 352 2405 384 318 2406 397 331 2407 395 329 2408 397 331 2409 384 318 2410 420 353 2411 420 353 2412 384 318 2413 415 348 2414 415 348 2415 384 318 2416 386 320 2417 381 315 2418 395 329 2419 393 327 2420 395 329 2421 381 315 2422 384 318 2423 379 313 2424 393 327 2425 391 325 2426 393 327 2427 379 313 2428 381 315 2429 377 311 2430 391 325 2431 389 323 2432 391 325 2433 377 311 2434 379 313 2435 376 310 2436 389 323 2437 387 321 2438 389 323 2439 376 310 2440 377 311 2441 390 324 2442 375 309 2443 388 322 2444 375 309 2445 390 324 2446 378 312 2447 392 326 2448 378 312 2449 390 324 2450 378 312 2451 392 326 2452 380 314 2453 394 328 2454 380 314 2455 392 326 2456 380 314 2457 394 328 2458 382 316 2459 396 330 2460 382 316 2461 394 328 2462 382 316 2463 396 330 2464 383 317 2465 398 332 2466 383 317 2467 396 330 2468 383 317 2469 398 332 2470 421 354 2471 383 317 2472 421 354 2473 414 347 2474 383 317 2475 414 347 2476 385 319 2477 420 353 2478 398 332 2479 397 331 2480 398 332 2481 420 353 2482 421 354 2483 421 354 2484 420 353 2485 422 355 2486 421 354 2487 422 355 2488 423 356 2489 423 356 2490 422 355 2491 424 357 2492 423 356 2493 424 357 2494 425 358 2495 403 337 2496 400 334 2497 399 333 2498 401 335 2499 400 334 2500 402 336 2501 404 338 2502 405 339 2503 407 341 2504 406 340 2505 407 341 2506 408 333 2507 409 342 2508 411 344 2509 410 343 2510 413 346 2511 412 345 2512 411 344 2513 426 359 2514 419 352 2515 418 351 2516 419 352 2517 426 359 2518 427 360 2519 427 360 2520 426 359 2521 428 361 2522 427 360 2523 428 361 2524 429 362 2525 429 362 2526 428 361 2527 430 363 2528 429 362 2529 430 363 2530 431 364 2531 417 350 2532 424 357 2533 422 355 2534 424 357 2535 417 350 2536 432 365 2537 432 365 2538 417 350 2539 427 360 2540 427 360 2541 417 350 2542 419 352 2543 415 348 2544 422 355 2545 420 353 2546 422 355 2547 415 348 2548 417 350 2549 423 356 2550 414 347 2551 421 354 2552 414 347 2553 423 356 2554 416 349 2555 425 358 2556 416 349 2557 423 356 2558 416 349 2559 425 358 2560 433 366 2561 416 349 2562 433 366 2563 426 359 2564 416 349 2565 426 359 2566 418 351 2567 432 365 2568 425 358 2569 424 357 2570 425 358 2571 432 365 2572 433 366 2573 433 366 2574 432 365 2575 434 367 2576 433 366 2577 434 367 2578 435 368 2579 435 368 2580 434 367 2581 436 369 2582 436 369 2583 434 367 2584 437 370 2585 438 371 2586 431 364 2587 430 363 2588 431 364 2589 438 371 2590 439 372 2591 439 372 2592 438 371 2593 440 373 2594 439 372 2595 440 373 2596 441 374 2597 441 374 2598 440 373 2599 442 375 2600 441 374 2601 442 375 2602 443 376 2603 443 376 2604 442 375 2605 444 377 2606 444 377 2607 442 375 2608 445 378 2609 429 362 2610 437 370 2611 434 367 2612 437 370 2613 429 362 2614 446 379 2615 446 379 2616 429 362 2617 439 372 2618 439 372 2619 429 362 2620 431 364 2621 427 360 2622 434 367 2623 432 365 2624 434 367 2625 427 360 2626 429 362 2627 435 368 2628 426 359 2629 433 366 2630 426 359 2631 435 368 2632 428 361 2633 436 369 2634 428 361 2635 435 368 2636 428 361 2637 436 369 2638 447 380 2639 428 361 2640 447 380 2641 438 371 2642 428 361 2643 438 371 2644 430 363 2645 446 379 2646 436 369 2647 437 370 2648 436 369 2649 446 379 2650 447 380 2651 447 380 2652 446 379 2653 448 381 2654 447 380 2655 448 381 2656 449 382 2657 449 382 2658 448 381 2659 450 383 2660 449 382 2661 450 383 2662 451 384 2663 451 384 2664 450 383 2665 452 385 2666 452 385 2667 450 383 2668 453 386 2669 449 382 2670 438 371 2671 447 380 2672 438 371 2673 449 382 2674 440 373 2675 451 384 2676 440 373 2677 449 382 2678 440 373 2679 451 384 2680 442 375 2681 452 385 2682 442 375 2683 451 384 2684 442 375 2685 452 385 2686 454 387 2687 442 375 2688 454 387 2689 455 388 2690 442 375 2691 455 388 2692 456 389 2693 442 375 2694 456 389 2695 457 390 2696 442 375 2697 457 390 2698 445 378 2699 445 378 2700 457 390 2701 458 391 2702 458 391 2703 457 390 2704 459 392 2705 445 378 2706 460 393 2707 444 377 2708 460 393 2709 445 378 2710 458 391 2711 443 376 2712 453 386 2713 450 383 2714 453 386 2715 443 376 2716 461 394 2717 461 394 2718 443 376 2719 462 395 2720 462 395 2721 443 376 2722 463 396 2723 463 396 2724 443 376 2725 464 397 2726 464 397 2727 443 376 2728 444 377 2729 464 397 2730 444 377 2731 460 393 2732 464 397 2733 460 393 2734 465 398 2735 441 374 2736 450 383 2737 448 381 2738 450 383 2739 441 374 2740 443 376 2741 439 372 2742 448 381 2743 446 379 2744 448 381 2745 439 372 2746 441 374 2747 461 394 2748 452 385 2749 453 386 2750 452 385 2751 461 394 2752 454 387 2753 466 399 2754 457 390 2755 456 389 2756 457 390 2757 466 399 2758 467 400 2759 457 390 2760 467 400 2761 468 401 2762 457 390 2763 468 401 2764 469 402 2765 459 392 2766 464 397 2767 465 398 2768 464 397 2769 459 392 2770 457 390 2771 464 397 2772 457 390 2773 470 403 2774 470 403 2775 457 390 2776 469 402 2777 458 391 2778 465 398 2779 460 393 2780 465 398 2781 458 391 2782 459 392 2783 462 395 2784 454 387 2785 461 394 2786 454 387 2787 462 395 2788 455 388 2789 463 396 2790 455 388 2791 462 395 2792 455 388 2793 463 396 2794 456 389 2795 456 389 2796 463 396 2797 471 404 2798 456 389 2799 471 404 2800 466 399 2801 464 397 2802 471 404 2803 463 396 2804 471 404 2805 464 397 2806 472 405 2807 472 405 2808 464 397 2809 473 406 2810 473 406 2811 464 397 2812 470 403 2813 474 407 2814 468 401 2815 467 400 2816 468 401 2817 474 407 2818 475 408 2819 469 402 2820 473 406 2821 470 403 2822 473 406 2823 469 402 2824 468 401 2825 473 406 2826 468 401 2827 476 409 2828 476 409 2829 468 401 2830 475 408 2831 476 409 2832 475 408 2833 477 410 2834 476 409 2835 477 410 2836 478 411 2837 471 404 2838 467 400 2839 466 399 2840 467 400 2841 471 404 2842 472 405 2843 467 400 2844 472 405 2845 479 412 2846 467 400 2847 479 412 2848 474 407 2849 474 407 2850 479 412 2851 480 413 2852 480 413 2853 479 412 2854 481 414 2855 473 406 2856 479 412 2857 472 405 2858 479 412 2859 473 406 2860 476 409 2861 480 413 2862 475 408 2863 474 407 2864 475 408 2865 480 413 2866 482 415 2867 475 408 2868 482 415 2869 483 416 2870 475 408 2871 483 416 2872 477 410 2873 483 416 2874 478 411 2875 477 410 2876 478 411 2877 483 416 2878 484 417 2879 484 417 2880 483 416 2881 485 418 2882 484 417 2883 485 418 2884 486 419 2885 486 419 2886 485 418 2887 487 420 2888 487 420 2889 485 418 2890 488 421 2891 476 409 2892 481 414 2893 479 412 2894 481 414 2895 476 409 2896 489 422 2897 489 422 2898 476 409 2899 484 417 2900 484 417 2901 476 409 2902 478 411 2903 481 414 2904 482 415 2905 480 413 2906 482 415 2907 481 414 2908 489 422 2909 482 415 2910 489 422 2911 490 423 2912 482 415 2913 490 423 2914 491 424 2915 491 424 2916 490 423 2917 492 425 2918 491 424 2919 492 425 2920 493 426 2921 491 424 2922 483 416 2923 482 415 2924 483 416 2925 491 424 2926 485 418 2927 494 427 2928 487 420 2929 488 421 2930 487 420 2931 494 427 2932 495 428 2933 495 428 2934 494 427 2935 496 429 2936 495 428 2937 496 429 2938 497 430 2939 497 430 2940 496 429 2941 498 431 2942 497 430 2943 498 431 2944 499 432 2945 486 419 2946 492 425 2947 490 423 2948 492 425 2949 486 419 2950 500 433 2951 500 433 2952 486 419 2953 495 428 2954 495 428 2955 486 419 2956 487 420 2957 484 417 2958 490 423 2959 489 422 2960 490 423 2961 484 417 2962 486 419 2963 493 426 2964 485 418 2965 491 424 2966 485 418 2967 493 426 2968 501 434 2969 485 418 2970 501 434 2971 494 427 2972 485 418 2973 494 427 2974 488 421 2975 492 425 2976 501 434 2977 493 426 2978 501 434 2979 492 425 2980 500 433 2981 501 434 2982 500 433 2983 502 435 2984 502 435 2985 500 433 2986 503 436 2987 502 435 2988 503 436 2989 504 437 2990 504 437 2991 503 436 2992 505 438 2993 498 431 2994 506 439 2995 499 432 2996 506 439 2997 498 431 2998 507 440 2999 506 439 3000 507 440 3001 508 441 3002 508 441 3003 507 440 3004 509 442 3005 497 430 3006 505 438 3007 503 436 3008 505 438 3009 497 430 3010 510 443 3011 510 443 3012 497 430 3013 506 439 3014 506 439 3015 497 430 3016 499 432 3017 495 428 3018 503 436 3019 500 433 3020 503 436 3021 495 428 3022 497 430 3023 502 435 3024 494 427 3025 501 434 3026 494 427 3027 502 435 3028 496 429 3029 504 437 3030 496 429 3031 502 435 3032 496 429 3033 504 437 3034 511 444 3035 496 429 3036 511 444 3037 507 440 3038 496 429 3039 507 440 3040 498 431 3041 510 443 3042 504 437 3043 505 438 3044 504 437 3045 510 443 3046 511 444 3047 511 444 3048 510 443 3049 512 445 3050 511 444 3051 512 445 3052 513 446 3053 514 447 3054 508 441 3055 509 442 3056 508 441 3057 514 447 3058 515 448 3059 515 448 3060 514 447 3061 516 449 3062 515 448 3063 516 449 3064 517 450 3065 506 439 3066 512 445 3067 510 443 3068 512 445 3069 506 439 3070 508 441 3071 513 446 3072 507 440 3073 511 444 3074 507 440 3075 513 446 3076 509 442 3077 518 451 3078 513 446 3079 512 445 3080 513 446 3081 518 451 3082 519 452 3083 519 452 3084 518 451 3085 520 453 3086 520 453 3087 518 451 3088 521 454 3089 516 449 3090 522 455 3091 517 450 3092 522 455 3093 516 449 3094 523 456 3095 522 455 3096 523 456 3097 524 457 3098 524 457 3099 523 456 3100 525 458 3101 524 457 3102 525 458 3103 526 459 3104 526 459 3105 525 458 3106 527 460 3107 515 448 3108 521 454 3109 518 451 3110 521 454 3111 515 448 3112 528 461 3113 528 461 3114 515 448 3115 522 455 3116 522 455 3117 515 448 3118 517 450 3119 508 441 3120 518 451 3121 512 445 3122 518 451 3123 508 441 3124 515 448 3125 519 452 3126 509 442 3127 513 446 3128 509 442 3129 519 452 3130 514 447 3131 520 453 3132 514 447 3133 519 452 3134 514 447 3135 520 453 3136 529 462 3137 514 447 3138 529 462 3139 523 456 3140 514 447 3141 523 456 3142 516 449 3143 521 454 3144 529 462 3145 520 453 3146 529 462 3147 521 454 3148 528 461 3149 529 462 3150 528 461 3151 530 463 3152 529 462 3153 530 463 3154 531 464 3155 531 464 3156 530 463 3157 532 465 3158 531 464 3159 532 465 3160 533 466 3161 527 460 3162 534 467 3163 526 459 3164 534 467 3165 527 460 3166 535 468 3167 534 467 3168 535 468 3169 536 469 3170 536 469 3171 535 468 3172 537 470 3173 524 457 3174 532 465 3175 530 463 3176 532 465 3177 524 457 3178 538 471 3179 538 471 3180 524 457 3181 534 467 3182 534 467 3183 524 457 3184 526 459 3185 522 455 3186 530 463 3187 528 461 3188 530 463 3189 522 455 3190 524 457 3191 531 464 3192 523 456 3193 529 462 3194 523 456 3195 531 464 3196 525 458 3197 533 466 3198 525 458 3199 531 464 3200 525 458 3201 533 466 3202 539 472 3203 525 458 3204 539 472 3205 535 468 3206 525 458 3207 535 468 3208 527 460 3209 532 465 3210 539 472 3211 533 466 3212 539 472 3213 532 465 3214 538 471 3215 539 472 3216 538 471 3217 540 473 3218 539 472 3219 540 473 3220 541 474 3221 542 475 3222 536 469 3223 537 470 3224 536 469 3225 542 475 3226 543 476 3227 534 467 3228 540 473 3229 538 471 3230 540 473 3231 534 467 3232 544 477 3233 544 477 3234 534 467 3235 545 478 3236 545 478 3237 534 467 3238 546 479 3239 546 479 3240 534 467 3241 547 480 3242 547 480 3243 534 467 3244 548 481 3245 548 481 3246 534 467 3247 549 482 3248 549 482 3249 534 467 3250 550 483 3251 550 483 3252 534 467 3253 551 484 3254 551 484 3255 534 467 3256 552 485 3257 552 485 3258 534 467 3259 553 486 3260 553 486 3261 534 467 3262 536 469 3263 553 486 3264 536 469 3265 543 476 3266 553 486 3267 543 476 3268 554 487 3269 554 487 3270 543 476 3271 555 488 3272 556 489 3273 557 490 3274 558 491 3275 557 490 3276 556 489 3277 559 492 3278 557 490 3279 559 492 3280 560 493 3281 560 493 3282 559 492 3283 546 479 3284 546 479 3285 559 492 3286 561 494 3287 546 479 3288 561 494 3289 562 495 3290 546 479 3291 562 495 3292 563 496 3293 546 479 3294 563 496 3295 564 497 3296 546 479 3297 564 497 3298 565 498 3299 546 479 3300 565 498 3301 566 499 3302 546 479 3303 566 499 3304 567 500 3305 546 479 3306 567 500 3307 568 501 3308 546 479 3309 568 501 3310 545 478 3311 569 502 3312 570 503 3313 571 504 3314 570 503 3315 569 502 3316 572 505 3317 572 505 3318 569 502 3319 573 506 3320 572 505 3321 573 506 3322 574 507 3323 572 505 3324 574 507 3325 575 508 3326 575 508 3327 574 507 3328 576 509 3329 576 509 3330 574 507 3331 577 510 3332 577 510 3333 574 507 3334 578 511 3335 578 511 3336 574 507 3337 579 512 3338 579 512 3339 574 507 3340 580 513 3341 580 513 3342 574 507 3343 581 514 3344 581 514 3345 574 507 3346 582 515 3347 582 515 3348 574 507 3349 583 516 3350 541 474 3351 535 468 3352 539 472 3353 535 468 3354 541 474 3355 584 517 3356 535 468 3357 584 517 3358 583 516 3359 535 468 3360 583 516 3361 574 507 3362 535 468 3363 574 507 3364 585 518 3365 535 468 3366 585 518 3367 586 519 3368 535 468 3369 586 519 3370 587 520 3371 535 468 3372 587 520 3373 588 521 3374 535 468 3375 588 521 3376 589 522 3377 535 468 3378 589 522 3379 590 523 3380 535 468 3381 590 523 3382 591 524 3383 535 468 3384 591 524 3385 537 470 3386 537 470 3387 591 524 3388 542 475 3389 542 475 3390 591 524 3391 592 525 3392 542 475 3393 592 525 3394 593 526 3395 540 473 3396 584 517 3397 541 474 3398 584 517 3399 540 473 3400 544 477 3401 593 526 3402 543 476 3403 542 475 3404 543 476 3405 593 526 3406 555 488 3407 593 526 3408 554 487 3409 555 488 3410 554 487 3411 593 526 3412 592 525 3413 591 524 3414 554 487 3415 592 525 3416 554 487 3417 591 524 3418 553 486 3419 591 524 3420 552 485 3421 553 486 3422 552 485 3423 591 524 3424 590 523 3425 590 523 3426 551 484 3427 552 485 3428 551 484 3429 590 523 3430 589 522 3431 588 521 3432 551 484 3433 589 522 3434 551 484 3435 588 521 3436 550 483 3437 587 520 3438 550 483 3439 588 521 3440 550 483 3441 587 520 3442 549 482 3443 586 519 3444 549 482 3445 587 520 3446 549 482 3447 586 519 3448 548 481 3449 585 518 3450 548 481 3451 586 519 3452 548 481 3453 585 518 3454 547 480 3455 585 518 3456 546 479 3457 547 480 3458 546 479 3459 585 518 3460 574 507 3461 573 506 3462 546 479 3463 574 507 3464 546 479 3465 573 506 3466 560 493 3467 573 506 3468 557 490 3469 560 493 3470 557 490 3471 573 506 3472 569 502 3473 557 490 3474 569 502 3475 594 527 3476 594 527 3477 569 502 3478 595 528 3479 596 529 3480 597 530 3481 598 531 3482 597 530 3483 596 529 3484 558 491 3485 597 530 3486 558 491 3487 594 527 3488 594 527 3489 558 491 3490 557 490 3491 558 491 3492 570 503 3493 556 489 3494 570 503 3495 558 491 3496 571 504 3497 571 504 3498 558 491 3499 596 529 3500 571 504 3501 596 529 3502 599 532 3503 556 489 3504 572 505 3505 559 492 3506 572 505 3507 556 489 3508 570 503 3509 561 494 3510 572 505 3511 575 508 3512 572 505 3513 561 494 3514 559 492 3515 561 494 3516 576 509 3517 562 495 3518 576 509 3519 561 494 3520 575 508 3521 562 495 3522 577 510 3523 563 496 3524 577 510 3525 562 495 3526 576 509 3527 563 496 3528 578 511 3529 564 497 3530 578 511 3531 563 496 3532 577 510 3533 564 497 3534 579 512 3535 565 498 3536 579 512 3537 564 497 3538 578 511 3539 565 498 3540 580 513 3541 566 499 3542 580 513 3543 565 498 3544 579 512 3545 566 499 3546 581 514 3547 567 500 3548 581 514 3549 566 499 3550 580 513 3551 568 501 3552 581 514 3553 582 515 3554 581 514 3555 568 501 3556 567 500 3557 568 501 3558 583 516 3559 545 478 3560 583 516 3561 568 501 3562 582 515 3563 545 478 3564 584 517 3565 544 477 3566 584 517 3567 545 478 3568 583 516 3569 600 533 3570 599 532 3571 601 534 3572 599 532 3573 600 533 3574 571 504 3575 571 504 3576 600 533 3577 595 528 3578 571 504 3579 595 528 3580 569 502 3581 600 533 3582 594 527 3583 595 528 3584 594 527 3585 600 533 3586 597 530 3587 597 530 3588 600 533 3589 602 535 3590 602 535 3591 600 533 3592 603 536 3593 604 537 3594 605 538 3595 606 539 3596 605 538 3597 604 537 3598 598 531 3599 605 538 3600 598 531 3601 602 535 3602 602 535 3603 598 531 3604 597 530 3605 598 531 3606 599 532 3607 596 529 3608 599 532 3609 598 531 3610 601 534 3611 601 534 3612 598 531 3613 604 537 3614 601 534 3615 604 537 3616 607 540 3617 608 541 3618 607 540 3619 609 542 3620 607 540 3621 608 541 3622 601 534 3623 601 534 3624 608 541 3625 603 536 3626 601 534 3627 603 536 3628 600 533 3629 603 536 3630 605 538 3631 602 535 3632 605 538 3633 603 536 3634 608 541 3635 605 538 3636 608 541 3637 610 543 3638 610 543 3639 608 541 3640 611 544 3641 612 545 3642 613 546 3643 614 547 3644 613 546 3645 612 545 3646 606 539 3647 613 546 3648 606 539 3649 610 543 3650 610 543 3651 606 539 3652 605 538 3653 606 539 3654 607 540 3655 604 537 3656 607 540 3657 606 539 3658 609 542 3659 609 542 3660 606 539 3661 612 545 3662 609 542 3663 612 545 3664 615 548 3665 616 549 3666 615 548 3667 617 550 3668 615 548 3669 616 549 3670 609 542 3671 609 542 3672 616 549 3673 611 544 3674 609 542 3675 611 544 3676 608 541 3677 611 544 3678 613 546 3679 610 543 3680 613 546 3681 611 544 3682 616 549 3683 613 546 3684 616 549 3685 618 551 3686 618 551 3687 616 549 3688 619 552 3689 620 553 3690 621 554 3691 622 555 3692 621 554 3693 620 553 3694 614 547 3695 621 554 3696 614 547 3697 618 551 3698 618 551 3699 614 547 3700 613 546 3701 612 545 3702 617 550 3703 615 548 3704 617 550 3705 612 545 3706 614 547 3707 617 550 3708 614 547 3709 623 556 3710 623 556 3711 614 547 3712 620 553 3713 624 557 3714 623 556 3715 625 558 3716 623 556 3717 624 557 3718 617 550 3719 617 550 3720 624 557 3721 619 552 3722 617 550 3723 619 552 3724 616 549 3725 619 552 3726 621 554 3727 618 551 3728 621 554 3729 619 552 3730 624 557 3731 621 554 3732 624 557 3733 626 559 3734 626 559 3735 624 557 3736 627 560 3737 628 561 3738 629 562 3739 630 563 3740 629 562 3741 628 561 3742 622 555 3743 629 562 3744 622 555 3745 626 559 3746 626 559 3747 622 555 3748 621 554 3749 620 553 3750 625 558 3751 623 556 3752 625 558 3753 620 553 3754 622 555 3755 625 558 3756 622 555 3757 628 561 3758 625 558 3759 628 561 3760 631 564 3761 632 565 3762 631 564 3763 633 566 3764 631 564 3765 632 565 3766 625 558 3767 625 558 3768 632 565 3769 627 560 3770 625 558 3771 627 560 3772 624 557 3773 627 560 3774 629 562 3775 626 559 3776 629 562 3777 627 560 3778 632 565 3779 629 562 3780 632 565 3781 634 567 3782 634 567 3783 632 565 3784 635 568 3785 630 563 3786 636 569 3787 637 570 3788 636 569 3789 630 563 3790 629 562 3791 636 569 3792 629 562 3793 634 567 3794 636 569 3795 634 567 3796 638 571 3797 630 563 3798 631 564 3799 628 561 3800 631 564 3801 630 563 3802 633 566 3803 633 566 3804 630 563 3805 637 570 3806 633 566 3807 637 570 3808 639 572 3809 640 573 3810 633 566 3811 639 572 3812 633 566 3813 640 573 3814 632 565 3815 632 565 3816 640 573 3817 635 568 3818 635 568 3819 640 573 3820 641 574 3821 635 568 3822 638 571 3823 634 567 3824 638 571 3825 635 568 3826 641 574 3827 638 571 3828 641 574 3829 642 575 3830 642 575 3831 641 574 3832 643 576 3833 638 571 3834 644 577 3835 636 569 3836 644 577 3837 638 571 3838 645 578 3839 645 578 3840 638 571 3841 642 575 3842 646 579 3843 645 578 3844 642 575 3845 637 570 3846 640 573 3847 639 572 3848 640 573 3849 637 570 3850 636 569 3851 640 573 3852 636 569 3853 644 577 3854 640 573 3855 644 577 3856 647 580 3857 648 581 3858 643 576 3859 649 582 3860 647 580 3861 641 574 3862 640 573 3863 641 574 3864 647 580 3865 649 582 3866 641 574 3867 649 582 3868 643 576 3869 648 581 3870 642 575 3871 643 576 3872 642 575 3873 648 581 3874 646 579 3875 646 579 3876 648 581 3877 650 583 3878 650 583 3879 648 581 3880 651 584 3881 646 579 3882 652 585 3883 645 578 3884 652 585 3885 646 579 3886 653 586 3887 653 586 3888 646 579 3889 650 583 3890 653 586 3891 650 583 3892 654 587 3893 645 578 3894 647 580 3895 644 577 3896 647 580 3897 645 578 3898 649 582 3899 649 582 3900 645 578 3901 655 588 3902 655 588 3903 645 578 3904 652 585 3905 655 588 3906 648 581 3907 649 582 3908 648 581 3909 655 588 3910 656 589 3911 648 581 3912 656 589 3913 651 584 3914 651 584 3915 656 589 3916 657 590 3917 657 590 3918 650 583 3919 651 584 3920 650 583 3921 657 590 3922 654 587 3923 654 587 3924 657 590 3925 658 591 3926 658 591 3927 657 590 3928 659 592 3929 654 587 3930 660 593 3931 653 586 3932 660 593 3933 654 587 3934 661 594 3935 661 594 3936 654 587 3937 658 591 3938 661 594 3939 658 591 3940 662 595 3941 652 585 3942 656 589 3943 655 588 3944 656 589 3945 652 585 3946 653 586 3947 656 589 3948 653 586 3949 663 596 3950 663 596 3951 653 586 3952 660 593 3953 663 596 3954 657 590 3955 656 589 3956 657 590 3957 663 596 3958 664 597 3959 657 590 3960 664 597 3961 659 592 3962 659 592 3963 664 597 3964 665 598 3965 665 598 3966 658 591 3967 659 592 3968 658 591 3969 665 598 3970 662 595 3971 662 595 3972 665 598 3973 666 599 3974 662 595 3975 666 599 3976 667 600 3977 662 595 3978 668 601 3979 661 594 3980 668 601 3981 662 595 3982 669 602 3983 669 602 3984 662 595 3985 667 600 3986 669 602 3987 667 600 3988 670 603 3989 661 594 3990 663 596 3991 660 593 3992 663 596 3993 661 594 3994 664 597 3995 664 597 3996 661 594 3997 671 604 3998 671 604 3999 661 594 4000 668 601 4001 671 604 4002 665 598 4003 664 597 4004 665 598 4005 671 604 4006 672 605 4007 665 598 4008 672 605 4009 666 599 4010 666 599 4011 672 605 4012 673 606 4013 666 599 4014 670 603 4015 667 600 4016 670 603 4017 666 599 4018 673 606 4019 670 603 4020 673 606 4021 674 607 4022 670 603 4023 674 607 4024 675 608 4025 670 603 4026 676 609 4027 669 602 4028 676 609 4029 670 603 4030 677 610 4031 677 610 4032 670 603 4033 675 608 4034 677 610 4035 675 608 4036 678 611 4037 668 601 4038 672 605 4039 671 604 4040 672 605 4041 668 601 4042 669 602 4043 672 605 4044 669 602 4045 676 609 4046 672 605 4047 676 609 4048 679 612 4049 679 612 4050 673 606 4051 672 605 4052 673 606 4053 679 612 4054 680 613 4055 673 606 4056 680 613 4057 674 607 4058 674 607 4059 680 613 4060 681 614 4061 674 607 4062 678 611 4063 675 608 4064 678 611 4065 674 607 4066 681 614 4067 678 611 4068 681 614 4069 682 615 4070 678 611 4071 683 616 4072 677 610 4073 683 616 4074 678 611 4075 682 615 4076 677 610 4077 679 612 4078 676 609 4079 679 612 4080 677 610 4081 680 613 4082 680 613 4083 677 610 4084 683 616 4085 683 616 4086 681 614 4087 680 613 4088 681 614 4089 683 616 4090 682 615 4091

+
+
+
+
+ + + + + 1 0 0 -0.02701864 0 1 0 -2.56998e-6 0 0 1 0.00128819 0 0 0 1 + + + + + + + + + + + + + +
\ No newline at end of file diff --git a/cram_pr2/cram_pr2_pick_place_demo/resource/knife.dae b/cram_demos/cram_projection_demos/resource/household/knife.dae similarity index 100% rename from cram_pr2/cram_pr2_pick_place_demo/resource/knife.dae rename to cram_demos/cram_projection_demos/resource/household/knife.dae diff --git a/cram_pr2/cram_pr2_pick_place_demo/resource/milk.dae b/cram_demos/cram_projection_demos/resource/household/milk.dae similarity index 100% rename from cram_pr2/cram_pr2_pick_place_demo/resource/milk.dae rename to cram_demos/cram_projection_demos/resource/household/milk.dae diff --git a/cram_pr2/cram_pr2_pick_place_demo/resource/milk.stl b/cram_demos/cram_projection_demos/resource/household/milk.stl similarity index 100% rename from cram_pr2/cram_pr2_pick_place_demo/resource/milk.stl rename to cram_demos/cram_projection_demos/resource/household/milk.stl diff --git a/cram_pr2/cram_pr2_pick_place_demo/resource/red_metal_plate.stl b/cram_demos/cram_projection_demos/resource/household/red_metal_plate.stl similarity index 100% rename from cram_pr2/cram_pr2_pick_place_demo/resource/red_metal_plate.stl rename to cram_demos/cram_projection_demos/resource/household/red_metal_plate.stl diff --git a/cram_pr2/cram_pr2_pick_place_demo/resource/spoon.dae b/cram_demos/cram_projection_demos/resource/household/spoon.dae similarity index 100% rename from cram_pr2/cram_pr2_pick_place_demo/resource/spoon.dae rename to cram_demos/cram_projection_demos/resource/household/spoon.dae diff --git a/cram_pr2/cram_pr2_pick_place_demo/resource/spoon.stl b/cram_demos/cram_projection_demos/resource/household/spoon.stl similarity index 100% rename from cram_pr2/cram_pr2_pick_place_demo/resource/spoon.stl rename to cram_demos/cram_projection_demos/resource/household/spoon.stl diff --git a/cram_demos/cram_projection_demos/resource/household/tray-base.stl b/cram_demos/cram_projection_demos/resource/household/tray-base.stl new file mode 100644 index 0000000000..c2f092d1f5 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/household/tray-base.stl differ diff --git a/cram_demos/cram_projection_demos/resource/household/tray.stl b/cram_demos/cram_projection_demos/resource/household/tray.stl new file mode 100644 index 0000000000..0595766cb5 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/household/tray.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/balea-bottle.stl b/cram_demos/cram_projection_demos/resource/retail/balea-bottle.stl new file mode 100644 index 0000000000..36f3f3b51a Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/balea-bottle.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/basket1.stl b/cram_demos/cram_projection_demos/resource/retail/basket1.stl new file mode 100644 index 0000000000..cd7a972583 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/basket1.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/basket2.dae b/cram_demos/cram_projection_demos/resource/retail/basket2.dae new file mode 100644 index 0000000000..48279188d2 --- /dev/null +++ b/cram_demos/cram_projection_demos/resource/retail/basket2.dae @@ -0,0 +1,1341 @@ + + + + + SketchUp 6.4.245 + + 2017-12-17T21:50:06Z + 2017-12-17T21:50:06Z + + Z_UP + + + + + + + 35 + 0 + 1 + 1000 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0.8463224 -0.02189584 0.5322208 126.0873 0.5326711 0.03478871 -0.845607 -34.08389 -3.469447e-18 0.9991548 0.04110575 42.55851 0 0 0 1 + + + + 0.8463223 -0.5326711 0 10.28253 0.5326711 0.8463223 0 10.99287 -0 0 1 0 0 0 0 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 3.892457 -7.11058e-17 2.866858 3.655764 -7.11058e-17 3.073114 3.949213 -7.11058e-17 2.185975 3.503039 -2.931504e-16 3.627106 3.050582 -7.11058e-17 3.600473 2.07298 -2.931504e-16 3.972726 3.149508 -7.11058e-17 3.956831 2.310179 -2.931504e-16 4.465705 1.095378 -7.11058e-17 3.988236 0.2256372 -7.11058e-17 4.084641 0.8791916 -2.931504e-16 4.451951 1.512129 -2.931504e-16 4.561978 -0.2391257 -7.11058e-17 3.026582 -0.4186123 -7.11058e-17 3.186904 -0.3632656 -7.11058e-17 2.39065 0.2574336 -2.931504e-16 3.569452 + + + + + + + + + + -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 -3.474156e-18 -1 -9.381262e-17 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 4 3 5 5 3 6 5 6 7 5 7 8 8 7 9 9 7 10 10 7 11 12 13 14 13 12 15 13 15 9 9 15 8

+
+
+
+ + + + 1.376066 -3.623819e-15 58.88633 0.9739964 -4.511998e-15 59.11934 -0.3285532 -4.511998e-15 58.91904 3.016875 -3.401775e-15 59.99305 3.112569 -3.401775e-15 60.10702 0.2914635 -4.511998e-15 58.62689 -1.487429 -3.623819e-15 58.66472 -0.7282479 -2.957686e-15 58.56203 -2.716527 -2.735641e-15 59.17059 + + + + + + + + + + -2.458718e-16 -1 8.634661e-16 -2.458718e-16 -1 8.634661e-16 -2.458718e-16 -1 8.634661e-16 -2.458718e-16 -1 8.634661e-16 -2.458718e-16 -1 8.634661e-16 -2.458718e-16 -1 8.634661e-16 -2.458718e-16 -1 8.634661e-16 -2.458718e-16 -1 8.634661e-16 -2.458718e-16 -1 8.634661e-16 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 5 6 7 6 5 0 6 0 2 6 2 8

+
+
+
+ + + + -8.699609 -2.069507e-15 30.24236 -9.150825 -1.181329e-15 30.18223 -8.880096 -7.372396e-16 30.07699 -8.541683 -1.847463e-15 31.73071 -9.60956 -3.623819e-15 32.13662 -9.083142 -1.847463e-15 31.72319 -8.383758 -2.291552e-15 31.89608 -9.150825 -2.957686e-15 33.29422 -10.34655 -3.845864e-15 33.88806 -9.556919 -2.735641e-15 34.85022 -9.635688 -2.957686e-15 30.08142 -9.272521 -3.17973e-15 30.0436 -10.97487 -2.957686e-15 30.64861 -8.73721 -1.181329e-15 30.51297 -9.353872 -1.181329e-15 30.95647 -11.0602 -1.625418e-15 30.76447 -12.15346 -2.735641e-15 32.24876 -9.88781 3.729834e-16 31.52775 -10.30142 -1.847463e-15 32.17421 -10.49695 -1.181329e-15 32.89583 -12.3897 -2.735641e-15 32.56951 -12.46521 -2.291552e-15 35.09825 -9.855484 -1.403373e-15 35.28573 -11.08748 -2.069507e-15 35.49858 -12.15346 -2.735641e-15 32.24876 -11.28507 -2.069507e-15 30.8528 -11.0602 -1.625418e-15 30.76447 -12.09463 -5.15195e-16 31.85106 + + + + + + + + + + 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 1.289031e-16 -1 -7.363092e-17 -5.621437e-15 -1 -4.277625e-15 -5.621437e-15 -1 -4.277625e-15 -5.621437e-15 -1 -4.277625e-15 -5.621437e-15 -1 -4.277625e-15 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.2004856 -3.623819e-15 64.85642 -0.6044442 -3.845864e-15 63.77693 -0.08506865 -6.510399e-15 63.5462 -0.6703965 -9.592842e-16 64.55976 -1.049623 -6.288355e-15 65.17779 0.02359036 -6.288355e-15 65.37478 -1.338165 -2.513596e-15 65.51565 0.5208183 -7.842667e-15 66.08923 -1.700903 -5.178132e-15 65.75462 4.555837 -3.845864e-15 68.42454 4.330499 -4.067909e-15 68.05356 4.913725 -1.403373e-15 67.88132 3.063003 -1.181329e-15 68.24538 1.822798 -2.957686e-15 68.30372 0.7139095 -5.622221e-15 68.49332 5.059532 -2.069507e-15 68.66302 3.9461 -5.400176e-15 70.18668 3.124282 -4.511998e-15 69.9747 3.985866 -2.735641e-15 69.68321 2.050616 -4.511998e-15 70.7299 0.9902048 -3.623819e-15 70.51791 1.997595 -3.623819e-15 70.34567 0.9504393 -2.735641e-15 70.79615 -0.3618191 -9.592842e-16 70.58416 -1.91076 -4.734043e-15 63.64485 -2.816906 -2.957686e-15 63.16121 -2.544323 -1.181329e-15 62.97352 -3.16951 -2.735641e-15 64.75897 -2.038909 -4.734043e-15 63.80165 -2.426379 -4.511998e-15 64.69161 -2.426379 -7.11058e-17 65.30964 -3.639648 -5.178132e-15 66.25099 -2.129594 -2.513596e-15 65.69693 0.4275881 -4.956087e-15 66.82438 -3.486853 -4.956087e-15 67.89573 0.8626627 -4.956087e-15 68.0669 -2.84053 -3.845864e-15 69.35198 4.650138 -3.845864e-15 69.20109 4.87396 -4.734043e-15 69.31223 -1.634312 -1.847463e-15 70.27943 3.044751 -7.176533e-15 70.30593 -0.7594733 -4.511998e-15 70.7829 -0.2097926 -2.513596e-15 71.09924 3.968377 -4.067909e-15 67.77191 + + + + + + + + + + -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 -5.569153e-17 -1 5.774896e-17 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 0.07751133 -2.931504e-16 1.290536 -0.6875039 -7.11058e-17 1.261942 -0.5625031 -7.11058e-17 0.8246356 -0.6312535 -7.11058e-17 1.443112 -0.2035019 -7.11058e-17 1.524609 -0.2856781 -7.11058e-17 1.81676 -0.3632656 -7.11058e-17 2.39065 + + + + + + + + + + -2.53243e-16 -1 6.170692e-17 -2.53243e-16 -1 6.170692e-17 -2.53243e-16 -1 6.170692e-17 -2.53243e-16 -1 6.170692e-17 -2.53243e-16 -1 6.170692e-17 -2.53243e-16 -1 6.170692e-17 -2.53243e-16 -1 6.170692e-17 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 0 4 3 4 5 3 5 6

+
+
+
+ + + + 0.02499985 -7.11058e-17 0.5747459 -0.6125033 -7.11058e-17 0.4747901 -0.4750025 -7.11058e-17 0.1749228 -0.5851946 -7.11058e-17 0.6658659 0.4500021 -7.11058e-17 0.6122292 0.6125033 -7.11058e-17 0.787152 -0.5625031 -7.11058e-17 0.8246356 0.4365828 -7.11058e-17 1.118883 0.07751133 -2.931504e-16 1.290536 0 -7.11058e-17 0 -2.229968 -7.11058e-17 -0.08746155 -0.6332961 -7.11058e-17 -0.08746155 -2.61632 -7.11058e-17 0.5809267 -0.4750025 -7.11058e-17 0.1749228 -0.6125033 -7.11058e-17 0.4747901 -0.5851946 -7.11058e-17 0.6658659 -1.937342 -7.11058e-17 0.7194317 + + + + + + + + + + 3.162529e-17 -1 -1.616798e-16 3.162529e-17 -1 -1.616798e-16 3.162529e-17 -1 -1.616798e-16 3.162529e-17 -1 -1.616798e-16 3.162529e-17 -1 -1.616798e-16 3.162529e-17 -1 -1.616798e-16 3.162529e-17 -1 -1.616798e-16 3.162529e-17 -1 -1.616798e-16 3.162529e-17 -1 -1.616798e-16 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 0 4 3 4 5 3 5 6 6 5 7 6 7 8 9 10 11 10 9 12 12 9 13 12 13 14 12 14 15 12 15 16

+
+
+
+ + + + 8.686465 -4.511998e-15 34.776 8.311984 -9.592842e-16 37.6255 8.436186 -1.847463e-15 34.74946 11.25639 -1.847463e-15 34.94384 11.62401 -1.403373e-15 34.95637 11.48848 -3.17973e-15 37.7923 7.732379 -1.847463e-15 42.30165 11.62351 -2.957686e-15 38.84664 11.62331 -3.623819e-15 40.35734 11.26292 -3.17973e-15 45.09838 7.2268 5.95028e-16 46.52386 11.01484 -2.069507e-15 46.76356 6.412227 -5.400176e-15 48.64962 6.967613 -4.511998e-15 48.73178 10.28516 -2.513596e-15 49.99597 + + + + + + + + + + 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 1.183999e-17 -1 -4.864905e-17 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 1 4 5 1 5 6 6 5 7 6 7 8 6 8 9 6 9 10 10 9 11 10 11 12 12 11 13 13 11 14

+
+
+
+ + + + 2.200012 -7.11058e-17 0 0 -7.11058e-17 0 1.062505 -7.11058e-17 -0.08746155 3.200017 -7.11058e-17 0.8371299 -0.4750025 -7.11058e-17 0.1749228 0.02499985 -7.11058e-17 0.5747459 0.4500021 -7.11058e-17 0.6122292 0.6125033 -7.11058e-17 0.787152 0.4365828 -7.11058e-17 1.118883 3.810939 -7.11058e-17 1.925333 0.07751133 -2.931504e-16 1.290536 -0.2035019 -7.11058e-17 1.524609 -0.2856781 -7.11058e-17 1.81676 -0.03739845 -7.11058e-17 2.375139 3.143686 -7.11058e-17 2.607797 0.676406 -7.11058e-17 2.871477 2.445399 -7.11058e-17 2.902498 1.51435 -7.11058e-17 3.042093 + + + + + + + + + + 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 7.235522e-18 -1 -1.808741e-18 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 4 3 5 5 3 6 6 3 7 7 3 8 8 3 9 8 9 10 10 9 11 11 9 12 12 9 13 13 9 14 13 14 15 15 14 16 15 16 17

+
+
+
+ + + + 4.148516 -2.735641e-15 64.18445 -0.08506865 -6.510399e-15 63.5462 4.624403 -3.623819e-15 63.02912 -0.2004856 -3.623819e-15 64.85642 4.119428 -1.847463e-15 64.75432 4.538299 -6.06631e-15 65.44632 0.02359036 -6.288355e-15 65.37478 0.5208183 -7.842667e-15 66.08923 4.317228 -6.954489e-15 66.44069 0.4275881 -4.956087e-15 66.82438 4.194989 -3.17973e-15 67.39926 0.8626627 -4.956087e-15 68.0669 3.968377 -4.067909e-15 67.77191 3.063003 -1.181329e-15 68.24538 1.822798 -2.957686e-15 68.30372 0.7139095 -5.622221e-15 68.49332 0.9739964 -4.511998e-15 59.11934 -2.716527 -2.735641e-15 59.17059 -0.3285532 -4.511998e-15 58.91904 3.112569 -3.401775e-15 60.10702 -3.627505 -4.289953e-15 60.13898 3.319971 -2.735641e-15 60.35404 -3.584125 -5.178132e-15 60.4425 3.213513 -2.513596e-15 60.37299 3.410831 1.509388e-16 60.62535 -3.237086 -1.625418e-15 60.76048 3.400432 -5.178132e-15 61.167 -2.835603 -2.513596e-15 61.19022 3.785802 -4.956087e-15 62.17978 -2.544323 -1.181329e-15 62.97352 3.84089 -3.17973e-15 62.64231 4.5795 -3.623819e-15 62.78329 -1.91076 -4.734043e-15 63.64485 -0.6044442 -3.845864e-15 63.77693 -2.038909 -4.734043e-15 63.80165 -0.6703965 -9.592842e-16 64.55976 -2.426379 -4.511998e-15 64.69161 -1.049623 -6.288355e-15 65.17779 -2.426379 -7.11058e-17 65.30964 -1.338165 -2.513596e-15 65.51565 -2.129594 -2.513596e-15 65.69693 -1.700903 -5.178132e-15 65.75462 + + + + + + + + + + -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 -2.105892e-18 -1 -1.179111e-16 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 9.02875 -5.15195e-16 29.68473 8.775303 -2.931504e-16 30.05464 8.933047 -9.592842e-16 29.59148 9.242663 -1.847463e-15 29.6977 10.45619 -2.069507e-15 30.56953 9.356983 -2.069507e-15 30.84301 11.42322 -2.291552e-15 32.49641 9.652752 -2.291552e-15 31.72007 9.613316 -9.592842e-16 32.43945 9.366842 -1.625418e-15 33.30665 11.48522 -2.513596e-15 33.99952 8.864034 -2.513596e-15 30.99083 8.371085 -2.957686e-15 30.95141 8.548547 -3.401775e-15 30.85286 8.292213 -1.403373e-15 32.20294 9.130226 -1.847463e-15 31.84818 9.120367 -2.291552e-15 32.40989 8.42038 -2.291552e-15 34.21327 11.25639 -1.847463e-15 34.94384 8.686465 -4.511998e-15 34.776 + + + + + + + + + + 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 1.926707e-16 -1 -2.898039e-16 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 1 4 5 5 4 6 5 6 7 7 6 8 8 6 9 9 6 10 11 12 13 12 11 14 14 11 15 14 15 16 14 16 17 17 16 9 17 9 10 17 10 18 17 18 19

+
+
+
+ + + + 3.949213 -7.11058e-17 2.185975 3.143686 -7.11058e-17 2.607797 3.810939 -7.11058e-17 1.925333 3.655764 -7.11058e-17 3.073114 2.445399 -7.11058e-17 2.902498 1.51435 -7.11058e-17 3.042093 -0.03739845 -7.11058e-17 2.375139 -0.3632656 -7.11058e-17 2.39065 -0.2856781 -7.11058e-17 1.81676 0.676406 -7.11058e-17 2.871477 -0.2391257 -7.11058e-17 3.026582 0.2574336 -2.931504e-16 3.569452 3.050582 -7.11058e-17 3.600473 1.095378 -7.11058e-17 3.988236 2.07298 -2.931504e-16 3.972726 + + + + + + + + + + 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 5.651384e-18 -1 -5.922121e-17 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 4 3 5 6 7 8 7 6 9 7 9 10 10 9 5 10 5 11 11 5 3 11 3 12 11 12 13 13 12 14

+
+
+
+ + + + -0.5625031 -7.11058e-17 0.8246356 -1.937342 -7.11058e-17 0.7194317 -0.5851946 -7.11058e-17 0.6658659 -2.385319 -7.11058e-17 1.360664 -2.61632 -7.11058e-17 0.5809267 -0.8026566 -7.11058e-17 0.9194414 -0.9599727 -7.11058e-17 1.717766 -1.663174 -7.11058e-17 1.962182 -1.024971 -7.11058e-17 2.047612 + + + + + + + + + + 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 + + + + + + + + + + + + + + +

0 1 2 1 3 4 3 1 0 3 0 5 3 5 6 3 6 7 7 6 8

+
+
+
+ + + + 7.129938 -3.401775e-15 39.03096 7.024295 -3.845864e-15 35.60014 7.377742 -1.181329e-15 35.57307 6.080943 -1.181329e-15 35.6724 -7.087642 -1.181329e-15 36.4229 -6.584432 -2.735641e-15 42.71022 6.646375 -3.401775e-15 44.69384 -6.761216 -9.592842e-16 49.32586 6.276589 -1.847463e-15 48.62955 6.412227 -5.400176e-15 48.64962 6.967613 -4.511998e-15 48.73178 10.28516 -2.513596e-15 49.99597 -6.636205 -3.17973e-15 34.80158 -7.294847 -7.11058e-17 34.60328 1.121015 -2.735641e-15 35.10383 -6.978891 -1.181329e-15 49.32048 -10.9849 -6.732444e-15 50.95156 -7.433722 -4.289953e-15 49.31781 -6.870616 -9.592842e-16 49.32112 10.5565 -2.513596e-15 50.10338 9.094294 -5.178132e-15 55.81307 -11.74802 -1.403373e-15 51.30264 -9.127466 -1.181329e-15 57.58239 8.381689 -2.957686e-15 57.61984 -8.481249 -4.734043e-15 58.46157 -0.7282479 -2.957686e-15 58.56203 7.182426 -4.511998e-15 58.8012 0.2914635 -4.511998e-15 58.62689 1.376066 -3.623819e-15 58.88633 3.845346 -2.513596e-15 60.26052 3.016875 -3.401775e-15 59.99305 3.112569 -3.401775e-15 60.10702 3.319971 -2.735641e-15 60.35404 -7.027259 -2.735641e-15 59.39458 -1.487429 -3.623819e-15 58.66472 -2.716527 -2.735641e-15 59.17059 -3.627505 -4.289953e-15 60.13898 -4.061304 -4.289953e-15 60.61594 -3.584125 -5.178132e-15 60.4425 -3.237086 -1.625418e-15 60.76048 + + + + + + + + + + -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 -4.021744e-17 -1 -5.870165e-17 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -9.658083 -1.403373e-15 36.97898 -9.855484 -1.403373e-15 35.28573 -9.692526 -1.847463e-15 35.25758 -11.08748 -2.069507e-15 35.49858 -6.978891 -1.181329e-15 49.32048 -7.433722 -4.289953e-15 49.31781 -8.550982 -3.623819e-15 43.58936 -12.46521 -2.291552e-15 35.09825 -12.71122 -1.181329e-15 42.07124 -12.93021 -2.291552e-15 34.72395 -9.279205 -2.735641e-15 37.75361 -8.848663 -3.17973e-15 40.50785 -10.9849 -6.732444e-15 50.95156 + + + + + + + + + + 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 2.117878e-16 -1 -1.852814e-16 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 7 8 9 8 7 3 8 3 0 8 0 10 8 10 11 8 11 6 8 6 12 12 6 5

+
+
+
+ + + + -0.6875039 -7.11058e-17 1.261942 -0.8026566 -7.11058e-17 0.9194414 -0.5625031 -7.11058e-17 0.8246356 -0.9599727 -7.11058e-17 1.717766 -0.6312535 -7.11058e-17 1.443112 -0.3632656 -7.11058e-17 2.39065 -1.024971 -7.11058e-17 2.047612 4.011514 -7.11058e-17 3.996891 3.892457 -7.11058e-17 2.866858 4.26624 -7.11058e-17 2.773632 3.503039 -2.931504e-16 3.627106 3.149508 -7.11058e-17 3.956831 2.310179 -2.931504e-16 4.465705 5.003464 -7.372396e-16 8.475154 1.512129 -2.931504e-16 4.561978 -1.549515 -5.15195e-16 6.546715 -1.937112 -5.15195e-16 7.012807 -4.260262 -7.372396e-16 15.9837 5.509694 -7.372396e-16 13.80151 5.349832 -2.069507e-15 17.3968 -4.041846 -7.372396e-16 16.73789 -3.595336 -7.372396e-16 17.0419 -6.350576 -2.069507e-15 27.75496 5.330935 -1.403373e-15 19.75652 6.204863 -1.403373e-15 23.99185 6.602104 -2.291552e-15 29.70955 -6.686256 -2.735641e-15 29.92575 6.867097 -2.957686e-15 31.1451 -6.636205 -3.17973e-15 34.80158 1.121015 -2.735641e-15 35.10383 7.024295 -3.845864e-15 35.60014 6.080943 -1.181329e-15 35.6724 -1.663174 -7.11058e-17 1.962182 -1.840465 -7.11058e-17 2.68922 -2.20437 -7.11058e-17 1.793184 -0.4186123 -7.11058e-17 3.186904 0.2256372 -7.11058e-17 4.084641 0.8791916 -2.931504e-16 4.451951 + + + + + + + + + + -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 -1.569141e-18 -1 -8.151927e-17 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + -0.2300517 -4.067909e-15 61.41776 1.349407 -2.513596e-15 60.31828 2.266968 -3.401775e-15 60.17539 3.016875 -1.625418e-15 60.23916 3.213513 -2.513596e-15 60.37299 + + + + + + + + + + + + + +

1 0 1 2 2 3 3 4

+
+
+
+ + + + 10.10626 -1.181329e-15 30.73461 9.02875 -5.15195e-16 29.68473 10.73724 -2.735641e-15 32.17338 + + + + + + + + + + + + + +

1 0 0 2

+
+
+
+ + + + -10.31646 -1.181329e-15 30.73096 -9.150825 -1.181329e-15 30.18223 -11.60995 -1.847463e-15 32.4373 + + + + + + + + + + + + + +

1 0 0 2

+
+
+
+ + + + -1.560754 -2.957686e-15 63.21658 -1.91076 -4.734043e-15 63.64485 -1.263968 -2.957686e-15 63.21658 -1.016647 -5.622221e-15 63.45555 + + + + + + + + + + + + + +

1 0 0 2 2 3

+
+
+
+ + + + -1.389596 -7.11058e-17 3.897956 -1.024971 -7.11058e-17 2.047612 -1.161918 -7.11058e-17 6.080624 -0.6226979 -2.931504e-16 13.67195 -0.02460687 -7.11058e-17 17.17918 -0.3037158 -2.069507e-15 23.11756 0.01526583 -2.291552e-15 29.73348 + + + + + + + + + + + + + +

1 0 0 2 2 3 3 4 4 5 5 6

+
+
+
+ + + + 6.262331 -4.067909e-15 52.07277 6.276589 -1.847463e-15 48.62955 + + + + + + + + + + + + + +

1 0

+
+
+
+ + + + -2.671783 -1.181329e-15 17.6707 -3.595336 -7.372396e-16 17.0419 + + + + + + + + + + + + + +

1 0

+
+
+
+ + + + -6.904132 5.95028e-16 52.62575 -6.761216 -9.592842e-16 49.32586 + + + + + + + + + + + + + +

1 0

+
+
+
+ + + + 71.18867 63.3252 16.32867 50.88542 44.44507 16.32867 50.88542 63.3252 16.32867 71.18867 44.44507 16.32867 71.18867 44.44507 16.32867 71.18867 63.3252 16.32867 50.88542 44.44507 16.32867 50.88542 63.3252 16.32867 + + + + + + + + + + 0 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 2 1 0 3

+
+ + +

4 5 6 7 6 5

+
+
+
+ + + + 58.80693 57.69237 36.58725 59.15071 57.69237 36.58725 58.97882 57.69237 36.56462 58.64676 57.69237 36.6536 59.31088 57.69237 36.6536 58.50921 57.69237 36.75914 59.44843 57.69237 36.75914 58.40367 57.69237 36.89669 59.55397 57.69237 36.89669 58.33733 57.69237 37.05686 59.62032 57.69237 37.05686 58.3147 57.69237 37.22875 59.64295 57.69237 37.22875 58.33733 57.69237 37.40064 59.62032 57.69237 37.40064 58.40367 57.69237 37.56081 59.55397 57.69237 37.56081 58.50921 57.69237 37.69836 59.44843 57.69237 37.69836 58.64676 57.69237 37.8039 59.31088 57.69237 37.8039 58.80693 57.69237 37.87025 59.15071 57.69237 37.87025 58.97882 57.69237 37.89287 59.64295 57.69237 37.22875 59.62032 50.67162 37.40064 59.64295 50.67162 37.22875 59.62032 57.69237 37.40064 59.62032 57.69237 37.05686 59.62032 50.67162 37.05686 59.55397 57.69237 36.89669 59.55397 50.67162 36.89669 59.44843 57.69237 36.75914 59.44843 50.67162 36.75914 59.31088 50.67162 36.6536 59.31088 57.69237 36.6536 59.15071 50.67162 36.58725 59.15071 57.69237 36.58725 58.97882 50.67162 36.56462 58.97882 57.69237 36.56462 58.80693 50.67162 36.58725 58.80693 57.69237 36.58725 58.64676 50.67162 36.6536 58.64676 57.69237 36.6536 58.50921 50.67162 36.75914 58.50921 57.69237 36.75914 58.40367 57.69237 36.89669 58.40367 50.67162 36.89669 58.33733 57.69237 37.05686 58.33733 50.67162 37.05686 58.3147 57.69237 37.22875 58.3147 50.67162 37.22875 58.33733 57.69237 37.40064 58.33733 50.67162 37.40064 58.40367 57.69237 37.56081 58.40367 50.67162 37.56081 58.50921 57.69237 37.69836 58.50921 50.67162 37.69836 58.64676 50.67162 37.8039 58.64676 57.69237 37.8039 58.80693 50.67162 37.87025 58.80693 57.69237 37.87025 58.97882 50.67162 37.89287 58.97882 57.69237 37.89287 59.15071 50.67162 37.87025 59.15071 57.69237 37.87025 59.31088 50.67162 37.8039 59.31088 57.69237 37.8039 59.44843 50.67162 37.69836 59.44843 57.69237 37.69836 59.55397 57.69237 37.56081 59.55397 50.67162 37.56081 59.15071 50.67162 36.58725 58.80693 50.67162 36.58725 58.97882 50.67162 36.56462 59.31088 50.67162 36.6536 58.64676 50.67162 36.6536 59.44843 50.67162 36.75914 58.50921 50.67162 36.75914 59.55397 50.67162 36.89669 58.40367 50.67162 36.89669 59.62032 50.67162 37.05686 58.33733 50.67162 37.05686 59.64295 50.67162 37.22875 58.3147 50.67162 37.22875 59.62032 50.67162 37.40064 58.33733 50.67162 37.40064 59.55397 50.67162 37.56081 58.40367 50.67162 37.56081 59.44843 50.67162 37.69836 58.50921 50.67162 37.69836 59.31088 50.67162 37.8039 58.64676 50.67162 37.8039 59.15071 50.67162 37.87025 58.80693 50.67162 37.87025 58.97882 50.67162 37.89287 + + + + + + + + + + -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -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 1.069333e-14 0.9659258 0 0.258819 1 0 1.069333e-14 0.9659258 0 0.258819 0.9659258 0 -0.258819 0.9659258 0 -0.258819 0.8660254 0 -0.5 0.8660254 0 -0.5 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.5 0 -0.8660254 0.5 0 -0.8660254 0.258819 0 -0.9659258 0.258819 0 -0.9659258 5.337755e-15 0 -1 5.337755e-15 0 -1 -0.258819 0 -0.9659258 -0.258819 0 -0.9659258 -0.5 0 -0.8660254 -0.5 0 -0.8660254 -0.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 -0.8660254 0 -0.5 -0.8660254 0 -0.5 -0.9659258 0 -0.258819 -0.9659258 0 -0.258819 -1 0 1.070224e-14 -1 0 1.070224e-14 -0.9659258 0 0.258819 -0.9659258 0 0.258819 -0.8660254 0 0.5 -0.8660254 0 0.5 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.5 0 0.8660254 -0.5 0 0.8660254 -0.258819 0 0.9659258 -0.258819 0 0.9659258 5.346666e-15 0 1 5.346666e-15 0 1 0.258819 0 0.9659258 0.258819 0 0.9659258 0.5 0 0.8660254 0.5 0 0.8660254 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.8660254 0 0.5 0.8660254 0 0.5 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 4 3 5 4 5 6 6 5 7 6 7 8 8 7 9 8 9 10 10 9 11 10 11 12 12 11 13 12 13 14 14 13 15 14 15 16 16 15 17 16 17 18 18 17 19 18 19 20 20 19 21 20 21 22 22 21 23 24 25 26 25 24 27 28 26 29 26 28 24 30 29 31 29 30 28 32 31 33 31 32 30 32 34 35 34 32 33 35 36 37 36 35 34 37 38 39 38 37 36 39 40 41 40 39 38 41 42 43 42 41 40 43 44 45 44 43 42 46 44 47 44 46 45 48 47 49 47 48 46 50 49 51 49 50 48 52 51 53 51 52 50 54 53 55 53 54 52 56 55 57 55 56 54 58 56 57 56 58 59 60 59 58 59 60 61 62 61 60 61 62 63 64 63 62 63 64 65 66 65 64 65 66 67 68 67 66 67 68 69 70 68 71 68 70 69 27 71 25 71 27 70 72 73 74 73 72 75 73 75 76 76 75 77 76 77 78 78 77 79 78 79 80 80 79 81 80 81 82 82 81 83 82 83 84 84 83 85 84 85 86 86 85 87 86 87 88 88 87 89 88 89 90 90 89 91 90 91 92 92 91 93 92 93 94 94 93 95

+
+
+
+ + + + 63.58951 57.78542 36.58725 63.42933 50.76467 36.6536 63.42933 57.78542 36.6536 63.58951 50.76467 36.58725 63.58951 57.78542 36.58725 63.93328 57.78542 36.58725 63.76139 57.78542 36.56462 63.42933 57.78542 36.6536 64.09346 57.78542 36.6536 63.29179 57.78542 36.75914 64.231 57.78542 36.75914 63.18624 57.78542 36.89669 64.33654 57.78542 36.89669 63.1199 57.78542 37.05686 64.40289 57.78542 37.05686 63.09727 57.78542 37.22875 64.42552 57.78542 37.22875 63.1199 57.78542 37.40064 64.40289 57.78542 37.40064 63.18624 57.78542 37.56081 64.33654 57.78542 37.56081 63.29179 57.78542 37.69836 64.231 57.78542 37.69836 63.42933 57.78542 37.8039 64.09346 57.78542 37.8039 63.58951 57.78542 37.87025 63.93328 57.78542 37.87025 63.76139 57.78542 37.89287 63.76139 57.78542 36.56462 63.76139 50.76467 36.56462 63.93328 50.76467 36.58725 63.58951 50.76467 36.58725 63.76139 50.76467 36.56462 64.09346 50.76467 36.6536 63.42933 50.76467 36.6536 64.231 50.76467 36.75914 63.29179 50.76467 36.75914 64.33654 50.76467 36.89669 63.18624 50.76467 36.89669 64.40289 50.76467 37.05686 63.1199 50.76467 37.05686 64.42552 50.76467 37.22875 63.09727 50.76467 37.22875 64.40289 50.76467 37.40064 63.1199 50.76467 37.40064 64.33654 50.76467 37.56081 63.18624 50.76467 37.56081 64.231 50.76467 37.69836 63.29179 50.76467 37.69836 64.09346 50.76467 37.8039 63.42933 50.76467 37.8039 63.93328 50.76467 37.87025 63.58951 50.76467 37.87025 63.76139 50.76467 37.89287 63.29179 50.76467 36.75914 63.29179 57.78542 36.75914 64.42552 57.78542 37.22875 64.40289 50.76467 37.40064 64.42552 50.76467 37.22875 64.40289 57.78542 37.40064 64.40289 57.78542 37.05686 64.40289 50.76467 37.05686 64.33654 57.78542 36.89669 64.33654 50.76467 36.89669 64.231 57.78542 36.75914 64.231 50.76467 36.75914 64.09346 50.76467 36.6536 64.09346 57.78542 36.6536 63.93328 50.76467 36.58725 63.93328 57.78542 36.58725 63.18624 57.78542 36.89669 63.18624 50.76467 36.89669 63.1199 57.78542 37.05686 63.1199 50.76467 37.05686 63.09727 57.78542 37.22875 63.09727 50.76467 37.22875 63.1199 57.78542 37.40064 63.1199 50.76467 37.40064 63.18624 57.78542 37.56081 63.18624 50.76467 37.56081 63.29179 57.78542 37.69836 63.29179 50.76467 37.69836 63.42933 50.76467 37.8039 63.42933 57.78542 37.8039 63.58951 50.76467 37.87025 63.58951 57.78542 37.87025 63.76139 50.76467 37.89287 63.76139 57.78542 37.89287 63.93328 50.76467 37.87025 63.93328 57.78542 37.87025 64.09346 50.76467 37.8039 64.09346 57.78542 37.8039 64.231 50.76467 37.69836 64.231 57.78542 37.69836 64.33654 57.78542 37.56081 64.33654 50.76467 37.56081 + + + + + + + + + + -0.258819 0 -0.9659258 -0.5 0 -0.8660254 -0.5 0 -0.8660254 -0.258819 0 -0.9659258 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -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.069333e-14 0 -1 -1.069333e-14 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.7071068 0 -0.7071068 -0.7071068 0 -0.7071068 1 0 5.346666e-15 0.9659258 0 0.258819 1 0 5.346666e-15 0.9659258 0 0.258819 0.9659258 0 -0.258819 0.9659258 0 -0.258819 0.8660254 0 -0.5 0.8660254 0 -0.5 0.7071068 0 -0.7071068 0.7071068 0 -0.7071068 0.5 0 -0.8660254 0.5 0 -0.8660254 0.258819 0 -0.9659258 0.258819 0 -0.9659258 -0.8660254 0 -0.5 -0.8660254 0 -0.5 -0.9659258 0 -0.258819 -0.9659258 0 -0.258819 -1 0 5.346666e-15 -1 0 5.346666e-15 -0.9659258 0 0.258819 -0.9659258 0 0.258819 -0.8660254 0 0.5 -0.8660254 0 0.5 -0.7071068 0 0.7071068 -0.7071068 0 0.7071068 -0.5 0 0.8660254 -0.5 0 0.8660254 -0.258819 0 0.9659258 -0.258819 0 0.9659258 -1.069333e-14 0 1 -1.069333e-14 0 1 0.258819 0 0.9659258 0.258819 0 0.9659258 0.5 0 0.8660254 0.5 0 0.8660254 0.7071068 0 0.7071068 0.7071068 0 0.7071068 0.8660254 0 0.5 0.8660254 0 0.5 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 5 4 7 5 7 8 8 7 9 8 9 10 10 9 11 10 11 12 12 11 13 12 13 14 14 13 15 14 15 16 16 15 17 16 17 18 18 17 19 18 19 20 20 19 21 20 21 22 22 21 23 22 23 24 24 23 25 24 25 26 26 25 27 28 3 0 3 28 29 30 31 32 31 30 33 31 33 34 34 33 35 34 35 36 36 35 37 36 37 38 38 37 39 38 39 40 40 39 41 40 41 42 42 41 43 42 43 44 44 43 45 44 45 46 46 45 47 46 47 48 48 47 49 48 49 50 50 49 51 50 51 52 52 51 53 2 54 55 54 2 1 56 57 58 57 56 59 60 58 61 58 60 56 62 61 63 61 62 60 64 63 65 63 64 62 64 66 67 66 64 65 67 68 69 68 67 66 69 29 28 29 69 68 70 54 71 54 70 55 72 71 73 71 72 70 74 73 75 73 74 72 76 75 77 75 76 74 78 77 79 77 78 76 80 79 81 79 80 78 82 80 81 80 82 83 84 83 82 83 84 85 86 85 84 85 86 87 88 87 86 87 88 89 90 89 88 89 90 91 92 91 90 91 92 93 94 92 95 92 94 93 59 95 57 95 59 94

+
+
+
+ + + + 62.43954 44.44507 16.81251 63.25985 44.44507 16.8197 62.43954 44.44507 20.60751 64.49323 44.44507 16.8197 63.25985 44.44507 20.6147 61.20616 44.44507 20.60751 65.1287 44.44507 16.82624 64.49323 44.44507 20.6147 67.36574 44.44507 16.82465 68.50424 44.44507 16.82465 66.36207 44.44507 16.82624 65.1287 44.44507 20.62124 69.09191 44.44507 16.82564 68.50424 44.44507 20.61965 70.32528 44.44507 16.82564 69.09191 44.44507 20.62064 67.36574 44.44507 20.61965 55.5985 44.44507 16.84117 56.71984 44.44507 16.9052 55.5985 44.44507 20.63617 57.95322 44.44507 16.9052 56.71984 44.44507 20.7002 54.36512 44.44507 20.63617 53.30409 44.44507 20.65508 52.07072 44.44507 20.65508 53.30409 44.44507 16.86008 54.36512 44.44507 16.84117 58.93008 44.44507 16.84062 58.93008 44.44507 20.63562 57.95322 44.44507 20.7002 60.16345 44.44507 16.84062 61.20616 44.44507 16.81251 60.16345 44.44507 20.63562 66.36207 44.44507 20.62124 62.34295 44.44507 21.08863 63.16326 44.44507 21.09582 62.34295 44.44507 24.88363 64.39663 44.44507 21.09582 63.16326 44.44507 24.89082 61.10957 44.44507 24.88363 65.0321 44.44507 21.10236 64.39663 44.44507 24.89082 67.26915 44.44507 21.10077 68.40765 44.44507 21.10077 66.26548 44.44507 21.10236 65.0321 44.44507 24.89736 68.99532 44.44507 21.10177 68.40765 44.44507 24.89577 70.22869 44.44507 21.10177 68.99532 44.44507 24.89677 67.26915 44.44507 24.89577 55.50191 44.44507 21.11729 56.62325 44.44507 21.18132 55.50191 44.44507 24.91229 57.85663 44.44507 21.18132 56.62325 44.44507 24.97632 54.26853 44.44507 24.91229 53.2075 44.44507 24.9312 51.97412 44.44507 24.9312 53.2075 44.44507 21.1362 54.26853 44.44507 21.11729 58.83349 44.44507 21.11675 58.83349 44.44507 24.91175 57.85663 44.44507 24.97632 60.06686 44.44507 21.11675 61.10957 44.44507 21.08863 60.06686 44.44507 24.91175 66.26548 44.44507 24.89736 62.30036 44.44507 25.47136 63.12067 44.44507 25.47855 62.30036 44.44507 29.26636 64.35405 44.44507 25.47855 63.12067 44.44507 29.27355 61.06698 44.44507 29.26636 64.98952 44.44507 25.48509 64.35405 44.44507 29.27355 67.22656 44.44507 25.4835 68.36506 44.44507 25.4835 66.22289 44.44507 25.48509 64.98952 44.44507 29.28009 68.95273 44.44507 25.48449 68.36506 44.44507 29.2785 70.18611 44.44507 25.48449 68.95273 44.44507 29.27949 67.22656 44.44507 29.2785 55.45932 44.44507 25.50002 56.58066 44.44507 25.56405 55.45932 44.44507 29.29502 57.81404 44.44507 25.56405 56.58066 44.44507 29.35905 54.22594 44.44507 29.29502 53.16491 44.44507 29.31393 51.93154 44.44507 29.31393 71.18867 44.44507 16.32867 50.88542 44.44507 16.32867 71.18867 44.44507 30.46505 70.32528 44.44507 20.62064 70.22869 44.44507 24.89677 70.18611 44.44507 29.27949 66.22289 44.44507 29.28009 60.02427 44.44507 29.29447 58.7909 44.44507 29.29447 57.81404 44.44507 29.35905 52.07072 44.44507 16.86008 50.88542 44.44507 30.46505 51.97412 44.44507 21.1362 51.93154 44.44507 25.51893 54.22594 44.44507 25.50002 61.06698 44.44507 25.47136 58.7909 44.44507 25.49947 60.02427 44.44507 25.49947 53.16491 44.44507 25.51893 68.95273 44.44507 29.27949 67.22656 44.44507 29.2785 66.22289 44.44507 29.28009 66.22289 44.44507 25.48509 67.22656 44.44507 25.4835 64.98952 44.44507 29.28009 63.12067 44.44507 29.27355 60.02427 44.44507 29.29447 61.06698 44.44507 29.26636 60.02427 44.44507 25.49947 61.06698 44.44507 25.47136 57.81404 44.44507 29.35905 58.7909 44.44507 29.29447 57.81404 44.44507 25.56405 58.7909 44.44507 25.49947 55.45932 44.44507 25.50002 53.16491 44.44507 29.31393 54.22594 44.44507 29.29502 53.16491 44.44507 25.51893 54.22594 44.44507 25.50002 71.18867 44.44507 30.46505 56.58066 44.44507 29.35905 50.88542 44.44507 30.46505 51.93154 44.44507 29.31393 51.93154 44.44507 25.51893 62.30036 44.44507 25.47136 56.62325 44.44507 24.97632 51.97412 44.44507 24.9312 51.97412 44.44507 21.1362 53.2075 44.44507 21.1362 54.26853 44.44507 21.11729 55.50191 44.44507 21.11729 58.83349 44.44507 21.11675 60.06686 44.44507 21.11675 61.10957 44.44507 21.08863 62.34295 44.44507 21.08863 56.71984 44.44507 20.7002 52.07072 44.44507 20.65508 52.07072 44.44507 16.86008 53.30409 44.44507 16.86008 54.36512 44.44507 16.84117 55.5985 44.44507 16.84117 58.93008 44.44507 16.84062 60.16345 44.44507 16.84062 61.20616 44.44507 16.81251 62.43954 44.44507 16.81251 50.88542 44.44507 16.32867 70.18611 44.44507 29.27949 70.18611 44.44507 25.48449 68.36506 44.44507 25.4835 64.35405 44.44507 25.47855 57.85663 44.44507 24.97632 58.83349 44.44507 24.91175 60.06686 44.44507 24.91175 65.0321 44.44507 24.89736 66.26548 44.44507 24.89736 68.99532 44.44507 24.89677 70.22869 44.44507 24.89677 70.22869 44.44507 21.10177 68.40765 44.44507 21.10077 64.39663 44.44507 21.09582 57.95322 44.44507 20.7002 58.93008 44.44507 20.63562 60.16345 44.44507 20.63562 65.1287 44.44507 20.62124 66.36207 44.44507 20.62124 69.09191 44.44507 20.62064 70.32528 44.44507 20.62064 70.32528 44.44507 16.82564 68.50424 44.44507 16.82465 64.49323 44.44507 16.8197 71.18867 44.44507 16.32867 55.45932 44.44507 29.29502 56.58066 44.44507 25.56405 68.36506 44.44507 29.2785 68.95273 44.44507 25.48449 64.35405 44.44507 29.27355 64.98952 44.44507 25.48509 62.30036 44.44507 29.26636 63.12067 44.44507 25.47855 67.26915 44.44507 24.89577 66.26548 44.44507 21.10236 67.26915 44.44507 21.10077 63.16326 44.44507 24.89082 61.10957 44.44507 24.88363 57.85663 44.44507 21.18132 53.2075 44.44507 24.9312 54.26853 44.44507 24.91229 55.50191 44.44507 24.91229 56.62325 44.44507 21.18132 68.40765 44.44507 24.89577 68.99532 44.44507 21.10177 64.39663 44.44507 24.89082 65.0321 44.44507 21.10236 62.34295 44.44507 24.88363 63.16326 44.44507 21.09582 67.36574 44.44507 20.61965 66.36207 44.44507 16.82624 67.36574 44.44507 16.82465 63.25985 44.44507 20.6147 61.20616 44.44507 20.60751 57.95322 44.44507 16.9052 53.30409 44.44507 20.65508 54.36512 44.44507 20.63617 55.5985 44.44507 20.63617 56.71984 44.44507 16.9052 68.50424 44.44507 20.61965 69.09191 44.44507 16.82564 64.49323 44.44507 20.6147 65.1287 44.44507 16.82624 62.43954 44.44507 20.60751 63.25985 44.44507 16.8197 71.18867 60.03814 25.60448 71.18867 60.08073 25.01675 71.18867 61.17664 25.60448 71.18867 60.08073 21.22175 71.18867 61.21923 25.01675 71.18867 61.17664 29.39948 71.18867 60.17732 20.74063 71.18867 61.21923 21.22175 71.18867 60.17732 16.94563 71.18867 61.31582 20.74063 71.18867 61.76431 25.60548 71.18867 61.8069 25.01775 71.18867 62.99769 25.60548 71.18867 61.8069 21.22275 71.18867 63.04027 25.01775 71.18867 62.99769 29.40048 71.18867 61.90349 20.74163 71.18867 63.04027 21.22275 71.18867 61.90349 16.94663 71.18867 63.13687 20.74163 71.18867 44.44507 16.32867 71.18867 44.8823 16.98106 71.18867 44.44507 30.46505 71.18867 63.3252 16.32867 71.18867 44.78571 21.25719 71.18867 44.74312 25.63991 71.18867 46.11567 16.98106 71.18867 47.1767 16.96215 71.18867 46.11567 20.77606 71.18867 47.08011 21.23827 71.18867 47.03753 25.621 71.18867 48.41008 16.96215 71.18867 49.53142 17.02618 71.18867 48.41008 20.75715 71.18867 49.43483 21.30231 71.18867 49.39224 25.68503 71.18867 51.74166 16.96161 71.18867 50.7648 17.02618 71.18867 50.7648 20.82118 71.18867 51.64507 21.23773 71.18867 51.60248 25.62046 71.18867 52.97503 16.96161 71.18867 54.01774 16.93349 71.18867 52.97503 20.75661 71.18867 53.92115 21.20962 71.18867 53.87857 25.59234 71.18867 55.25112 16.93349 71.18867 56.07143 16.94068 71.18867 55.25112 20.72849 71.18867 55.97484 21.2168 71.18867 55.93225 25.59953 71.18867 57.30481 16.94068 71.18867 57.94028 16.94722 71.18867 57.30481 20.73568 71.18867 57.84368 21.22334 71.18867 57.8011 25.60607 71.18867 59.17365 16.94722 71.18867 59.17365 20.74222 71.18867 61.31582 16.94563 71.18867 63.13687 16.94663 71.18867 44.74312 29.43491 71.18867 63.3252 30.46505 71.18867 45.97649 29.43491 71.18867 47.03753 29.416 71.18867 46.01908 25.05219 71.18867 48.2709 29.416 71.18867 49.39224 29.48003 71.18867 48.31349 25.03327 71.18867 50.62562 29.48003 71.18867 51.60248 29.41546 71.18867 50.66821 25.09731 71.18867 52.83586 29.41546 71.18867 53.87857 29.38734 71.18867 52.87844 25.03273 71.18867 55.11194 29.38734 71.18867 55.93225 29.39453 71.18867 55.15453 25.00462 71.18867 57.16563 29.39453 71.18867 57.8011 29.40107 71.18867 57.20821 25.0118 71.18867 59.03447 29.40107 71.18867 60.03814 29.39948 71.18867 59.07706 25.01834 71.18867 61.76431 29.40048 71.18867 44.78571 25.05219 71.18867 45.97649 25.63991 71.18867 44.8823 20.77606 71.18867 46.01908 21.25719 71.18867 47.08011 25.03327 71.18867 48.2709 25.621 71.18867 47.1767 20.75715 71.18867 48.31349 21.23827 71.18867 49.43483 25.09731 71.18867 50.62562 25.68503 71.18867 49.53142 20.82118 71.18867 50.66821 21.30231 71.18867 51.64507 25.03273 71.18867 52.83586 25.62046 71.18867 51.74166 20.75661 71.18867 52.87844 21.23773 71.18867 53.92115 25.00462 71.18867 55.11194 25.59234 71.18867 54.01774 20.72849 71.18867 55.15453 21.20962 71.18867 55.97484 25.0118 71.18867 57.16563 25.59953 71.18867 56.07143 20.73568 71.18867 57.20821 21.2168 71.18867 57.84368 25.01834 71.18867 59.03447 25.60607 71.18867 57.94028 20.74222 71.18867 59.07706 21.22334 71.18867 59.07706 25.01834 71.18867 59.17365 20.74222 71.18867 59.07706 21.22334 71.18867 57.94028 20.74222 71.18867 57.94028 16.94722 71.18867 57.84368 21.22334 71.18867 59.03447 29.40107 71.18867 59.03447 25.60607 71.18867 57.84368 25.01834 71.18867 57.8011 25.60607 71.18867 57.20821 25.0118 71.18867 57.30481 20.73568 71.18867 57.20821 21.2168 71.18867 56.07143 20.73568 71.18867 56.07143 16.94068 71.18867 55.97484 21.2168 71.18867 57.16563 29.39453 71.18867 57.16563 25.59953 71.18867 55.97484 25.0118 71.18867 55.93225 25.59953 71.18867 55.15453 25.00462 71.18867 55.25112 20.72849 71.18867 55.15453 21.20962 71.18867 54.01774 20.72849 71.18867 54.01774 16.93349 71.18867 53.92115 21.20962 71.18867 55.11194 29.38734 71.18867 55.11194 25.59234 71.18867 53.92115 25.00462 71.18867 53.87857 25.59234 71.18867 52.87844 25.03273 71.18867 52.97503 20.75661 71.18867 52.87844 21.23773 71.18867 51.74166 20.75661 71.18867 51.74166 16.96161 71.18867 51.64507 21.23773 71.18867 52.83586 29.41546 71.18867 52.83586 25.62046 71.18867 51.64507 25.03273 71.18867 51.60248 25.62046 71.18867 50.66821 25.09731 71.18867 50.7648 20.82118 71.18867 50.66821 21.30231 71.18867 49.53142 20.82118 71.18867 49.53142 17.02618 71.18867 49.43483 21.30231 71.18867 50.62562 29.48003 71.18867 50.62562 25.68503 71.18867 49.43483 25.09731 71.18867 49.39224 25.68503 71.18867 48.31349 25.03327 71.18867 48.41008 20.75715 71.18867 48.31349 21.23827 71.18867 47.1767 20.75715 71.18867 47.1767 16.96215 71.18867 47.08011 21.23827 71.18867 48.2709 29.416 71.18867 48.2709 25.621 71.18867 47.08011 25.03327 71.18867 47.03753 25.621 71.18867 46.01908 25.05219 71.18867 46.11567 20.77606 71.18867 46.01908 21.25719 71.18867 44.8823 20.77606 71.18867 44.8823 16.98106 71.18867 44.78571 21.25719 71.18867 45.97649 29.43491 71.18867 45.97649 25.63991 71.18867 44.78571 25.05219 71.18867 44.74312 25.63991 71.18867 63.3252 16.32867 71.18867 63.13687 20.74163 71.18867 63.3252 30.46505 71.18867 63.04027 25.01775 71.18867 62.99769 29.40048 71.18867 61.76431 29.40048 71.18867 61.76431 25.60548 71.18867 61.31582 20.74063 71.18867 61.21923 25.01675 71.18867 61.17664 29.39948 71.18867 60.03814 29.39948 71.18867 60.03814 25.60448 71.18867 57.8011 29.40107 71.18867 55.93225 29.39453 71.18867 53.87857 29.38734 71.18867 51.60248 29.41546 71.18867 49.39224 29.48003 71.18867 47.03753 29.416 71.18867 44.74312 29.43491 71.18867 44.44507 30.46505 71.18867 63.13687 16.94663 71.18867 61.90349 16.94663 71.18867 61.8069 21.22275 71.18867 61.31582 16.94563 71.18867 60.17732 16.94563 71.18867 60.08073 21.22175 71.18867 59.17365 16.94722 71.18867 57.30481 16.94068 71.18867 55.25112 16.93349 71.18867 52.97503 16.96161 71.18867 50.7648 17.02618 71.18867 48.41008 16.96215 71.18867 46.11567 16.98106 71.18867 44.44507 16.32867 71.18867 63.04027 21.22275 71.18867 61.90349 20.74163 71.18867 62.99769 25.60548 71.18867 61.8069 25.01775 71.18867 61.21923 21.22175 71.18867 60.17732 20.74063 71.18867 61.17664 25.60448 71.18867 60.08073 25.01675 50.88542 44.70972 20.96835 50.88542 44.80632 21.44947 50.88542 45.9431 20.96835 50.88542 44.80632 25.24447 50.88542 46.03969 21.44947 50.88542 45.9431 17.17335 50.88542 44.8489 25.8322 50.88542 46.03969 25.24447 50.88542 44.8489 29.6272 50.88542 46.08228 25.8322 50.88542 61.73092 21.00279 50.88542 61.82751 21.48391 50.88542 62.96429 21.00279 50.88542 61.82751 25.27891 50.88542 63.06088 21.48391 50.88542 62.96429 17.20779 50.88542 61.8701 25.86664 50.88542 63.06088 25.27891 50.88542 61.8701 29.66164 50.88542 63.10347 25.86664 50.88542 44.44507 30.46505 50.88542 44.44507 16.32867 50.88542 63.3252 30.46505 50.88542 46.08228 29.6272 50.88542 46.66994 29.6262 50.88542 46.53077 20.96735 50.88542 46.62736 25.24348 50.88542 47.80844 29.6262 50.88542 48.81212 29.62779 50.88542 47.80844 25.8312 50.88542 48.67294 20.96895 50.88542 48.76953 25.24507 50.88542 50.04549 29.62779 50.88542 50.68096 29.62125 50.88542 50.04549 25.83279 50.88542 50.54178 20.9624 50.88542 50.63838 25.23853 50.88542 51.91434 29.62125 50.88542 52.73465 29.61407 50.88542 51.91434 25.82625 50.88542 52.59547 20.95522 50.88542 52.69206 25.23134 50.88542 53.96802 29.61407 50.88542 55.01073 29.64218 50.88542 53.96802 25.81907 50.88542 54.87156 20.98333 50.88542 54.96815 25.25945 50.88542 56.24411 29.64218 50.88542 57.22097 29.70676 50.88542 56.24411 25.84718 50.88542 57.08179 21.04791 50.88542 57.17838 25.32403 50.88542 58.45434 29.70676 50.88542 59.57569 29.64272 50.88542 58.45434 25.91176 50.88542 59.43651 20.98387 50.88542 59.5331 25.26 50.88542 60.80906 29.64272 50.88542 60.80906 25.84772 50.88542 63.10347 29.66164 50.88542 44.70972 17.17335 50.88542 63.3252 16.32867 50.88542 46.53077 17.17235 50.88542 47.66927 17.17235 50.88542 48.67294 17.17395 50.88542 47.76586 21.44848 50.88542 49.90631 17.17395 50.88542 50.54178 17.1674 50.88542 50.0029 21.45007 50.88542 51.77516 17.1674 50.88542 52.59547 17.16022 50.88542 51.87175 21.44353 50.88542 53.82884 17.16022 50.88542 54.87156 17.18833 50.88542 53.92544 21.43634 50.88542 56.10493 17.18833 50.88542 57.08179 17.25291 50.88542 56.20152 21.46445 50.88542 58.31517 17.25291 50.88542 59.43651 17.18887 50.88542 58.41176 21.52903 50.88542 60.66989 17.18887 50.88542 61.73092 17.20779 50.88542 60.76648 21.465 50.88542 59.5331 21.465 50.88542 60.66989 20.98387 50.88542 59.57569 25.84772 50.88542 60.76648 25.26 50.88542 57.17838 21.52903 50.88542 58.31517 21.04791 50.88542 57.22097 25.91176 50.88542 58.41176 25.32403 50.88542 54.96815 21.46445 50.88542 56.10493 20.98333 50.88542 55.01073 25.84718 50.88542 56.20152 25.25945 50.88542 52.69206 21.43634 50.88542 53.82884 20.95522 50.88542 52.73465 25.81907 50.88542 53.92544 25.23134 50.88542 50.63838 21.44353 50.88542 51.77516 20.9624 50.88542 50.68096 25.82625 50.88542 51.87175 25.23853 50.88542 48.76953 21.45007 50.88542 49.90631 20.96895 50.88542 48.81212 25.83279 50.88542 50.0029 25.24507 50.88542 46.62736 21.44848 50.88542 47.66927 20.96735 50.88542 46.66994 25.8312 50.88542 47.76586 25.24348 50.88542 47.76586 21.44848 50.88542 47.80844 25.8312 50.88542 47.76586 25.24348 50.88542 46.66994 25.8312 50.88542 46.66994 29.6262 50.88542 46.62736 25.24348 50.88542 47.66927 17.17235 50.88542 47.66927 20.96735 50.88542 46.62736 21.44848 50.88542 46.53077 20.96735 50.88542 50.0029 21.45007 50.88542 50.04549 25.83279 50.88542 50.0029 25.24507 50.88542 48.81212 25.83279 50.88542 48.81212 29.62779 50.88542 48.76953 25.24507 50.88542 49.90631 17.17395 50.88542 49.90631 20.96895 50.88542 48.76953 21.45007 50.88542 48.67294 20.96895 50.88542 51.87175 21.44353 50.88542 51.91434 25.82625 50.88542 51.87175 25.23853 50.88542 50.68096 25.82625 50.88542 50.68096 29.62125 50.88542 50.63838 25.23853 50.88542 51.77516 17.1674 50.88542 51.77516 20.9624 50.88542 50.63838 21.44353 50.88542 50.54178 20.9624 50.88542 53.92544 21.43634 50.88542 53.96802 25.81907 50.88542 53.92544 25.23134 50.88542 52.73465 25.81907 50.88542 52.73465 29.61407 50.88542 52.69206 25.23134 50.88542 53.82884 17.16022 50.88542 53.82884 20.95522 50.88542 52.69206 21.43634 50.88542 52.59547 20.95522 50.88542 56.20152 21.46445 50.88542 56.24411 25.84718 50.88542 56.20152 25.25945 50.88542 55.01073 25.84718 50.88542 55.01073 29.64218 50.88542 54.96815 25.25945 50.88542 56.10493 17.18833 50.88542 56.10493 20.98333 50.88542 54.96815 21.46445 50.88542 54.87156 20.98333 50.88542 58.41176 21.52903 50.88542 58.45434 25.91176 50.88542 58.41176 25.32403 50.88542 57.22097 25.91176 50.88542 57.22097 29.70676 50.88542 57.17838 25.32403 50.88542 58.31517 17.25291 50.88542 58.31517 21.04791 50.88542 57.17838 21.52903 50.88542 57.08179 21.04791 50.88542 60.76648 21.465 50.88542 60.80906 25.84772 50.88542 60.76648 25.26 50.88542 59.57569 25.84772 50.88542 59.57569 29.64272 50.88542 59.5331 25.26 50.88542 60.66989 17.18887 50.88542 60.66989 20.98387 50.88542 59.5331 21.465 50.88542 59.43651 20.98387 50.88542 63.3252 30.46505 50.88542 63.10347 25.86664 50.88542 63.3252 16.32867 50.88542 63.06088 21.48391 50.88542 62.96429 17.20779 50.88542 61.73092 17.20779 50.88542 61.73092 21.00279 50.88542 59.43651 17.18887 50.88542 57.08179 17.25291 50.88542 54.87156 17.18833 50.88542 52.59547 17.16022 50.88542 50.54178 17.1674 50.88542 48.67294 17.17395 50.88542 46.53077 17.17235 50.88542 46.08228 25.8322 50.88542 46.03969 21.44947 50.88542 45.9431 17.17335 50.88542 44.70972 17.17335 50.88542 44.70972 20.96835 50.88542 44.44507 16.32867 50.88542 63.10347 29.66164 50.88542 61.8701 29.66164 50.88542 61.82751 25.27891 50.88542 60.80906 29.64272 50.88542 58.45434 29.70676 50.88542 56.24411 29.64218 50.88542 53.96802 29.61407 50.88542 51.91434 29.62125 50.88542 50.04549 29.62779 50.88542 47.80844 29.6262 50.88542 46.08228 29.6272 50.88542 44.8489 29.6272 50.88542 44.80632 25.24447 50.88542 44.44507 30.46505 50.88542 63.06088 25.27891 50.88542 61.8701 25.86664 50.88542 62.96429 21.00279 50.88542 61.82751 21.48391 50.88542 46.03969 25.24447 50.88542 44.8489 25.8322 50.88542 45.9431 20.96835 50.88542 44.80632 21.44947 59.86023 63.3252 25.66123 59.03992 63.3252 25.66842 59.86023 63.3252 29.45623 57.80654 63.3252 25.66842 59.03992 63.3252 29.46342 61.0936 63.3252 29.45623 57.17107 63.3252 25.67496 57.80654 63.3252 29.46342 54.93402 63.3252 25.67336 53.79552 63.3252 25.67336 55.9377 63.3252 25.67496 57.17107 63.3252 29.46996 53.20786 63.3252 25.67436 53.79552 63.3252 29.46836 51.97448 63.3252 25.67436 53.20786 63.3252 29.46936 54.93402 63.3252 29.46836 66.70127 63.3252 25.68988 65.57992 63.3252 25.75392 66.70127 63.3252 29.48488 64.34655 63.3252 25.75392 65.57992 63.3252 29.54892 67.93464 63.3252 29.48488 68.99568 63.3252 29.5038 70.22905 63.3252 29.5038 50.88542 63.3252 16.32867 51.8353 63.3252 17.01551 71.18867 63.3252 16.32867 50.88542 63.3252 30.46505 59.72105 63.3252 17.00238 57.66736 63.3252 17.00957 53.65635 63.3252 17.01452 51.8353 63.3252 20.81051 51.9319 63.3252 21.29164 53.06868 63.3252 20.81051 55.79852 63.3252 20.81111 57.03189 63.3252 20.81111 61.99714 63.3252 20.82549 63.23051 63.3252 20.82549 64.20737 63.3252 20.89007 65.44075 63.3252 20.89007 59.81764 63.3252 21.2785 57.76395 63.3252 21.28569 53.75294 63.3252 21.29064 51.9319 63.3252 25.08664 53.16527 63.3252 25.08664 55.89511 63.3252 25.08723 57.12848 63.3252 25.08723 62.09373 63.3252 25.10161 63.3271 63.3252 25.10161 64.30396 63.3252 25.16619 65.53734 63.3252 25.16619 51.97448 63.3252 29.46936 55.9377 63.3252 29.46996 62.13631 63.3252 29.48434 63.36969 63.3252 29.48434 64.34655 63.3252 29.54892 70.08987 63.3252 17.04995 71.18867 63.3252 30.46505 67.79546 63.3252 17.03103 60.95442 63.3252 17.00238 63.23051 63.3252 17.03049 61.99714 63.3252 17.03049 66.56209 63.3252 17.03103 68.8565 63.3252 17.04995 70.18646 63.3252 21.32607 70.08987 63.3252 20.84495 67.89206 63.3252 21.30716 61.05102 63.3252 21.2785 63.3271 63.3252 21.30661 62.09373 63.3252 21.30661 66.65868 63.3252 21.30716 68.95309 63.3252 21.32607 70.18646 63.3252 25.12107 70.22905 63.3252 25.7088 67.93464 63.3252 25.68988 61.0936 63.3252 25.66123 63.36969 63.3252 25.68934 62.13631 63.3252 25.68934 68.99568 63.3252 25.7088 58.99733 63.3252 21.28569 59.81764 63.3252 25.0735 58.99733 63.3252 25.08069 61.05102 63.3252 25.0735 57.12848 63.3252 21.29223 57.76395 63.3252 25.08069 54.89144 63.3252 21.29064 55.89511 63.3252 21.29223 53.16527 63.3252 21.29164 53.75294 63.3252 25.08564 54.89144 63.3252 25.08564 65.53734 63.3252 21.37119 66.65868 63.3252 25.10216 64.30396 63.3252 21.37119 67.89206 63.3252 25.10216 68.95309 63.3252 25.12107 58.90074 63.3252 17.00957 59.72105 63.3252 20.79738 58.90074 63.3252 20.80457 60.95442 63.3252 20.79738 57.03189 63.3252 17.01611 57.66736 63.3252 20.80457 54.79485 63.3252 17.01452 55.79852 63.3252 17.01611 53.06868 63.3252 17.01551 53.65635 63.3252 20.80952 54.79485 63.3252 20.80952 65.44075 63.3252 17.09507 66.56209 63.3252 20.82603 64.20737 63.3252 17.09507 67.79546 63.3252 20.82603 68.8565 63.3252 20.84495 53.06868 63.3252 20.81051 54.79485 63.3252 20.80952 55.79852 63.3252 20.81111 55.79852 63.3252 17.01611 54.79485 63.3252 17.01452 57.03189 63.3252 20.81111 58.90074 63.3252 20.80457 61.99714 63.3252 20.82549 60.95442 63.3252 20.79738 61.99714 63.3252 17.03049 60.95442 63.3252 17.00238 64.20737 63.3252 20.89007 63.23051 63.3252 20.82549 64.20737 63.3252 17.09507 63.23051 63.3252 17.03049 66.56209 63.3252 17.03103 68.8565 63.3252 20.84495 67.79546 63.3252 20.82603 68.8565 63.3252 17.04995 67.79546 63.3252 17.03103 70.08987 63.3252 20.84495 65.44075 63.3252 20.89007 66.56209 63.3252 20.82603 65.44075 63.3252 17.09507 53.65635 63.3252 20.80952 53.06868 63.3252 17.01551 51.8353 63.3252 17.01551 53.65635 63.3252 17.01452 57.66736 63.3252 20.80457 57.03189 63.3252 17.01611 57.66736 63.3252 17.00957 59.72105 63.3252 20.79738 58.90074 63.3252 17.00957 59.72105 63.3252 17.00238 53.16527 63.3252 25.08664 54.89144 63.3252 25.08564 55.89511 63.3252 25.08723 55.89511 63.3252 21.29223 54.89144 63.3252 21.29064 57.12848 63.3252 25.08723 58.99733 63.3252 25.08069 62.09373 63.3252 25.10161 61.05102 63.3252 25.0735 62.09373 63.3252 21.30661 61.05102 63.3252 21.2785 64.30396 63.3252 25.16619 63.3271 63.3252 25.10161 64.30396 63.3252 21.37119 63.3271 63.3252 21.30661 66.65868 63.3252 21.30716 68.95309 63.3252 25.12107 67.89206 63.3252 25.10216 68.95309 63.3252 21.32607 67.89206 63.3252 21.30716 70.18646 63.3252 25.12107 65.53734 63.3252 25.16619 66.65868 63.3252 25.10216 65.53734 63.3252 21.37119 53.75294 63.3252 25.08564 53.16527 63.3252 21.29164 51.9319 63.3252 21.29164 53.75294 63.3252 21.29064 57.76395 63.3252 25.08069 57.12848 63.3252 21.29223 57.76395 63.3252 21.28569 59.81764 63.3252 25.0735 58.99733 63.3252 21.28569 59.81764 63.3252 21.2785 53.20786 63.3252 29.46936 54.93402 63.3252 29.46836 55.9377 63.3252 29.46996 55.9377 63.3252 25.67496 54.93402 63.3252 25.67336 57.17107 63.3252 29.46996 59.03992 63.3252 29.46342 62.13631 63.3252 29.48434 61.0936 63.3252 29.45623 62.13631 63.3252 25.68934 61.0936 63.3252 25.66123 64.34655 63.3252 29.54892 63.36969 63.3252 29.48434 64.34655 63.3252 25.75392 63.36969 63.3252 25.68934 66.70127 63.3252 25.68988 68.99568 63.3252 29.5038 67.93464 63.3252 29.48488 68.99568 63.3252 25.7088 67.93464 63.3252 25.68988 50.88542 63.3252 30.46505 65.57992 63.3252 29.54892 71.18867 63.3252 30.46505 70.22905 63.3252 29.5038 70.22905 63.3252 25.7088 59.86023 63.3252 25.66123 70.18646 63.3252 21.32607 70.08987 63.3252 17.04995 71.18867 63.3252 16.32867 51.97448 63.3252 29.46936 51.97448 63.3252 25.67436 53.79552 63.3252 25.67336 57.80654 63.3252 25.66842 51.9319 63.3252 25.08664 51.8353 63.3252 20.81051 50.88542 63.3252 16.32867 66.70127 63.3252 29.48488 65.57992 63.3252 25.75392 53.79552 63.3252 29.46836 53.20786 63.3252 25.67436 57.80654 63.3252 29.46342 57.17107 63.3252 25.67496 59.86023 63.3252 29.45623 59.03992 63.3252 25.66842 + + + + + + + + + + 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -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 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 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 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 + + + + + + + + + + + + + + +

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

+
+
+
+ + + + 70.62073 44.95786 20.50317 70.62073 44.95786 30.46505 63.64954 48.05032 37.12085 63.64954 60.98956 37.12085 71.18867 63.3252 30.46505 + + + + + + + + + + + + + +

1 0 2 1 4 3

+
+ + +

3 2

+
+
+
+ + + + 50.88542 44.44507 30.46505 51.26623 44.95786 30.46505 51.26623 44.95786 20.50317 58.97882 46.66503 37.22875 58.97882 61.26384 37.22875 58.97882 61.45073 37.28572 50.88542 63.3252 30.46505 + + + + + + + + + + + + + +

1 0 1 2 1 3 5 4 6 5

+
+ + +

3 4

+
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0.7215686 0.5254902 0.04313725 1 + + + + + + + + + + + 0.3764706 0.3764706 0.3764706 1 + + + + + + + + + + + 0.827451 0.7411765 0.5647059 1 + + + + + + + + + + + 0.4666667 0.345098 0.2117647 1 + + + + + + + + + + + 0.1372549 0.1372549 0.1372549 1 + + + + + + + + + + + 0 0 0 1 + + + + + + + + + + + 0.654902 0.3960784 0.3215686 1 + + + + + + + + + + + 0.1411765 0.1843137 0.2588235 1 + + + + + + + + + + + 0 0 0 1 + + + 1 + + + + + + + + + + + 1 0.6 0.6 1 + + + + + + + + + + + 0.8 0.6392157 0.6392157 1 + + + + + + + + + + + 0.8 0 0 1 + + + + + + + + + + + 0.8 0.6 1 1 + + + 1 + + + + + + + + + +
diff --git a/cram_demos/cram_projection_demos/resource/retail/denkmit.stl b/cram_demos/cram_projection_demos/resource/retail/denkmit.stl new file mode 100644 index 0000000000..c2401be23f Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/denkmit.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/denkmit_allzweckreiniger.stl b/cram_demos/cram_projection_demos/resource/retail/denkmit_allzweckreiniger.stl new file mode 100644 index 0000000000..93d5d1d3ab Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/denkmit_allzweckreiniger.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/denkmit_allzweckreiniger_frueling.stl b/cram_demos/cram_projection_demos/resource/retail/denkmit_allzweckreiniger_frueling.stl new file mode 100644 index 0000000000..c76c10052c Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/denkmit_allzweckreiniger_frueling.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/denkmit_allzweckreiniger_limette.stl b/cram_demos/cram_projection_demos/resource/retail/denkmit_allzweckreiniger_limette.stl new file mode 100644 index 0000000000..b8f7f2cf4a Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/denkmit_allzweckreiniger_limette.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/denkmit_edelstahl_reiniger.stl b/cram_demos/cram_projection_demos/resource/retail/denkmit_edelstahl_reiniger.stl new file mode 100644 index 0000000000..38c271748e Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/denkmit_edelstahl_reiniger.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/denkmit_edelstahl_reiniger_spray.stl b/cram_demos/cram_projection_demos/resource/retail/denkmit_edelstahl_reiniger_spray.stl new file mode 100644 index 0000000000..6914b7a1c4 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/denkmit_edelstahl_reiniger_spray.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/denkmit_entkalker.stl b/cram_demos/cram_projection_demos/resource/retail/denkmit_entkalker.stl new file mode 100644 index 0000000000..09f0937691 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/denkmit_entkalker.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/denkmit_glaskeramik_reiniger.stl b/cram_demos/cram_projection_demos/resource/retail/denkmit_glaskeramik_reiniger.stl new file mode 100644 index 0000000000..165b670991 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/denkmit_glaskeramik_reiniger.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/denkmit_maschienen_entkalker.stl b/cram_demos/cram_projection_demos/resource/retail/denkmit_maschienen_entkalker.stl new file mode 100644 index 0000000000..916f449ea3 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/denkmit_maschienen_entkalker.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/denkmit_maschienenpfleger.stl b/cram_demos/cram_projection_demos/resource/retail/denkmit_maschienenpfleger.stl new file mode 100644 index 0000000000..34d985db24 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/denkmit_maschienenpfleger.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/denkmit_spezialsalz.stl b/cram_demos/cram_projection_demos/resource/retail/denkmit_spezialsalz.stl new file mode 100644 index 0000000000..60133a64fd Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/denkmit_spezialsalz.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/denkmit_spuelmaschienen_tabs_allinone.stl b/cram_demos/cram_projection_demos/resource/retail/denkmit_spuelmaschienen_tabs_allinone.stl new file mode 100644 index 0000000000..677974168c Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/denkmit_spuelmaschienen_tabs_allinone.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/denkmit_spuelmaschienen_tabs_classic.stl b/cram_demos/cram_projection_demos/resource/retail/denkmit_spuelmaschienen_tabs_classic.stl new file mode 100644 index 0000000000..e9119ddb85 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/denkmit_spuelmaschienen_tabs_classic.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/denkmit_spuelmaschienen_tabs_nature.stl b/cram_demos/cram_projection_demos/resource/retail/denkmit_spuelmaschienen_tabs_nature.stl new file mode 100644 index 0000000000..ed70d2aa73 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/denkmit_spuelmaschienen_tabs_nature.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/denkmit_spuelmaschienen_tabs_power.stl b/cram_demos/cram_projection_demos/resource/retail/denkmit_spuelmaschienen_tabs_power.stl new file mode 100644 index 0000000000..d08f49ef6f Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/denkmit_spuelmaschienen_tabs_power.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/denkmit_spuelmaschienen_tabs_revolution.stl b/cram_demos/cram_projection_demos/resource/retail/denkmit_spuelmaschienen_tabs_revolution.stl new file mode 100644 index 0000000000..25ffa2a0b4 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/denkmit_spuelmaschienen_tabs_revolution.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/der_general_allzweckreiniger.stl b/cram_demos/cram_projection_demos/resource/retail/der_general_allzweckreiniger.stl new file mode 100644 index 0000000000..cc56cac23b Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/der_general_allzweckreiniger.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/dish-washer-tabs.stl b/cram_demos/cram_projection_demos/resource/retail/dish-washer-tabs.stl new file mode 100644 index 0000000000..615ec62e5c Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/dish-washer-tabs.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/dm_shelves.urdf b/cram_demos/cram_projection_demos/resource/retail/dm_shelves.urdf new file mode 100644 index 0000000000..6ef791c655 --- /dev/null +++ b/cram_demos/cram_projection_demos/resource/retail/dm_shelves.urdf @@ -0,0 +1,1460 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/cram_demos/cram_projection_demos/resource/retail/domestos_allzweckreiniger.stl b/cram_demos/cram_projection_demos/resource/retail/domestos_allzweckreiniger.stl new file mode 100644 index 0000000000..8467349aba Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/domestos_allzweckreiniger.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/dove.stl b/cram_demos/cram_projection_demos/resource/retail/dove.stl new file mode 100644 index 0000000000..7758ff0153 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/dove.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/finish_deo.stl b/cram_demos/cram_projection_demos/resource/retail/finish_deo.stl new file mode 100644 index 0000000000..981e216138 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/finish_deo.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/finish_klarspueler.stl b/cram_demos/cram_projection_demos/resource/retail/finish_klarspueler.stl new file mode 100644 index 0000000000..1e182a6003 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/finish_klarspueler.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/finish_maschienenpfleger.stl b/cram_demos/cram_projection_demos/resource/retail/finish_maschienenpfleger.stl new file mode 100644 index 0000000000..6a59a0a72b Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/finish_maschienenpfleger.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/finish_spezialsalz.stl b/cram_demos/cram_projection_demos/resource/retail/finish_spezialsalz.stl new file mode 100644 index 0000000000..1fd96351db Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/finish_spezialsalz.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/finish_spuelmaschienen_protector.stl b/cram_demos/cram_projection_demos/resource/retail/finish_spuelmaschienen_protector.stl new file mode 100644 index 0000000000..ed061e2bcd Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/finish_spuelmaschienen_protector.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/finish_spuelmaschienen_pulver.stl b/cram_demos/cram_projection_demos/resource/retail/finish_spuelmaschienen_pulver.stl new file mode 100644 index 0000000000..a508b22870 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/finish_spuelmaschienen_pulver.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/finish_spuelmaschienen_tabs_classic.stl b/cram_demos/cram_projection_demos/resource/retail/finish_spuelmaschienen_tabs_classic.stl new file mode 100644 index 0000000000..145d6e8079 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/finish_spuelmaschienen_tabs_classic.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/finish_spuelmaschienen_tabs_classic_vorratspack.stl b/cram_demos/cram_projection_demos/resource/retail/finish_spuelmaschienen_tabs_classic_vorratspack.stl new file mode 100644 index 0000000000..6783c39ea8 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/finish_spuelmaschienen_tabs_classic_vorratspack.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/finish_spuelmaschienen_tabs_quantum.stl b/cram_demos/cram_projection_demos/resource/retail/finish_spuelmaschienen_tabs_quantum.stl new file mode 100644 index 0000000000..8790f16e41 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/finish_spuelmaschienen_tabs_quantum.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/heitmann.stl b/cram_demos/cram_projection_demos/resource/retail/heitmann.stl new file mode 100644 index 0000000000..784fb2200c Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/heitmann.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/heitmann_citronensaeure.stl b/cram_demos/cram_projection_demos/resource/retail/heitmann_citronensaeure.stl new file mode 100644 index 0000000000..cbd1c58844 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/heitmann_citronensaeure.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/heitmann_citronensaeure_box.stl b/cram_demos/cram_projection_demos/resource/retail/heitmann_citronensaeure_box.stl new file mode 100644 index 0000000000..78416c19b4 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/heitmann_citronensaeure_box.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/kuehne_essig_essenz.stl b/cram_demos/cram_projection_demos/resource/retail/kuehne_essig_essenz.stl new file mode 100644 index 0000000000..ee370823ed Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/kuehne_essig_essenz.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/meister_proper_allzweckreiniger.stl b/cram_demos/cram_projection_demos/resource/retail/meister_proper_allzweckreiniger.stl new file mode 100644 index 0000000000..d01140da42 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/meister_proper_allzweckreiniger.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/sagrotan_allzweckreiniger.stl b/cram_demos/cram_projection_demos/resource/retail/sagrotan_allzweckreiniger.stl new file mode 100644 index 0000000000..f25c73a29b Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/sagrotan_allzweckreiniger.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/shelf.urdf b/cram_demos/cram_projection_demos/resource/retail/shelf.urdf new file mode 100644 index 0000000000..742ea91195 --- /dev/null +++ b/cram_demos/cram_projection_demos/resource/retail/shelf.urdf @@ -0,0 +1,348 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/cram_demos/cram_projection_demos/resource/retail/somat.stl b/cram_demos/cram_projection_demos/resource/retail/somat.stl new file mode 100644 index 0000000000..dcc9c41105 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/somat.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/somat_spuelmaschienen_pulver.stl b/cram_demos/cram_projection_demos/resource/retail/somat_spuelmaschienen_pulver.stl new file mode 100644 index 0000000000..2e8af99be1 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/somat_spuelmaschienen_pulver.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/somat_spuelmaschienen_tabs_classic.stl b/cram_demos/cram_projection_demos/resource/retail/somat_spuelmaschienen_tabs_classic.stl new file mode 100644 index 0000000000..06bfa6a196 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/somat_spuelmaschienen_tabs_classic.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/somat_spuelmaschienen_tabs_extra.stl b/cram_demos/cram_projection_demos/resource/retail/somat_spuelmaschienen_tabs_extra.stl new file mode 100644 index 0000000000..494fa187d4 Binary files /dev/null and b/cram_demos/cram_projection_demos/resource/retail/somat_spuelmaschienen_tabs_extra.stl differ diff --git a/cram_demos/cram_projection_demos/resource/retail/table.urdf b/cram_demos/cram_projection_demos/resource/retail/table.urdf new file mode 100644 index 0000000000..1b0d015596 --- /dev/null +++ b/cram_demos/cram_projection_demos/resource/retail/table.urdf @@ -0,0 +1,118 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/cram_demos/cram_projection_demos/src/assembly-demo.lisp b/cram_demos/cram_projection_demos/src/assembly-demo.lisp new file mode 100644 index 0000000000..c90b1d69a3 --- /dev/null +++ b/cram_demos/cram_projection_demos/src/assembly-demo.lisp @@ -0,0 +1,428 @@ +;;; +;;; Copyright (c) 2018, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :demos) + +(defparameter *plate-x* -1.1115) +(defparameter *plate-y* 1.6) +(defparameter *plate-z* 0.8626) + +(defparameter *plate-rad-x* 0.36) +(defparameter *plate-rad-y* 0.60) +(defparameter *plate-rad-z* 0.008) +(defparameter *holder-bolt-rad-x* 0.05) +(defparameter *holder-bolt-rad-y* 0.025) +(defparameter *holder-bolt-rad-z* 0.0125) +(defparameter *bolt-rad-x* 0.01) +(defparameter *bolt-rad-y* 0.01) +(defparameter *bolt-rad-z* 0.0225) +(defparameter *holder-upperbody-rad-x* 0.085) +(defparameter *holder-upperbody-rad-y* 0.025) +(defparameter *holder-upperbody-rad-z* 0.021) +(defparameter *holder-bottom-wing-rad-x* 0.035) +(defparameter *holder-bottom-wing-rad-y* 0.045) +(defparameter *holder-bottom-wing-rad-z* 0.045) +(defparameter *holder-underbody-rad-x* 0.0925) +(defparameter *holder-underbody-rad-y* 0.025) +(defparameter *holder-underbody-rad-z* 0.024) +(defparameter *holder-plane-horizontal-rad-x* 0.1015) +(defparameter *holder-plane-horizontal-rad-y* 0.05) +(defparameter *holder-plane-horizontal-rad-z* 0.0335) +(defparameter *holder-window-rad-x* 0.026) +(defparameter *holder-window-rad-y* 0.025) +(defparameter *holder-window-rad-z* 0.017) +(defparameter *front-wheel-rad-z* 0.015) +(defparameter *nut-rad-z* 0.0075) +(defparameter *chassis-rad-z* 0.0515) +(defparameter *holder-plane-vertical-rad-x* 0.065) +(defparameter *holder-plane-vertical-rad-y* 0.06) +(defparameter *holder-plane-vertical-rad-z* 0.0175) +(defparameter *holder-top-wing-rad-x* 0.035) +(defparameter *holder-top-wing-rad-y* 0.0415) +(defparameter *holder-top-wing-rad-z* 0.045) + +(defparameter *yellow-plastic* '(0.949 0.807 0.082)) +(defparameter *gray-plastic* '(0.568 0.592 0.584)) +(defparameter *red-plane* '(0.878 0.376 0.243)) +(defparameter *cyan-plane* '(0.078 0.513 0.541)) +(defparameter *yellow-plane* '(0.964 0.847 0.584)) +(defparameter *transparent-plane* '(1 1 1)) +(defparameter *black-plane* '(0.184 0.152 0.121)) +(defparameter *gray-plane* '(0.482 0.537 0.549)) + +(defparameter *object-spawning-data* + `((:big-wooden-plate + :big-wooden-plate + (0.823 0.698 0.513) + ((,*plate-rad-x* ,*plate-rad-y* ,(- *plate-rad-z*)) (0 0 0 1))) + (:holder-bolt + :holder-bolt + ,*yellow-plastic* + ((,*holder-bolt-rad-x* ,*holder-bolt-rad-y* ,*holder-bolt-rad-z*) (0 0 0 1))) + (:holder-upper-body + :holder-upper-body + ,*yellow-plastic* + ((,(+ 0.05 *holder-upperbody-rad-x*) 0.10 ,*holder-upperbody-rad-z*) (0 0 0 1))) + (:holder-bottom-wing + :holder-bottom-wing + ,*gray-plastic* + ((,(+ 0.1 *holder-bottom-wing-rad-x*) + ,(- 0.3 *holder-bottom-wing-rad-y*) + ,*holder-bottom-wing-rad-z*) + ,man-int:*rotation-around-z-90-list*)) + (:holder-underbody + :holder-underbody + ,*yellow-plastic* + ((,(+ 0.05 *holder-underbody-rad-x*) 0.4 ,*holder-underbody-rad-z*) (0 0 0 1))) + (:holder-plane-horizontal + :holder-plane-horizontal + ,*yellow-plastic* + ((,(+ 0.05 *holder-plane-horizontal-rad-x*) 0.6 ,*holder-plane-horizontal-rad-z*) + (0 0 0 1))) + (:holder-window + :holder-window + ,*gray-plastic* + ((,*holder-window-rad-x* ,(+ 0.75 *holder-window-rad-y*) ,*holder-window-rad-z*) + (0 0 0 1))) + (:holder-plane-vertical + :holder-plane-vertical + ,*yellow-plastic* + ((,*holder-plane-vertical-rad-x* + ,(- 1.0 *holder-plane-vertical-rad-y*) + ,*holder-plane-vertical-rad-z*) + (0 0 0 1))) + (:holder-top-wing + :holder-top-wing + ,*yellow-plastic* + ((,(+ 0.15 *holder-top-wing-rad-x*) + ,(- 1.15 *holder-top-wing-rad-y*) + ,*holder-top-wing-rad-z*) + ,man-int:*rotation-around-z-90-list*)) + + ;; rear wing is already well positioned + (:rear-wing + :rear-wing + ,*yellow-plane* + ((0.079 0.599 0.056) + ,man-int:*rotation-around-z+90-list*)) + + ;; bolts are used intermediately + (:bolt-1 + :bolt + ,*gray-plane* + ((0.015 0.0125 ,*bolt-rad-z*) (0 0 0 1))) + (:bolt-2 + :bolt + ,*gray-plane* + ((0.0325 0.0375 ,*bolt-rad-z*) (0 0 0 1))) + (:bolt-3 + :bolt + ,*gray-plane* + ((0.05 0.0125 ,*bolt-rad-z*) (0 0 0 1))) + (:bolt-4 + :bolt + ,*gray-plane* + ((0.0675 0.0375 ,*bolt-rad-z*) (0 0 0 1))) + (:bolt-5 + :bolt + ,*gray-plane* + ((0.085 0.0125 ,*bolt-rad-z*) (0 0 0 1))) + + ;; first part of scenario on horizontal holder + (:chassis + :chassis + ,*yellow-plane* + ((0.2 0.9 ,*chassis-rad-z*) ,man-int:*rotation-around-z-90-list*)) + (:bottom-wing + :bottom-wing + ,*cyan-plane* + ((0.134 0.25 0.093) (0 0 0 1))) + (:underbody + :underbody + ,*red-plane* + ((0.145 0.399 0.024) (0 0 0 1))) + (:motor-grill + :motor-grill + ,*black-plane* + ((0.238 0.399 0.039) ,man-int:*rotation-around-y+90-list*)) + (:upper-body + :upper-body + ,*red-plane* + ((0.119 0.1003 0.0482) (0 0 0 1))) + (:top-wing + :top-wing + ,*cyan-plane* + ((0.18522 1.11423 0.08852) (0 0 0 1))) + (:window + :window + ,*transparent-plane* + ((0.024 0.775 0.01962) (0 0 0 1))) + + ;; second part of scenario on vertical holder + (:propeller + :propeller + ,*yellow-plane* + ((0.075 1.10 0) (0 0 0 1))) + (:front-wheel-1 + :front-wheel + ,*black-plane* + ((0.15 0.775 ,*front-wheel-rad-z*) (0 0 0 1))) + (:front-wheel-2 + :front-wheel + ,*black-plane* + ((0.215 0.775 ,*front-wheel-rad-z*) (0 0 0 1))) + (:nut-1 + :nut + ,*gray-plane* + ((0.15 0.725 ,*nut-rad-z*) (0 0 0 1))) + (:nut-2 + :nut + ,*gray-plane* + ((0.215 0.725 ,*nut-rad-z*) (0 0 0 1))))) + + +(defun spawn-assembly-objects (&optional (spawning-data *object-spawning-data*)) + (btr-utils:kill-all-objects) + (btr:detach-all-objects (btr:get-robot-object)) + (btr:detach-all-objects (btr:get-environment-object)) + ;; detach all items from each other + (mapcar #'btr:detach-all-objects + (remove-if-not (lambda (obj) (typep obj 'btr:item)) + (btr:objects btr:*current-bullet-world*))) + ;; spawn objects at default poses + (let ((objects + (mapcar (lambda (object-name-type-pose-list) + (destructuring-bind (object-name object-type object-color + object-pose-list) + object-name-type-pose-list + (let ((object-relative-pose + (cram-tf:list->pose object-pose-list))) + (unless (btr:object btr:*current-bullet-world* object-name) + (btr:add-object + btr:*current-bullet-world* + :mesh + object-name + (cl-transforms:make-identity-pose) + :mesh object-type + :mass 0.0 + :color object-color)) + (setf (btr:pose + (btr:object btr:*current-bullet-world* + object-name)) + (cl-transforms:make-pose + (cl-transforms:v+ + (cl-transforms:make-3d-vector + (- *plate-x* *plate-rad-x*) + (- *plate-y* *plate-rad-y*) + (+ *plate-z* *plate-rad-z*)) + (cl-transforms:origin + object-relative-pose)) + (cl-transforms:orientation + object-relative-pose)))))) + spawning-data))) + + (btr:attach-object :motor-grill :underbody) + + objects)) + +;;; ASSEMBLY STEPS: +;;; (1) put chassis on holder (bump inwards) +;;; (2) put bottom wing on chassis +;;; * maybe: dont hit the top-wing with the arm +;;; (3) put underbody on bottom wing +;;; (4) put upperbody on underbody +;;; (5) screw rear hole +;;; (6) put top wing on body +;;; (7) screw top wing +;;; (8) put window on body +;;; (9) screw window +;;; (10) put plane on vertical holder +;;; (11) put propeller on grill +;;; (12) screw propeller +;;; * put wheel on +;;; * screw nut onto wheel +;;; * put other wheel on +;;; * screw nut onto wheel +;;; * screw bottom body +(defun assembly-demo () + (urdf-proj:with-projected-robot + ;;(setf cram-robosherlock::*no-robosherlock-mode* t) + (spawn-assembly-objects) + (let ((old-visibility btr:*visibility-threshold*)) + (setf btr:*visibility-threshold* 0.4) + (unwind-protect + (let* ((?env-name + (rob-int:get-environment-name)) + (wooden-plate + (desig:an object + (type big-wooden-plate) + (location (desig:a location + (on (desig:an object + (type counter-top) + (urdf-name + kitchen-island-surface) + (part-of ?env-name))) + ;; (side back) + (side front) + (range 0.3)))))) + ;; 1 + (go-transport :chassis '(:side :left) :holder-plane-horizontal '(:range 0.3) + :horizontal-attachment + wooden-plate) + ;; 2 + (go-transport :bottom-wing '(:side :right) :chassis '(:range 0.3) + :wing-attachment + wooden-plate) + ;; 3 + (go-transport :underbody '(:side :right) :bottom-wing '(:range 0.3) + :body-attachment + wooden-plate) + + ;; we put the underbody on the bottom-wing but by doing that + ;; we also put it on the rear-wing. + ;; as there is no explicit placing action, the two will not be + ;; attached automatically. + ;; so we have to attach them manually unfortunately. + ;; this is required for later moving the whole plane onto another holder + (btr:attach-object 'underbody 'rear-wing) + + ;; 4 + (go-transport :upper-body '(:side :right) :underbody '(:range 0.3) + :body-on-body + wooden-plate) + ;; 5 + (go-transport :bolt '(:side :right) :upper-body '(:range 0.3) + :rear-thread + wooden-plate) + ;; 6 + (go-transport :top-wing '(:side :left) :upper-body '(:range 0.3) + :wing-attachment + wooden-plate) + ;; 7 + (go-transport :bolt :bolt :top-wing '(:range 0.3) + :middle-thread + wooden-plate) + ;; 8 + (go-transport :window '(:side :left) :top-wing '(:range 0.3) + :window-attachment + wooden-plate) + ;; 9 + (go-transport :bolt :bolt :window '(:range 0.3) + :window-thread + wooden-plate) + + ;; 10 + (go-transport :top-wing '(:range 0.3) :holder-plane-vertical '(:side :left) + ;; or `((,(- *base-x* 0.00) 1.45 0) (0 0 0 1)) + :vertical-attachment + wooden-plate) + + ;; 11 + (go-transport :propeller '(:side :left) :motor-grill '(:side :left) + ;; or `((,(- *base-x* 0.15) 1.8 0) (0 0 0 1)) + :propeller-attachment + wooden-plate) + + ;; 12 + (go-transport :bolt :bolt :propeller '(:side :left) + ;; or `((,*base-x* 1.85 0) (0 0 0 1)) + :propeller-thread + wooden-plate)) + (setf btr:*visibility-threshold* old-visibility))))) + + +(defun go-transport (?object-type ?object-location-property + ?other-object-type ?other-object-location-property + ?attachment-type + ?wooden-plate) + (let* ((?env-name + (rob-int:get-environment-name)) + (?object-location + (if (eq ?object-location-property :bolt) + (desig:a location + (on (desig:an object + (type counter-top) + (urdf-name kitchen-island-surface) + (part-of ?env-name))) + (range-invert 0.9) + (side right) + (side front)) + (desig:a location + (on ?wooden-plate) + ?object-location-property + (side front)))) + (?other-object-location + (desig:a location + (on ?wooden-plate) + ?other-object-location-property + (side front))) + (?object + (desig:an object + (type ?object-type) + (location ?object-location))) + (?other-object + (desig:an object + (type ?other-object-type) + (location ?other-object-location)))) + (exe:perform + (desig:an action + (type transporting) + (object ?object) + (target (desig:a location + (on ?other-object) + (for ?object) + (attachments (?attachment-type)))))))) + + +#+boxy-action-examples +( + (urdf-proj:with-projected-robot + (cram-executive:perform + (desig:an action + (type looking) + (direction down)))) + + (urdf-proj:with-projected-robot + (cram-executive:perform + (desig:an action + (type detecting) + (object (desig:an object (type chassis)))))) + + (urdf-proj:with-simulated-robot + (exe:perform + (desig:an action + (type opening-gripper) + (gripper left)))) + + (urdf-proj:with-projected-robot + (cram-executive:perform + (desig:an action + (type placing) + (arm left)))) + ) diff --git a/cram_demos/cram_projection_demos/src/costmaps.lisp b/cram_demos/cram_projection_demos/src/costmaps.lisp new file mode 100644 index 0000000000..886cfd406e --- /dev/null +++ b/cram_demos/cram_projection_demos/src/costmaps.lisp @@ -0,0 +1,113 @@ +;;; +;;; Copyright (c) 2017, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :demos) + +(defun make-dm-room-restricted-area-cost-function () + (lambda (x y) + (if (> x 4.0) + 0.0 + (if (< x 0.0) + 0.0 + (if (> y 1.0) + 0.0 + (if (< y -1.0) + 0.0 + 1.0)))))) + +(defun make-small-retail-restricted-area-cost-function () + (lambda (x y) + (if (> x 2.0) + 0.0 + (if (< x -5.0) + 0.0 + (if (> y 1.0) + 0.0 + (if (< y -1.0) + 0.0 + 1.0)))))) + +(defun make-iai-kitchen-assembly-restricted-area-cost-function () + (lambda (x y) + (declare (ignore y)) + (if (> x -1.2) + 0.0 + 1.0))) + +(defun make-iai-kitchen-household-restricted-area-cost-function () + (lambda (x y) + (if (> x 1.2) + 0.0 + (if (and (> x 0.5) (> y -1.5) (< y 2.0)) + 1.0 + (if (and (> x 0.0) (> y -1.5) (< y 1.0)) + 1.0 + (if (and (> x -1.5) (> y -1.5) (< y 2.5)) + 1.0 + (if (and (> x -4.0) (> y -1.0) (< y 1.0)) + 1.0 + 0.0))))))) + +(defun make-restricted-area-cost-function () + (ecase (rob-int:get-environment-name) + (:iai-kitchen + (if (btr:object btr:*current-bullet-world* :big-wooden-plate) + (make-iai-kitchen-assembly-restricted-area-cost-function) + (make-iai-kitchen-household-restricted-area-cost-function))) + (:dm-room + (make-dm-room-restricted-area-cost-function)) + (:dm-shelves + (make-small-retail-restricted-area-cost-function)))) + +(defmethod costmap:costmap-generator-name->score ((name (eql 'restricted-area))) + 5) + +(def-fact-group demo-restricted-ground-costmap (costmap:desig-costmap) + (<- (costmap:desig-costmap ?designator ?costmap) + (or (rob-int:visibility-designator ?designator) + (rob-int:reachability-designator ?designator)) + ;; make sure that the location is not on the robot itself + ;; if it is, don't generate a costmap + (once (or (and (desig:desig-prop ?designator (:object ?some-object)) + (desig:current-designator ?some-object ?object) + (lisp-fun man-int:get-object-pose-in-map ?object ?to-reach-pose) + (lisp-pred identity ?to-reach-pose) + (-> (desig:desig-prop ?object (:location ?loc)) + (not (man-int:location-always-reachable ?loc)) + (true))) + (and (desig:desig-prop ?designator (:location ?some-location)) + (desig:current-designator ?some-location ?location) + ;; if the location is on the robot itself, + ;; don't use the costmap + (not (man-int:location-always-reachable ?location))))) + (costmap:costmap ?costmap) + (costmap:costmap-add-function + restricted-area + (make-restricted-area-cost-function) + ?costmap))) diff --git a/cram_demos/cram_projection_demos/src/household-demo.lisp b/cram_demos/cram_projection_demos/src/household-demo.lisp new file mode 100644 index 0000000000..8b2b6c6129 --- /dev/null +++ b/cram_demos/cram_projection_demos/src/household-demo.lisp @@ -0,0 +1,687 @@ +;;; +;;; Copyright (c) 2017, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Intelligent Autonomous Systems Group/ +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software +;;; without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :demos) + +(defparameter *object-spawning-poses* + '("sink_area_surface" + (:breakfast-cereal . ((0.2 -0.15 0.1) (0 0 0 1))) + (:cup . ((0.2 -0.35 0.1) (0 0 0 1))) + (:bowl . ((0.18 -0.55 0.1) (0 0 0 1))) + (:spoon . ((0.15 -0.4 -0.05) (0 0 0 1))) + (:milk . ((0.07 -0.35 0.1) (0 0 0 1)))) + "Relative poses on sink area") + +(defparameter *object-placing-poses* + '((:breakfast-cereal . ((-0.78 0.9 0.95) (0 0 1 0))) + (:cup . ((-0.79 1.35 0.9) (0 0 0.7071 0.7071))) + (:bowl . ((-0.76 1.19 0.88) (0 0 0.7071 0.7071))) + (:spoon . ((-0.78 1.5 0.86) (0 0 0 1))) + (:milk . ((-0.75 1.7 0.95) (0 0 0.7071 0.7071)))) + "Absolute poses on kitchen_island.") + +(defparameter *demo-object-spawning-poses* + '((:bowl + "sink_area_left_middle_drawer_main" + ((0.10 -0.1505 -0.062256) (0 0 -1 0))) + (:cup + "sink_area_left_bottom_drawer_main" + ((0.11 0.12 -0.0547167) (0 0 -1 0))) + (:spoon + ;; "oven_area_area_middle_upper_drawer_main" + "sink_area_left_upper_drawer_main" + ((0.125 0 -0.0136) (0 -0.053938 -0.998538 -0.003418))) + ;; So far only this orientation works + (:breakfast-cereal + "oven_area_area_right_drawer_board_3_link" + ((0.123 -0.03 0.11) (0.0087786 0.005395 -0.838767 -0.544393))) + ;; ((:breakfast-cereal . ((1.398 1.490 1.2558) (0 0 0.7071 0.7071))) + ;; (:breakfast-cereal . ((1.1 1.49 1.25) (0 0 0.7071 0.7071))) + (:milk + ;; "iai_fridge_main_middle_level" + ;; ((0.10355 0.022 0.094) (0.00939 -0.00636 -0.96978 -0.2437)) + "iai_fridge_door_shelf1_bottom" + ((-0.01 -0.05 0.094) (0 0 0 1))))) + +(defparameter *delivery-poses-relative* + `((:bowl + "kitchen_island_surface" + ((0.24 -0.5 0.0432199478149414d0) + (0.0 0.0 0.33465 0.94234))) + (:cup + "kitchen_island_surface" + ((0.21 -0.20 0.06) + (0.0 0.0 0.33465 0.94234))) + (:spoon + "kitchen_island_surface" + ((0.26 -0.32 0.025) + (0.0 0.0 1 0))) + (:milk + "kitchen_island_surface" + ((0.25 0 0.0983174006144206d0) + (0.0 0.0 -0.9 0.7))) + (:breakfast-cereal + "kitchen_island_surface" + ((0.32 -0.9 0.1) (0 0 0.6 0.4))))) + +(defparameter *delivery-poses* + `((:bowl . ((-0.8399440765380859d0 1.2002920786539713d0 0.8932199478149414d0) + (0.0 0.0 0.33465 0.94234))) + (:cup . ((-0.8908212025960287d0 1.4991984049479166d0 0.9027448018391927d0) + (0.0 0.0 0.33465 0.94234))) + (:spoon . ((-0.8409400304158529d0 1.38009208679199219d0 0.8673268000284831d0) + (0.0 0.0 1 0))) + (:milk . ((-0.8495257695515951d0 1.6991498311360678d0 0.9483174006144206d0) + (0.0 0.0 -0.9 0.7))) + (:breakfast-cereal . ((-0.78 0.8 0.95) (0 0 0.6 0.4))))) + +(defparameter *cleaning-deliver-poses* + `((:bowl . ((1.45 -0.4 1.0) (0 0 0 1))) + (:cup . ((1.45 -0.4 1.0) (0 0 0 1))) + (:spoon . ((1.45 -0.4 1.0) (0 0 0 1))) + (:milk . ((1.2 -0.5 0.8) (0 0 1 0))) + (:breakfast-cereal . ((1.15 -0.5 0.8) (0 0 1 0))))) + +(defparameter *object-grasping-arms* + '(;; (:breakfast-cereal . :right) + ;; (:cup . :left) + ;; (:bowl . :right) + ;; (:spoon . :right) + ;; (:milk . :right) + )) + +(defparameter *object-cad-models* + '(;; (:cup . "cup_eco_orange") + ;; (:bowl . "edeka_red_bowl") + )) + +(defparameter *object-colors* + '((:spoon . "black") + (:breakfast-cereal . "yellow") + (:milk . "blue") + (:bowl . "red") + (:cup . "red"))) + +(defparameter *object-grasps* + '((:spoon . :top) + (:breakfast-cereal . :front) + (:milk . :front) + (:cup . :top) + (:bowl . :top))) + + + + +(defun spawn-objects-on-sink-counter (&key + (object-types + '(:breakfast-cereal + :cup + :bowl + :spoon + :milk)) + (spawning-poses-relative + *object-spawning-poses*) + (random + NIL)) + ;; make sure mesh paths are known, kill old objects and destroy all attachments + (btr:add-objects-to-mesh-list "cram_pr2_pick_place_demo") + (btr-utils:kill-all-objects) + (btr:detach-all-objects (btr:get-robot-object)) + (btr:detach-all-objects (btr:get-environment-object)) + + ;; spawn objects + (let* ((spawning-poses-absolute + (make-poses-relative spawning-poses-relative)) + (objects + (mapcar + (lambda (object-type) + (let* (;; generate object name of form :TYPE-1 + (object-name + (intern (format nil "~a-1" object-type) :keyword)) + ;; spawn object in Bullet World at default pose + (object + (btr-utils:spawn-object object-name object-type)) + ;; calculate new pose: either random or from input list + (object-pose + (if random + ;; generate a pose on a surface + (let* ((aabb-z + (cl-transforms:z + (cl-bullet:bounding-box-dimensions + (btr:aabb object))))) + (cram-tf:translate-pose + (desig:reference + (if (eq object-type :spoon) + (desig:a location + (in (desig:an object + (type drawer) + (urdf-name + sink-area-left-upper-drawer-main) + (part-of iai-kitchen))) + (side front) + (range 0.2) + (range-invert 0.12)) + (desig:a location + (on (desig:an object + (type counter-top) + (urdf-name sink-area-surface) + (part-of iai-kitchen))) + ;; below only works for knowrob sem-map + ;; (centered-with-padding 0.1) + (side left) + (side front)))) + :z (/ aabb-z 2.0))) + ;; take the pose from the function input list + (cdr (assoc object-type spawning-poses-absolute)))) + ;; rotate new pose randomly around Z + (rotated-object-pose + (cram-tf:rotate-pose object-pose + :z (/ (* 2 pi) (random 10.0))))) + ;; move object to calculated pose on surface + (btr-utils:move-object object-name rotated-object-pose) + ;; return object + object)) + object-types))) + + ;; make sure generated poses are stable, especially important for random ones + ;; TDOO: if unstable, call itself + + ;; attach spoon to the drawer + (when (btr:object btr:*current-bullet-world* :spoon-1) + (btr:attach-object (btr:get-environment-object) + (btr:object btr:*current-bullet-world* :spoon-1) + :link "sink_area_left_upper_drawer_main")) + + ;; stabilize world + (btr:simulate btr:*current-bullet-world* 100) + + ;; return list of BTR objects + objects)) + +(defun attach-object-to-the-world (object-type) + (when *demo-object-spawning-poses* + (btr:attach-object (btr:get-environment-object) + (btr:object btr:*current-bullet-world* + (intern (format nil "~a-1" object-type) :keyword)) + :link (second (find object-type + *demo-object-spawning-poses* + :key #'car))))) + + + +(defun spawn-objects-on-fixed-spots (&key + (spawning-poses-relative + *demo-object-spawning-poses*) + (object-types + '(:breakfast-cereal :cup :bowl :spoon :milk))) + (btr-utils:kill-all-objects) + (btr:add-objects-to-mesh-list "cram_pr2_pick_place_demo") + (btr:detach-all-objects (btr:get-robot-object)) + ;; spawn objects at default poses + (let* ((spawning-poses-absolute + (make-poses-list-relative spawning-poses-relative)) + (objects (mapcar (lambda (object-type) + (btr-utils:spawn-object + (intern (format nil "~a-1" object-type) :keyword) + object-type + :pose (cdr (assoc object-type + ;; *demo-object-spawning-poses* + spawning-poses-absolute + )))) + object-types))) + ;; stabilize world + ;; (btr:simulate btr:*current-bullet-world* 100) + objects) + + (mapcar #'attach-object-to-the-world object-types)) + + + +(defun park-robot () + (cpl:with-failure-handling + ((cpl:plan-failure (e) + (declare (ignore e)) + (return))) + (cpl:par + (exe:perform + (desig:an action + (type positioning-arm) + (left-configuration park) + (right-configuration park))) + (exe:perform + (desig:an action + (type moving-torso) + (joint-angle upper-limit))) + (let ((?pose (cl-transforms-stamped:make-pose-stamped + cram-tf:*fixed-frame* + 0.0 + (cl-transforms:make-identity-vector) + (cl-transforms:make-identity-rotation)))) + (exe:perform + (desig:an action + (type going) + (target (desig:a location + (pose ?pose)))))) + (exe:perform (desig:an action (type opening-gripper) (gripper (left right)))) + (exe:perform (desig:an action (type looking) (direction forward)))))) + +(defun initialize () + (sb-ext:gc :full t) + + ;;(when ccl::*is-logging-enabled* + ;; (setf ccl::*is-client-connected* nil) + ;; (ccl::connect-to-cloud-logger) + ;; (ccl::reset-logged-owl)) + + ;; (setf proj-reasoning::*projection-checks-enabled* t) + + (btr:detach-all-objects (btr:get-robot-object)) + (btr:detach-all-objects (btr:get-environment-object)) + (btr-utils:kill-all-objects) + (setf (btr:joint-state (btr:get-environment-object) + "sink_area_left_upper_drawer_main_joint") + 0.0 + (btr:joint-state (btr:get-environment-object) + "sink_area_left_middle_drawer_main_joint") + 0.0 + (btr:joint-state (btr:get-environment-object) + "sink_area_left_bottom_drawer_main_joint") + 0.0 + (btr:joint-state (btr:get-environment-object) + "iai_fridge_door_joint") + 0.0 + (btr:joint-state (btr:get-environment-object) + "sink_area_dish_washer_door_joint") + 0.0 + (btr:joint-state (btr:get-environment-object) + "sink_area_dish_washer_tray_main") + 0.0 + (btr:joint-state (btr:get-environment-object) + "oven_area_area_right_drawer_main_joint") + 0.0 + (btr:joint-state (btr:get-environment-object) + "sink_area_trash_drawer_main_joint") + 0) + (btr-belief::publish-environment-joint-state + (btr:joint-states (btr:get-environment-object))) + + (setf desig::*designators* (tg:make-weak-hash-table :weakness :key)) + + ;; (coe:clear-belief) + + (btr:clear-costmap-vis-object)) + +(defun finalize () + ;; (setf proj-reasoning::*projection-reasoning-enabled* nil) + + ;;(when ccl::*is-logging-enabled* + ;; (ccl::export-log-to-owl "ease_milestone_2018.owl") + ;; (ccl::export-belief-state-to-owl "ease_milestone_2018_belief.owl")) + (sb-ext:gc :full t)) + + +(defun household-demo-random (&optional + (random + nil) + (list-of-objects + '(:bowl :spoon :cup :milk :breakfast-cereal))) + + (urdf-proj:with-simulated-robot + + (initialize) + (when cram-projection:*projection-environment* + (spawn-objects-on-sink-counter :random random)) + + (park-robot) + + ;; (an object + ;; (obj-part "drawer_sinkblock_upper_handle")) + + (dolist (?object-type list-of-objects) + (let* ( ;; (?arm-to-use + ;; (cdr (assoc ?object-type *object-grasping-arms*))) + (?cad-model + (cdr (assoc ?object-type *object-cad-models*))) + (?color + (cdr (assoc ?object-type *object-colors*))) + (?object-to-fetch + (desig:an object + (type ?object-type) + (desig:when ?cad-model + (cad-model ?cad-model)) + (desig:when ?color + (color ?color))))) + + (cpl:with-failure-handling + ((common-fail:high-level-failure (e) + (roslisp:ros-warn (pp-plans demo) "Failure happened: ~a~%Skipping..." e) + (return))) + + (exe:perform + (desig:an action + (type transporting) + (context table-setting-counter) + (object ?object-to-fetch) + ;; (desig:when ?arm-to-use + ;; (arms (?arm-to-use))) + ))) + + ;; (setf proj-reasoning::*projection-reasoning-enabled* nil) + )) + + ;; (setf proj-reasoning::*projection-reasoning-enabled* nil) + + (park-robot) + + (finalize) + + cpl:*current-path*)) + + + + +(defun household-demo (&optional (object-list '(:bowl :spoon :cup + :breakfast-cereal :milk))) + (urdf-proj:with-simulated-robot + + (initialize) + (setf btr:*visibility-threshold* 0.7) + (when cram-projection:*projection-environment* + (spawn-objects-on-fixed-spots + :object-types object-list + :spawning-poses-relative *demo-object-spawning-poses*)) + (park-robot) + + ;; set the table + (dolist (?object-type object-list) + (exe:perform + (desig:an action + (type transporting) + (object (desig:an object (type ?object-type))) + (context table-setting)))) + + ;; clean up + ;; (when cram-projection:*projection-environment* + ;; (spawn-objects-on-fixed-spots + ;; :object-types object-list + ;; :spawning-poses-relative *delivery-poses-relative*)) + + (dolist (?object-type object-list) + (exe:perform + (desig:an action + (type transporting) + (object (desig:an object (type ?object-type))) + (context table-cleaning)))))) + + + + + + + + + + + + + + + +#+stuff-for-testing-different-projection-stuff-in-household-domain-also-old-stuff +( + (defparameter *sink-nav-goal* + (cl-transforms-stamped:make-pose-stamped + "map" + 0.0 + (cl-transforms:make-3d-vector 0.75d0 0.70d0 0.0) + (cl-transforms:make-identity-rotation))) + (defparameter *island-nav-goal* + (cl-transforms-stamped:make-pose-stamped + "map" + 0.0 + (cl-transforms:make-3d-vector -0.2d0 1.5d0 0.0) + (cl-transforms:make-quaternion 0 0 1 0))) + (defparameter *look-goal* + (cl-transforms-stamped:make-pose-stamped + "base_footprint" + 0.0 + (cl-transforms:make-3d-vector 0.5d0 0.0d0 1.0d0) + (cl-transforms:make-identity-rotation))) + + + (defun go-to-sink-or-island (&optional (sink-or-island :sink)) + (let ((?navigation-goal (ecase sink-or-island + (:sink *sink-nav-goal*) + (:island *island-nav-goal*))) + (?ptu-goal *look-goal*)) + (cpl:par + (exe:perform (desig:an action + (type parking-arms))) + (exe:perform (desig:a motion + (type going) + (pose ?navigation-goal)))) + (exe:perform (desig:a motion + (type looking) + (pose ?ptu-goal))))) + + (defun pick-object (&optional (?object-type :breakfast-cereal) (?arm :right)) + (go-to-sink-or-island :sink) + (let* ((?object-desig + (desig:an object (type ?object-type))) + (?perceived-object-desig + (exe:perform (desig:an action + (type detecting) + (object ?object-desig))))) + (cpl:par + (exe:perform (desig:an action + (type looking) + (object ?perceived-object-desig))) + (exe:perform (desig:an action + (type picking-up) + (arm ?arm) + (object ?perceived-object-desig)))))) + + (defun place-object (?target-pose &optional (?arm :right)) + (go-to-sink-or-island :island) + (cpl:par + (exe:perform (desig:a motion + (type looking) + (pose ?target-pose))) + (exe:perform (desig:an action + (type placing) + (arm ?arm) + (target (desig:a location + (pose ?target-pose))))))) + + (defun demo-hard-coded () + (spawn-objects-on-sink-counter) + + (urdf-proj:with-simulated-robot + + (dolist (object-type '(:breakfast-cereal :cup :bowl :spoon :milk)) + + (let ((placing-target + (cl-transforms-stamped:pose->pose-stamped + "map" 0.0 + (cram-bullet-reasoning:ensure-pose + (cdr (assoc object-type *object-placing-poses*))))) + (arm-to-use + (cdr (assoc object-type *object-grasping-arms*)))) + + (pick-object object-type (or arm-to-use :left)) + (place-object placing-target (or arm-to-use :left)))))) + + + + (defun test-projection () + (proj:with-projection-environment urdf-proj:urdf-bullet-projection-environment + (cpl:top-level + (exe:perform + (let ((?pose (cl-transforms-stamped:make-pose-stamped + cram-tf:*robot-base-frame* 0.0 + (cl-transforms:make-3d-vector -0.5 0 0) + (cl-transforms:make-identity-rotation)))) + (desig:a motion (type going) (pose ?pose)))) + (exe:perform + (desig:a motion (type moving-torso) (joint-angle 0.3))) + (exe:perform + (desig:a motion (type opening-gripper) (gripper left))) + (exe:perform + (desig:a motion (type looking) (direction forward))) + (exe:perform + (let ((?pose (cl-transforms-stamped:make-pose-stamped + cram-tf:*robot-base-frame* 0.0 + (cl-transforms:make-3d-vector 0.7 0.3 0.85) + (cl-transforms:make-identity-rotation)))) + (desig:a motion (type moving-tcp) (left-pose ?pose))))))) + + (defun test-desigs () + (let ((?pose + (desig:reference + (desig:a location + (on "CounterTop") + (name "iai_kitchen_meal_table_counter_top"))))) + (desig:reference + (desig:a location + (to see) + (object (desig:an object (at (desig:a location (pose ?pose))))))))) + + (defun spawn-bottle () + (add-objects-to-mesh-list) + (btr-utils:kill-all-objects) + (btr-utils:spawn-object :bottle-1 :bottle :color '(1 0.5 0)) + (btr-utils:move-object :bottle-1 (cl-transforms:make-pose + (cl-transforms:make-3d-vector -2 -1.0 0.861667d0) + (cl-transforms:make-identity-rotation))) + ;; stabilize world + (btr:simulate btr:*current-bullet-world* 100)) + + (defun spawn-objects () + (let ((object-types (add-objects-to-mesh-list))) + ;; spawn at default location + (let ((objects (mapcar (lambda (object-type) + (btr-utils:spawn-object + (intern (format nil "~a-1" object-type) :keyword) + object-type)) + object-types))) + ;; move on top of counter tops + (mapcar (lambda (btr-object) + (let* ((aabb-z + (cl-transforms:z + (cl-bullet:bounding-box-dimensions + (btr:aabb btr-object)))) + (new-pose + (cram-tf:translate-pose + (desig:reference + (desig:a location + (on "CounterTop") + (name "iai_kitchen_meal_table_counter_top"))) + :z (/ aabb-z 2.0)))) + (btr-utils:move-object (btr:name btr-object) new-pose))) + objects) + ;; bottle gets special treatment + (btr-utils:move-object + :bottle-1 + (cl-transforms:make-pose + (cl-transforms:make-3d-vector -2 -1.0 0.861667d0) + (cl-transforms:make-identity-rotation))))) + ;; stabilize world + (btr:simulate btr:*current-bullet-world* 100)) + + + (defparameter *meal-table-left-base-pose* + (cl-transforms-stamped:make-pose-stamped + "map" + 0.0 + (cl-transforms:make-3d-vector -1.12d0 -0.42d0 0.0) + (cl-transforms:axis-angle->quaternion + (cl-transforms:make-3d-vector 0 0 1) (/ pi -2)))) + (defparameter *meal-table-right-base-pose* + (cl-transforms-stamped:make-pose-stamped + "map" + 0.0 + (cl-transforms:make-3d-vector -2.0547d0 -0.481d0 0.0d0) + (cl-transforms:axis-angle->quaternion + (cl-transforms:make-3d-vector 0 0 1) (/ pi -2)))) + (defparameter *meal-table-left-base-look-pose* + (cl-transforms-stamped:make-pose-stamped + "base_footprint" + 0.0 + (cl-transforms:make-3d-vector 0.75d0 -0.12d0 1.11d0) + (cl-transforms:make-identity-rotation))) + (defparameter *meal-table-right-base-look-pose* + (cl-transforms-stamped:make-pose-stamped + "base_footprint" + 0.0 + (cl-transforms:make-3d-vector 0.65335d0 0.076d0 0.758d0) + (cl-transforms:make-identity-rotation))) + (defparameter *meal-table-left-base-look-down-pose* + (cl-transforms-stamped:make-pose-stamped + "base_footprint" + 0.0 + (cl-transforms:make-3d-vector 0.7d0 -0.12d0 0.7578d0) + (cl-transforms:make-identity-rotation))) + + + (defun prepare () + (cpl:with-failure-handling + ((common-fail:low-level-failure (e) + (roslisp:ros-warn (demo step-0) "~a" e) + (return))) + + (let ((?navigation-goal *meal-table-right-base-pose*) + (?ptu-goal *meal-table-right-base-look-pose*)) + (cpl:par + (exe:perform + (desig:an action + (type parking-arms))) + (exe:perform (desig:a motion + (type going) + (pose ?navigation-goal)))) + (exe:perform (desig:a motion + (type looking) + (pose ?ptu-goal)))))) + (defun test-pr2-plans () + (proj:with-projection-environment urdf-proj:urdf-bullet-projection-environment + (cpl:top-level + (prepare)))) + + (defun test-projection-perception () + (spawn-objects) + (test-pr2-plans) + (cpl:sleep 1) + (proj:with-projection-environment urdf-proj:urdf-bullet-projection-environment + (cpl:top-level + (exe:perform + (let ((?object-designator + (desig:an object (type bottle)))) + (desig:a motion + (type detecting) + (object ?object-designator))))))) + ) diff --git a/cram_boxy/cram_boxy_projection/src/package.lisp b/cram_demos/cram_projection_demos/src/package.lisp similarity index 89% rename from cram_boxy/cram_boxy_projection/src/package.lisp rename to cram_demos/cram_projection_demos/src/package.lisp index ee8a1a5783..460beda5a0 100644 --- a/cram_boxy/cram_boxy_projection/src/package.lisp +++ b/cram_demos/cram_projection_demos/src/package.lisp @@ -27,12 +27,15 @@ ;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE ;;; POSSIBILITY OF SUCH DAMAGE. -(defpackage cram-boxy-projection - (:nicknames #:boxy-proj) +(in-package :cl-user) + +(defpackage cram-projection-demos + (:nicknames #:demos) (:use #:common-lisp #:cram-prolog) (:export - ;; ik - ;; #:*torso-step* - ;; projection-environment - #:with-simulated-robot #:with-projected-robot - #:boxy-bullet-projection-environment)) + ;; household-demo + #:household-demo + ;; assembly-demo + #:assembly-demo + ;; retail-demo + #:retail-demo)) diff --git a/cram_demos/cram_projection_demos/src/retail-demo.lisp b/cram_demos/cram_projection_demos/src/retail-demo.lisp new file mode 100644 index 0000000000..33bf005414 --- /dev/null +++ b/cram_demos/cram_projection_demos/src/retail-demo.lisp @@ -0,0 +1,319 @@ +;;; +;;; Copyright (c) 2018, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Intelligent Autonomous Systems Group/ +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software +;;; without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :demos) + +(defparameter *y* -0.38) +(defparameter *off* -0.07) +(defparameter *big-shelf-poses* + `(("level_5_link" + (:denkmit-edelstahl-reiniger-spray . ((-0.36 ,*y* 0.1) (0 0 0 1))) + (:denkmit-edelstahl-reiniger . ((-0.28 ,*y* 0.1) (0 0 0 1))) + (:denkmit-glaskeramik-reiniger . ((-0.19 ,*y* 0.1) (0 0 0 1))) + (:denkmit-maschienen-entkalker . ((-0.03 ,*y* 0.1) (0 0 0 1))) + (:denkmit-entkalker . ((0.14 ,*y* 0.1) (0 0 0 1))) + (:kuehne-essig-essenz . ((0.23 ,*y* 0.1) (0 0 0 1))) + (:heitmann-citronensaeure . ((0.32 ,*y* 0.11) (0 0 0 1)))) + + ("level_4_link" + (:finish-deo . ((-0.43 ,*y* 0.11) (0 0 0 1))) + (:finish-spuelmaschienen-tabs-quantum . ((-0.26 ,*y* 0.11) (0 0 0 1))) + (:finish-spuelmaschienen-tabs-classic . ((0.17 ,*y* 0.13) (0 0 0 1))) + (:finish-spuelmaschienen-tabs-classic-vorratspack . ((0.38 ,*y* 0.16) + (0 0 0 1)))) + + ("level_3_link" + (:finish-spuelmaschienen-pulver . ((-0.4 ,*y* 0.1) (0 0 0 1))) + (:finish-spuelmaschienen-protector . ((-0.26 ,*y* 0.1) (0 0 0 1))) + (:somat-spuelmaschienen-tabs-extra . ((-0.02 ,*y* 0.1) (0 0 0 1))) + (:somat-spuelmaschienen-tabs-classic . ((0.21 ,*y* 0.1) (0 0 0 1))) + (:somat-spuelmaschienen-pulver . ((0.4 ,*y* 0.1) (0 0 0 1)))) + + ("level_2_link" + (:denkmit-spezialsalz . ((-0.4 ,*y* 0.13) (0 0 0 1))) + (:denkmit-spuelmaschienen-tabs-power . ((-0.212 ,*y* 0.1) (0 0 0 1))) + (:denkmit-spuelmaschienen-tabs-revolution . ((-0.039 ,*y* 0.12) (0 0 0 1))) + (:denkmit-spuelmaschienen-tabs-classic . ((0.137 ,*y* 0.1) (0 0 0 1))) + ;; (:denkmit-spuelmaschienen-tabs-nature . ((0.43 ,*y* 0.1) (0 0 0 1))) + ) + + ("level_1_link" + (:denkmit-maschienenpfleger . ((-0.31 ,*y* 0.08) (0 0 0 1))) + (:denkmit-maschienenpfleger . ((-0.25 ,*y* 0.08) (0 0 0 1))) + (:finish-maschienenpfleger . ((-0.175 ,*y* 0.09) (0 0 0 1))) + (:finish-spezialsalz . ((-0.05 ,*y* 0.13) (0 0 0 1))) + (:finish-klarspueler . ((0.082 ,*y* 0.15) (0 0 0 1))) + (:denkmit-spuelmaschienen-tabs-allinone . ((0.203 ,*y* 0.14) (0 0 0 1)))) + + ("level_0_link" + (:domestos-allzweckreiniger . ((-0.43 ,(+ *y* *off*) 0.15) (0 0 0 1))) + (:sagrotan-allzweckreiniger . ((-0.30 ,(+ *y* *off*) 0.15) (0 0 0 1))) + (:denkmit-allzweckreiniger . ((-0.14 ,(+ *y* *off*) 0.14) (0 0 0 1))) + (:denkmit-allzweckreiniger-frueling . ((0.01 ,(+ *y* *off*) 0.15) (0 0 0 1))) + (:meister-proper-allzweckreiniger . ((0.15 ,(+ *y* *off*) 0.15) (0 0 0 1))) + (:denkmit-allzweckreiniger-limette . ((0.29 ,(+ *y* *off*) 0.145) (0 0 0 1))) + (:der-general-allzweckreiniger . ((0.42 ,(+ *y* *off*) 0.13) (0 0 0 1)))))) + +(defparameter *small-shelf-poses* + '("shelf_2_shelf_2_level_3_link" + (:balea-bottle . ((-0.15 -0.1 0.1) (0 0 0.5 0.5))) + (:dish-washer-tabs . ((0 -0.13 0.11) (0 0 0.5 0.5))))) + +(defparameter *basket-in-pr2-wrist* + (cl-transforms:make-transform + (cl-transforms:make-3d-vector 0.36 0 -0.15) + (cl-transforms:make-quaternion 0.0d0 -0.7071067811865475d0 + 0.0d0 0.7071067811865475d0))) + +(defparameter *basket-in-boxy-wrist* + (cl-transforms:make-transform + (cl-transforms:make-3d-vector 0 -0.15 0.48) + (cl-transforms:make-quaternion 0.5 0.5 0 0))) + +(defun spawn-object-n-times (type pose times color &optional offset-axis offset) + "`offset-axis' can be one of :x, :y or :z." + (loop for i from 0 to (1- times) + for name = (intern (string-upcase (format nil "~a-~a" type i)) :keyword) + do (when offset-axis + (setf pose (cram-tf:translate-pose pose offset-axis offset))) + ;; if object with name NAME already exists, create a new unique name + (when (btr:object btr:*current-bullet-world* name) + (setf i (+ i times) + name (intern (string-upcase (format nil "~a-~a" type i)) + :keyword))) + (btr:add-object btr:*current-bullet-world* :mesh name pose :mesh type + :mass 0.0 + :color color))) + +(defun spawn-objects-on-big-shelf () + (let ((type-and-pose-list + (make-poses-relative-multiple *big-shelf-poses* "shelf_1_"))) + (mapcar (lambda (type-and-pose) + (destructuring-bind (type . pose) type-and-pose + (spawn-object-n-times + type + pose + (+ (random 3) 1) ; times + `(,(float (/ (random 10) 10)) ; color + ,(float (/ (random 10) 10)) + ,(float (/ (random 10) 10))) + :x + 0.13))) + type-and-pose-list))) + +(defun spawn-objects-on-small-shelf () + (sb-ext:gc :full t) + (setf desig::*designators* (tg:make-weak-hash-table :weakness :key)) + (btr:clear-costmap-vis-object) + ;; (btr-utils:kill-all-objects) + (btr:detach-all-objects (btr:get-robot-object)) + (btr:detach-all-objects (btr:get-environment-object)) + (mapcar (lambda (type-and-pose) + (destructuring-bind (type . pose) type-and-pose + (spawn-object-n-times type pose 1 + (case type + (:dish-washer-tabs '(0 1 0)) + (t '(1.0 1.0 0.9)))))) + (make-poses-relative *small-shelf-poses*)) + ;; (btr:simulate btr:*current-bullet-world* 50) + (btr-utils:move-robot '((1.0 0 0) (0 0 0 1)))) + +(defun spawn-basket () + (let* ((left-ee-frame + (cut:var-value + '?end-effector-link + (car + (prolog:prolog + `(and (rob-int:robot ?robot) + (rob-int:end-effector-link ?robot :left ?end-effector-link)))))) + (map-T-wrist + (btr:link-pose (btr:get-robot-object) left-ee-frame)) + (wrist-T-basket + (case (rob-int:get-robot-name) + (:pr2 *basket-in-pr2-wrist*) + (t *basket-in-boxy-wrist*))) + (map-T-basket + (cl-transforms:transform* + (cl-transforms:pose->transform map-T-wrist) + wrist-T-basket)) + (basket-pose + (cl-transforms:transform->pose map-T-basket)) + (basket-desig + (desig:an object (type basket) (name b)))) + (btr:add-object btr:*current-bullet-world* :basket + :b + basket-pose + :mass 1 + :length 0.5 :width 0.3 :height 0.18 :handle-height 0.09) + (coe:on-event + (make-instance 'cpoe:object-attached-robot + :link left-ee-frame + :not-loose t + :grasp :top + :arm :left + :object-name :b + :object-designator basket-desig)))) + + + +(defun retail-demo () + (urdf-proj:with-simulated-robot + + (setf btr:*visibility-threshold* 0.5) + (btr-utils:kill-all-objects) + (spawn-objects-on-small-shelf) + (spawn-objects-on-big-shelf) + (unless (eql (rob-int:get-robot-name) :iai-donbot) + (spawn-basket)) + + (let* ((?environment-name + (rob-int:get-environment-name)) + (?robot-name + (rob-int:get-robot-name)) + (?search-location + (desig:a location + (on (desig:an object + (type shelf) + (urdf-name shelf-2-base) + (owl-name "shelf_system_verhuetung") + (part-of ?environment-name) + (level 4))) + (side left) + (range 0.2))) + + (?dish-washer-tabs-desig + (desig:an object + (type dish-washer-tabs) + (location ?search-location))) + (?balea-bottle-desig + (desig:an object + (type balea-bottle) + (location ?search-location))) + (?target-location-shelf-dish-washer-tabs + (desig:a location + (on (desig:an object + (type environment) + (name ?environment-name) + (part-of ?environment-name) + (urdf-name shelf-1-level-2-link))) + (for ?dish-washer-tabs-desig) + (attachments (dish-washer-tabs-shelf-1-front + dish-washer-tabs-shelf-1-back)))) + (?target-location-shelf-balea-bottle + (desig:a location + (on (desig:an object + (type environment) + (name ?environment-name) + (part-of ?environment-name) + (urdf-name shelf-1-level-2-link))) + (for ?balea-bottle-desig) + (attachments (balea-bottle-shelf-1-front + balea-bottle-shelf-1-back)))) + (?target-location-tray-dish-washer-tabs + (desig:a location + (on (desig:an object + (type robot) + (name ?robot-name) + (part-of ?environment-name) + (owl-name "donbot_tray") + (urdf-name plate))) + (for ?dish-washer-tabs-desig) + (attachments (donbot-tray-front donbot-tray-back)))) + (?target-location-basket-dish-washer-tabs + (desig:a location + (on (desig:an object + (type basket) + (name b))) + (for ?dish-washer-tabs-desig) + (attachments (; in-basket-front + in-basket-back)))) + (?target-location-robot-dish-washer-tabs + (case ?robot-name + (:iai-donbot ?target-location-tray-dish-washer-tabs) + (t ?target-location-basket-dish-washer-tabs)))) + + (exe:perform + (desig:an action + (type transporting) + (object ?dish-washer-tabs-desig) + (target ?target-location-robot-dish-washer-tabs))) + (exe:perform + (desig:an action + (type transporting) + (object ?balea-bottle-desig) + (target ?target-location-shelf-balea-bottle))) + (exe:perform + (desig:an action + (type transporting) + (object ?dish-washer-tabs-desig) + (target ?target-location-shelf-dish-washer-tabs))) + + ;; look at separators + ;; (exe:perform + ;; (desig:an action + ;; (type looking) + ;; (direction right-separators))) + ;; (cpl:sleep 5.0) + ))) + + + + + + + + + + + + + + + +#+stuff-to-test-real-robot-interfaces +(defun stuff-that-works () + (cram-process-modules:with-process-modules-running + (giskard:giskard-pm) + (cpl-impl::named-top-level (:name :top-level) + (exe:perform + (let ((?pose (cl-transforms-stamped:make-pose-stamped + "base_footprint" 0.0 + (cl-transforms:make-3d-vector + -0.27012088894844055d0 + 0.5643729567527771d0 + 1.25943687558174133d0) + (cl-transforms:make-quaternion + -0.4310053586959839d0 + 0.24723316729068756d0 + 0.752766489982605d0 + 0.4318017065525055d0 )))) + (desig:a motion + (type moving-tcp) + (left-pose ?pose) + (collision-mode :allow-all))))))) diff --git a/cram_demos/cram_projection_demos/src/setup.lisp b/cram_demos/cram_projection_demos/src/setup.lisp new file mode 100644 index 0000000000..7f71b7dd79 --- /dev/null +++ b/cram_demos/cram_projection_demos/src/setup.lisp @@ -0,0 +1,121 @@ +;;; +;;; Copyright (c) 2017, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Intelligent Autonomous Systems Group/ +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software +;;; without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :demos) + +;; roslaunch cram_projection_demos ....launch + +(defun init-projection () + ;; (setf cram-tf:*transformer* (make-instance 'cl-tf2:buffer-client)) + (setf cram-tf:*tf-default-timeout* 0.5) ; projection tf is very fast + ;; (setf cram-tf:*tf-broadcasting-enabled* t) + + ;; (btr-belief:setup-world-database) + (coe:clear-belief) + + (setf prolog:*break-on-lisp-errors* t) + + (btr:clear-costmap-vis-object) + + (btr:add-objects-to-mesh-list "assembly_models" + :directory "fixtures" + :extension "stl") + (btr:add-objects-to-mesh-list "assembly_models" + :directory "battat/convention" + :extension "stl") + (btr:add-objects-to-mesh-list "cram_projection_demos" + :directory "resource/household") + (btr:add-objects-to-mesh-list "cram_projection_demos" + :directory "resource/retail")) + +(roslisp-utilities:register-ros-init-function init-projection) + + + +(defun make-poses-relative (spawning-poses &optional frame-prefix) + "Gets an associative list in a form of + (FRAME (TYPE . COORDINATES-LIST) + (TYPE2 . COORDS2) + ...), +where coordinates-list is defined in the FRAME coordinate frame. +If `frame-prefix' is given, instead of FRAME 'frame-prefixFRAME' is used. +Converts these coordinates into CRAM-TF:*FIXED-FRAME* frame +and returns a list in form + ((TYPE . POSE) (TYPE2 . POSE2) ...)." + (when spawning-poses + (destructuring-bind (frame . type-and-pose-list) + spawning-poses + (let* ((map-T-surface + (cl-transforms:pose->transform + (btr:link-pose (btr:get-environment-object) + (concatenate 'string frame-prefix frame))))) + (mapcar (lambda (type-and-pose) + (destructuring-bind (type . pose-list) + type-and-pose + (let* ((surface-T-object + (cl-transforms:pose->transform + (cram-tf:list->pose pose-list))) + (map-T-object + (cl-transforms:transform* + map-T-surface surface-T-object)) + (map-P-object + (cl-transforms:transform->pose map-T-object))) + `(,type . ,map-P-object)))) + type-and-pose-list))))) + +(defun make-poses-relative-multiple (poses &optional frame-prefix) + "Gets a list of ((FRAME1 ((TYPE1 . COORDS1) (TYPE2 . COORDS2) ...)) + (FRAME2 ((TYPEN . COORDSN) ...))). +Converts these coordinates into CRAM-TF:*FIXED-FRAME* frame +and returns a list in form + ((TYPE . POSE) ...)." + (mapcan (lambda (frame-and-list-of-type-and-coords) + (make-poses-relative frame-and-list-of-type-and-coords frame-prefix)) + poses)) + +(defun make-poses-list-relative (spawning-poses-list) + "Gets a list of ((:type \"frame\" cords-list) ...) +Converts these coordinates into CRAM-TF:*FIXED-FRAME* frame and returns a list in form + ((TYPE . POSE) ...)." + (when spawning-poses-list + (mapcar (lambda (type-and-frame-and-pose-list) + (destructuring-bind (type frame pose-list) + type-and-frame-and-pose-list + (let* ((map-T-surface + (cl-transforms:pose->transform + (btr:link-pose (btr:get-environment-object) frame))) + (surface-T-object + (cl-transforms:pose->transform + (cram-tf:list->pose pose-list))) + (map-T-object + (cl-transforms:transform* map-T-surface surface-T-object)) + (map-P-object + (cl-transforms:transform->pose map-T-object))) + `(,type . ,map-P-object)))) + spawning-poses-list))) diff --git a/cram_demos/cram_projection_demos/tests/package.lisp b/cram_demos/cram_projection_demos/tests/package.lisp new file mode 100644 index 0000000000..295ddd3bd4 --- /dev/null +++ b/cram_demos/cram_projection_demos/tests/package.lisp @@ -0,0 +1,3 @@ +(defpackage :cram-pr2-pick-place-demo-tests + (:nicknames :demo-tests) + (:use :common-lisp :lisp-unit)) diff --git a/cram_demos/cram_projection_demos/tests/projection-demo-tests.lisp b/cram_demos/cram_projection_demos/tests/projection-demo-tests.lisp new file mode 100644 index 0000000000..bae7e55195 --- /dev/null +++ b/cram_demos/cram_projection_demos/tests/projection-demo-tests.lisp @@ -0,0 +1,94 @@ +(in-package :cram-pr2-pick-place-demo-tests) + +(defparameter *relative-poses* + '("sink_area_surface" + ((:breakfast-cereal . ((0.2 -0.15 0.1) (0 0 0 1))) + (:cup . ((0.2 -0.35 0.1) (0 0 0 1))) + (:bowl . ((0.18 -0.55 0.1) (0 0 0 1))) + (:spoon . ((0.15 -0.4 -0.05) (0 0 0 1))) + (:milk . ((0.07 -0.35 0.1) (0 0 0 1)))))) + +(defun round-to (number precision &optional (what #'round)) + (let ((div (expt 10 precision))) + (/ (funcall what (* number div)) div))) + +(defun round-poses (type-pose-pairs &key (precision 3)) + (mapcar (lambda (type-pose-pair) + (with-slots (cl-transforms:x cl-transforms:y cl-transforms:z) + (cl-transforms:origin (cdr type-pose-pair)) + `(,(float (round-to cl-transforms:x precision)) + ,(float (round-to cl-transforms:y precision)) + ,(float (round-to cl-transforms:z precision))))) + type-pose-pairs)) + +(defun move-surface (&key (x 0) (y 0) (z 0) (alpha 0.0)) + (let* ((old-pose (btr:link-pose (btr:get-environment-object) "sink_area_surface")) + (rotated-pose (cram-tf:rotate-pose old-pose :z alpha)) + (new-pose (cram-tf:translate-pose rotated-pose :x x :y y :z z))) + (setf (btr:link-pose (btr:get-environment-object) "sink_area_surface") + new-pose))) + + +(define-test make-poses-relative-default + (let* ((goal '((1.335 0.44 0.94) ;; breakfast-cereal + (1.335 0.64 0.94) ;; cup + (1.355 0.84 0.94) ;; bowl + (1.385 0.69 0.79) ;; spoon + (1.465 0.64 0.94))) ;; milk + (poses (round-poses + (cram-pr2-pick-place-demo::make-poses-relative *relative-poses*)))) + (lisp-unit:assert-equal goal poses))) + + +(define-test make-poses-relative-x-move + (let ((goal '((2.335 0.44 0.94) ;; breakfast-cereal + (2.335 0.64 0.94) ;; cup + (2.355 0.84 0.94) ;; bowl + (2.385 0.69 0.79) ;; spoon + (2.465 0.64 0.94)))) ;; milk + (move-surface :x 1) + (unwind-protect + (let ((poses (round-poses + (cram-pr2-pick-place-demo::make-poses-relative *relative-poses*)))) + (lisp-unit:assert-equal goal poses)) + (move-surface :x -1)))) + +(define-test make-poses-relative-y-move + (let ((goal '((1.335 1.44 0.94) ;; breakfast-cereal + (1.335 1.64 0.94) ;; cup + (1.355 1.84 0.94) ;; bowl + (1.385 1.69 0.79) ;; spoon + (1.465 1.64 0.94)))) ;; milk + (move-surface :y 1) + (unwind-protect + (let ((poses (round-poses + (cram-pr2-pick-place-demo::make-poses-relative *relative-poses*)))) + (lisp-unit:assert-equal goal poses)) + (move-surface :y -1)))) + +(define-test make-poses-relative-z-move + (let ((goal '((1.335 0.44 1.94) ;; breakfast-cereal + (1.335 0.64 1.94) ;; cup + (1.355 0.84 1.94) ;; bowl + (1.385 0.69 1.79) ;; spoon + (1.465 0.64 1.94)))) ;; milk + (move-surface :z 1) + (unwind-protect + (let ((poses (round-poses + (cram-pr2-pick-place-demo::make-poses-relative *relative-poses*)))) + (lisp-unit:assert-equal goal poses)) + (move-surface :z -1)))) + + +(define-test make-poses-relative-alpha-move + (let ((goal '((1.735 0.14 0.94) ;; breakfast-cereal + (1.735 -0.06 0.94) ;; cup + (1.715 -0.26 0.94) ;; bowl + (1.685 -0.11 0.79) ;; spoon + (1.605 -0.06 0.94)))) ;; milk + (move-surface :alpha pi) + (unwind-protect + (let ((poses (round-poses + (cram-pr2-pick-place-demo::make-poses-relative *relative-poses*)))) + (lisp-unit:assert-equal goal poses)) + (move-surface :alpha (- pi))))) diff --git a/cram_pr2/cram_pr2_arm_kinematics/CMakeLists.txt b/cram_donbot/cram_donbot_description/CMakeLists.txt similarity index 72% rename from cram_pr2/cram_pr2_arm_kinematics/CMakeLists.txt rename to cram_donbot/cram_donbot_description/CMakeLists.txt index 78d5cb43a3..6c8417596d 100644 --- a/cram_pr2/cram_pr2_arm_kinematics/CMakeLists.txt +++ b/cram_donbot/cram_donbot_description/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 2.8.3) -project(cram_pr2_arm_kinematics) +project(cram_donbot_description) find_package(catkin REQUIRED) catkin_package() diff --git a/cram_boxy/cram_boxy_designators/cram-boxy-designators.asd b/cram_donbot/cram_donbot_description/cram-donbot-description.asd similarity index 85% rename from cram_boxy/cram_boxy_designators/cram-boxy-designators.asd rename to cram_donbot/cram_donbot_description/cram-donbot-description.asd index 57f044d7eb..c8bed648fc 100644 --- a/cram_boxy/cram_boxy_designators/cram-boxy-designators.asd +++ b/cram_donbot/cram_donbot_description/cram-donbot-description.asd @@ -1,4 +1,4 @@ -;;; Copyright (c) 2017, Gayane Kazhoyan +;;; Copyright (c) 2019, Gayane Kazhoyan ;;; All rights reserved. ;;; ;;; Redistribution and use in source and binary forms, with or without @@ -26,17 +26,17 @@ ;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE ;;; POSSIBILITY OF SUCH DAMAGE. -(defsystem cram-boxy-designators +(defsystem cram-donbot-description :author "Gayane Kazhoyan" :maintainer "Gayane Kazhoyan" :license "BSD" - :depends-on (cram-designators - cram-prolog - cram-designator-specification - cram-tf) + :depends-on (cram-prolog + cram-robot-interfaces + cram-location-costmap ; for robot-specific costmap metadata + ) :components ((:module "src" :components ((:file "package") - (:file "motions" :depends-on ("package")))))) + (:file "knowledge" :depends-on ("package")))))) diff --git a/cram_pr2/cram_pr2_arm_kinematics/package.xml b/cram_donbot/cram_donbot_description/package.xml similarity index 50% rename from cram_pr2/cram_pr2_arm_kinematics/package.xml rename to cram_donbot/cram_donbot_description/package.xml index 4d946246e6..19cb2699a7 100644 --- a/cram_pr2/cram_pr2_arm_kinematics/package.xml +++ b/cram_donbot/cram_donbot_description/package.xml @@ -1,8 +1,8 @@ - cram_pr2_arm_kinematics + cram_donbot_description 0.7.0 - cram_pr2_arm_kinematics + Prolog predicates describing Donbot the robot Gayane Kazhoyan Gayane Kazhoyan @@ -10,14 +10,7 @@ catkin - cram_robot_interfaces - cram_pr2_description - cram_tf - cl_transforms_stamped - cl_transforms - moveit_msgs cram_prolog - cram_utilities - roslisp - pr2_arm_kinematics + cram_robot_interfaces + cram_location_costmap diff --git a/cram_donbot/cram_donbot_description/src/knowledge.lisp b/cram_donbot/cram_donbot_description/src/knowledge.lisp new file mode 100644 index 0000000000..8f44b4f551 --- /dev/null +++ b/cram_donbot/cram_donbot_description/src/knowledge.lisp @@ -0,0 +1,247 @@ +;;; +;;; Copyright (c) 2019, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :donbot-descr) + +(defparameter *tcp-in-ee-pose* + (cl-transforms:make-pose + (cl-transforms:make-3d-vector 0 0 0.2581d0) + (cl-transforms:make-quaternion 0 0 -0.7071067811849626d0 -0.7071067811881324d0))) + +(defparameter *standard-to-donbot-gripper-transform* + (cl-transforms-stamped:make-identity-transform)) + +(defparameter *ee-p-camera* + (cl-transforms:make-pose + (cl-transforms:make-3d-vector -0.04214122915220634d0 + 0.022506720839268142d0 + 0.1335101519901074d0) + (cl-transforms:make-quaternion -0.006114286700067816d0 + 0.003707211262453658d0 + -0.7139449315234562d0 + 0.7001653424975933d0))) + + +(def-fact-group donbot-metadata (robot-odom-frame + robot-base-frame robot-torso-link-joint + arm + neck + camera-frame + camera-minimal-height camera-maximal-height + camera-horizontal-angle camera-vertical-angle) + + (<- (robot-odom-frame :iai-donbot "odom")) + + (<- (robot-base-frame :iai-donbot "base_footprint")) + (<- (robot-torso-link-joint :iai-donbot "ur5_base_link" "arm_base_mounting_joint")) + + (<- (arm :iai-donbot :left)) + + (<- (neck :iai-donbot :left)) + + (<- (camera-frame :iai-donbot "camera_link")) ; rgb camera for barcodes etc. + (<- (camera-frame :iai-donbot "rs_camera_depth_optical_frame")) ; realsense, virtual + (<- (camera-frame :iai-donbot "rs_camera_color_optical_frame")) ; virtual + + ;; (<- (camera-minimal-height :iai-donbot 0.5)) + ;; (<- (camera-maximal-height :iai-donbot 1.2)) + + ;; These are values taken from the Kinect's wikipedia page for the 360 variant + (<- (camera-horizontal-angle donbot 0.99483)) + (<- (camera-vertical-angle donbot 0.75049))) + + +(def-fact-group donbot-arm-facts (arm-joints arm-links + hand-links hand-link hand-finger-link + gripper-joint gripper-meter-to-joint-multiplier + standard<-particular-gripper-transform + end-effector-link + robot-tool-frame + tcp-in-ee-pose + robot-joint-states) + + (<- (arm-joints :iai-donbot :left ("ur5_shoulder_pan_joint" + "ur5_shoulder_lift_joint" + "ur5_elbow_joint" + "ur5_wrist_1_joint" + "ur5_wrist_2_joint" + "ur5_wrist_3_joint"))) + + (<- (arm-links :iai-donbot :left ("ur5_shoulder_link" + "ur5_upper_arm_link" + "ur5_forearm_link" + "ur5_wrist_1_link" + "ur5_wrist_2_link" + "ur5_wrist_3_link"))) + + (<- (hand-links :iai-donbot :left ("wrist_collision" + "gripper_base_link" + "gripper_finger_left_link" + "gripper_finger_right_link" + "gripper_gripper_left_link" + "gripper_gripper_right_link"))) + + (<- (hand-link :iai-donbot :left ?link) + (bound ?link) + (or (and (lisp-fun search "gripper_" ?link ?pos) + (lisp-pred identity ?pos)) + (and (lisp-fun search "finger" ?link ?pos) + (lisp-pred identity ?pos)))) + + (<- (hand-finger-link :iai-donbot ?arm ?link) + (bound ?link) + (hand-link :iai-donbot ?arm ?link) + (lisp-fun search "finger" ?link ?pos) + (lisp-pred identity ?pos)) + + (<- (gripper-joint :iai-donbot :left "gripper_joint")) + + (<- (gripper-meter-to-joint-multiplier :iai-donbot 1.0)) + + (<- (standard<-particular-gripper-transform :iai-donbot ?transform) + (symbol-value *standard-to-donbot-gripper-transform* ?transform)) + + (<- (end-effector-link :iai-donbot :left "ur5_wrist_3_link")) + + (<- (robot-tool-frame :iai-donbot :left "refills_tool_frame")) + + (<- (tcp-in-ee-pose :iai-donbot ?pose) + (symbol-value *tcp-in-ee-pose* ?pose)) + + (<- (robot-joint-states :iai-donbot :arm :left :carry + ;; (("ur5_shoulder_pan_joint" 0.29503026604652405d0) + ;; ("ur5_shoulder_lift_joint" -1.8346226851092737d0) + ;; ("ur5_elbow_joint" 2.1440072059631348d0) + ;; ("ur5_wrist_1_joint" -3.4500272909747522d0) + ;; ("ur5_wrist_2_joint" -1.8935192267047327d0) + ;; ("ur5_wrist_3_joint" -1.425162140523092d0)) + ;; (("ur5_shoulder_pan_joint" 3.378162384033203d0) + ;; ("ur5_shoulder_lift_joint" -1.5641868750201624d0) + ;; ("ur5_elbow_joint" -0.9430778662310999d0) + ;; ("ur5_wrist_1_joint" -2.2492716948138636d0) + ;; ("ur5_wrist_2_joint" 1.5673996210098267d0) + ;; ("ur5_wrist_3_joint" -3.5105767885791224d0)) + (("ur5_shoulder_pan_joint" 3.234022855758667d0) + ("ur5_shoulder_lift_joint" -1.5068710486041468d0) + ("ur5_elbow_joint" -0.7870314756976526d0) + ("ur5_wrist_1_joint" -2.337625328694479d0) + ("ur5_wrist_2_joint" 1.5699548721313477d0) + ("ur5_wrist_3_joint" -1.6504042784320276d0)))) + (<- (robot-joint-states :iai-donbot :arm :left :park ?joint-states) + (robot-joint-states :iai-donbot :arm :left :carry ?joint-states)) + (<- (robot-joint-states :iai-donbot :arm :left :carry-top ?joint-states) + (robot-joint-states :iai-donbot :arm :left :carry ?joint-states)) + (<- (robot-joint-states :iai-donbot :arm :left :carry-side-gripper-vertical + ?joint-states) + (robot-joint-states :iai-donbot :arm :left :carry ?joint-states))) + + + +(def-fact-group donbot-neck-facts (robot-neck-links robot-neck-joints + robot-neck-base-link + camera-in-neck-ee-pose + neck-camera-z-offset + neck-camera-pose-unit-vector-multiplier + neck-camera-resampling-step + neck-camera-x-axis-limit + neck-camera-y-axis-limit + neck-camera-z-axis-limit + robot-joint-states) + + (<- (robot-neck-links :iai-donbot . ?links) + (arm-links :iai-donbot :left ?links)) + + (<- (robot-neck-joints :iai-donbot . ?joints) + (arm-joints :iai-donbot :left ?joints)) + + (<- (robot-neck-base-link :iai-donbot "ur5_base_link")) + + (<- (camera-in-neck-ee-pose :iai-donbot ?pose) + (symbol-value *ee-p-camera* ?pose)) + + (<- (neck-camera-z-offset :iai-donbot 0.6)) + (<- (neck-camera-pose-unit-vector-multiplier :iai-donbot 0.4)) + (<- (neck-camera-resampling-step :iai-donbot 0.1)) + (<- (neck-camera-x-axis-limit :iai-donbot 0.5)) + (<- (neck-camera-y-axis-limit :iai-donbot 0.5)) + (<- (neck-camera-z-axis-limit :iai-donbot 0.2)) + + (<- (robot-joint-states :iai-donbot :neck ?there-is-only-one-neck :away + ?joint-states) + (robot-joint-states :iai-donbot :arm :left :carry ?joint-states)) + (<- (robot-joint-states :iai-donbot :neck ?there-is-only-one-neck :forward + ?joint-states) + (robot-joint-states :iai-donbot :arm :left :carry ?joint-states)) + (<- (robot-joint-states :iai-donbot :neck ?there-is-only-one-neck :down + (("ur5_shoulder_pan_joint" 4.130944728851318d0) + ("ur5_shoulder_lift_joint" 0.04936718940734863d0) + ("ur5_elbow_joint" -1.9734209219561976d0) + ("ur5_wrist_1_joint" -1.7624157110797327d0) + ("ur5_wrist_2_joint" 1.6369260549545288d0) + ("ur5_wrist_3_joint" -1.6503327528582972d0)))) + (<- (robot-joint-states :iai-donbot :neck ?there-is-only-one-neck :right + (("ur5_shoulder_pan_joint" 1.6281344890594482d0) + ("ur5_shoulder_lift_joint" -1.4734271208392542d0) + ("ur5_elbow_joint" -1.1555221716510218d0) + ("ur5_wrist_1_joint" -0.9881671110736292d0) + ("ur5_wrist_2_joint" 1.4996352195739746d0) + ("ur5_wrist_3_joint" -1.4276765028582972d0)))) + (<- (robot-joint-states :iai-donbot :neck ?there-is-only-one-neck :right-separators + (("ur5_shoulder_pan_joint" 1.4752850532531738d0) + ("ur5_shoulder_lift_joint" -1.4380276838885706d0) + ("ur5_elbow_joint" -1.9198325316058558d0) + ("ur5_wrist_1_joint" -0.0680769125567835d0) + ("ur5_wrist_2_joint" 1.704722285270691d0) + ("ur5_wrist_3_joint" -1.5686963240252894d0)))) + (<- (robot-joint-states :iai-donbot :neck ?there-is-only-one-neck + :right-separators-preplace-state + (("ur5_shoulder_pan_joint" 1.585883378982544d0) + ("ur5_shoulder_lift_joint" -0.49957687059511d0) + ("ur5_elbow_joint" -1.61414081255068d0) + ("ur5_wrist_1_joint" -1.1720898787127894d0) + ("ur5_wrist_2_joint" 1.37771737575531d0) + ("ur5_wrist_3_joint" -1.3602331320392054d0))))) + + +(def-fact-group location-costmap-metadata (costmap:costmap-padding + costmap:costmap-manipulation-padding + costmap:costmap-in-reach-distance + costmap:costmap-reach-minimal-distance + costmap:orientation-samples + costmap:orientation-sample-step + costmap:reachability-orientation-offset + costmap:visibility-costmap-size) + (<- (costmap:costmap-padding :iai-donbot 0.5)) + (<- (costmap:costmap-manipulation-padding :iai-donbot 0.5)) + (<- (costmap:costmap-in-reach-distance :iai-donbot 1.1)) + (<- (costmap:costmap-reach-minimal-distance :iai-donbot 0.1)) + (<- (costmap:orientation-samples :iai-donbot 1)) + (<- (costmap:orientation-sample-step :iai-donbot 0.3)) + (<- (costmap:reachability-orientation-offset :iai-donbot 1.57)) + (<- (costmap:visibility-costmap-size :iai-donbot 2.0))) diff --git a/cram_pr2/cram_pr2_cloud/src/package.lisp b/cram_donbot/cram_donbot_description/src/package.lisp similarity index 89% rename from cram_pr2/cram_pr2_cloud/src/package.lisp rename to cram_donbot/cram_donbot_description/src/package.lisp index 7467fc0f8b..d0ee197462 100644 --- a/cram_pr2/cram_pr2_cloud/src/package.lisp +++ b/cram_donbot/cram_donbot_description/src/package.lisp @@ -1,5 +1,5 @@ ;;; -;;; Copyright (c) 2017, Gayane Kazhoyan +;;; Copyright (c) 2019, Gayane Kazhoyan ;;; All rights reserved. ;;; ;;; Redistribution and use in source and binary forms, with or without @@ -29,7 +29,6 @@ (in-package :cl-user) -(defpackage cram-pr2-cloud - (:nicknames :pr2-cloud) - (:use #:common-lisp #:cram-prolog #:cram-tf ;; #:cram-designators - )) +(defpackage cram-donbot-description + (:nicknames #:donbot-descr) + (:use #:common-lisp #:cram-prolog #:cram-robot-interfaces)) diff --git a/cram_boxy/cram_boxy_plans/CMakeLists.txt b/cram_donbot/cram_donbot_low_level/CMakeLists.txt similarity index 73% rename from cram_boxy/cram_boxy_plans/CMakeLists.txt rename to cram_donbot/cram_donbot_low_level/CMakeLists.txt index 80d84b24d3..041c06eb2f 100644 --- a/cram_boxy/cram_boxy_plans/CMakeLists.txt +++ b/cram_donbot/cram_donbot_low_level/CMakeLists.txt @@ -1,5 +1,5 @@ cmake_minimum_required(VERSION 2.8.3) -project(cram_boxy_plans) +project(cram_donbot_low_level) find_package(catkin REQUIRED) catkin_package() diff --git a/cram_boxy/cram_boxy_projection/cram-boxy-projection.asd b/cram_donbot/cram_donbot_low_level/cram-donbot-low-level.asd similarity index 60% rename from cram_boxy/cram_boxy_projection/cram-boxy-projection.asd rename to cram_donbot/cram_donbot_low_level/cram-donbot-low-level.asd index cbaa0544b9..01df4f3f10 100644 --- a/cram_boxy/cram_boxy_projection/cram-boxy-projection.asd +++ b/cram_donbot/cram_donbot_low_level/cram-donbot-low-level.asd @@ -1,4 +1,5 @@ -;;; Copyright (c) 2017, Gayane Kazhoyan +;;; +;;; Copyright (c) 2019, Gayane Kazhoyan ;;; All rights reserved. ;;; ;;; Redistribution and use in source and binary forms, with or without @@ -26,35 +27,44 @@ ;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE ;;; POSSIBILITY OF SUCH DAMAGE. -(defsystem cram-boxy-projection +(defsystem cram-donbot-low-level :author "Gayane Kazhoyan" + :maintainer "Gayane Kazhoyan" :license "BSD" - :depends-on (cram-projection - cram-prolog - cram-designators + :depends-on (roslisp + roslisp-msg-protocol ; for ros-message class type + roslisp-utilities + actionlib + cl-transforms-stamped + cl-transforms + cram-simple-actionlib-client + cram-language ; for with-failure-handling to the least cram-utilities - cram-bullet-reasoning + cram-prolog + ;; cram-math ; for degrees->radians cram-tf - cram-robot-interfaces ; for ROBOT predicate and COMPUTE-IKS - cl-transforms - cl-transforms-stamped - cl-tf - cram-occasions-events - cram-plan-occasions-events - cram-boxy-description ; to get kinematic structure names - cram-common-designators cram-common-failures - cram-process-modules - alexandria ; for CURRY in low-level perception - roslisp-utilities ; for rosify-lisp-name - cram-bullet-reasoning-belief-state ; for special projection variable definition - cram-ik-interface) + ;; for reading out arm joint names + cram-robot-interfaces + cram-joint-states + cram-donbot-description + ;; msgs for low-level communication + slipping_control_msgs-msg + slipping_control_msgs-srv + sun_tactile_common-msg + ;; geometry_msgs-msg ; for force-torque sensor wrench + ;; std_srvs-srv ; for zeroing force-torque sensor + ;; sensor_msgs-msg + ;; visualization_msgs-msg + ;; iai_wsg_50_msgs-msg + ;; control_msgs-msg ; neck message + ;; trajectory_msgs-msg ; also for neck + ;; ;; iai_control_msgs-msg ; neck message + ;; iai_dlr_msgs-msg + ) :components ((:module "src" :components ((:file "package") - (:file "tf" :depends-on ("package")) - (:file "low-level" :depends-on ("package" "tf")) - (:file "process-modules" :depends-on ("package" "low-level")) - (:file "projection-environment" :depends-on ("package" "tf" "process-modules")))))) + (:file "grippers" :depends-on ("package")))))) diff --git a/cram_donbot/cram_donbot_low_level/package.xml b/cram_donbot/cram_donbot_low_level/package.xml new file mode 100644 index 0000000000..c3556c6811 --- /dev/null +++ b/cram_donbot/cram_donbot_low_level/package.xml @@ -0,0 +1,39 @@ + + cram_donbot_low_level + 0.7.0 + + Low-level code for Donbot + + Gayane Kazhoyan + Gayane Kazhoyan + BSD + + catkin + + roslisp + roslisp_utilities + actionlib_lisp + cl_transforms_stamped + cl_transforms + cram_simple_actionlib_client + cram_language + cram_utilities + cram_prolog + + cram_tf + cram_common_failures + cram_robot_interfaces + cram_joint_states + cram_donbot_description + slipping_control_msgs + sun_tactile_common + + + + + + + + + + diff --git a/cram_donbot/cram_donbot_low_level/src/grippers.lisp b/cram_donbot/cram_donbot_low_level/src/grippers.lisp new file mode 100644 index 0000000000..e33bb19549 --- /dev/null +++ b/cram_donbot/cram_donbot_low_level/src/grippers.lisp @@ -0,0 +1,157 @@ +;;; +;;; Copyright (c) 2019, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of Willow Garage, Inc. nor the names of its +;;; contributors may be used to endorse or promote products derived from +;;; this software without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :donbot-ll) + +(defparameter *gripper-action-timeout* 20.0 "in seconds") + +(defparameter *gripper-velocity-convergence-delta* 0.00000001 "in meters/second") +(defparameter *gripper-convergence-delta* 0.005 "in meters") + +(defun make-gripper-action-clients () + (actionlib-client:make-simple-action-client + 'gripper-home-action + "wsg50/home_gripper_action" + "slipping_control_msgs/HomeGripperAction" + *gripper-action-timeout*) + + (actionlib-client:make-simple-action-client + 'gripper-grasp-action + "wsg50/grasp_action" + "slipping_control_msgs/GraspAction" + *gripper-action-timeout*) + + (actionlib-client:make-simple-action-client + 'gripper-zero-left-action + "wsg50/finger0/compute_bias_action" + "sun_tactile_common/ComputeBiasAction" + *gripper-action-timeout*) + (actionlib-client:make-simple-action-client + 'gripper-zero-right-action + "wsg50/finger1/compute_bias_action" + "sun_tactile_common/ComputeBiasAction" + *gripper-action-timeout*)) + +(roslisp-utilities:register-ros-init-function make-gripper-action-clients) + +(defun call-gripper-set-object-parameters-service (object-parameter) + (let ((service-name-0 "wsg50/ls_0/change_params") + (service-name-1 "wsg50/ls_1/change_params")) + (cpl:with-failure-handling + ((roslisp::ros-rpc-error (e) + (format t "ROS communication error occured!~%~a~%Retrying...~%~%" e) + (loop until (roslisp:wait-for-service service-name-0 10) + do (roslisp:ros-info (donbot-ll change-params) + "Waiting for ~a service server..." + service-name-0)) + (loop until (roslisp:wait-for-service service-name-1 10) + do (roslisp:ros-info (donbot-ll change-params) + "Waiting for ~a service server..." + service-name-1)) + (cpl:retry))) + (roslisp:call-service service-name-0 'slipping_control_msgs-srv:chlsparams + :mu object-parameter) + (roslisp:call-service service-name-1 'slipping_control_msgs-srv:chlsparams + :mu object-parameter)))) + + +(defun make-gripper-home-action-goal () + (roslisp:make-message + 'slipping_control_msgs-msg:HomeGripperGoal)) + +(defun call-gripper-home-action () + (actionlib-client:call-simple-action-client + 'gripper-home-action + :action-goal (make-gripper-home-action-goal))) + + +(defun make-gripper-zero-action-goal () + (roslisp:make-message + 'sun_tactile_common-msg:ComputeBiasGoal)) + +(defun call-gripper-zero-actions () + (actionlib-client:call-simple-action-client + 'gripper-zero-left-action + :action-goal (make-gripper-zero-action-goal)) + (actionlib-client:call-simple-action-client + 'gripper-zero-right-action + :action-goal (make-gripper-zero-action-goal))) + + +(defun make-gripper-grasp-action-goal () + (roslisp:make-message + 'slipping_control_msgs-msg:GraspGoal + :desired_force 20.0)) + +(defun call-gripper-grasp-action () + (actionlib-client:call-simple-action-client + 'gripper-grasp-action + :action-goal (make-gripper-grasp-action-goal)) + (cpl:sleep 7.0)) + + + + +(defun call-gripper-action (&key action-type-or-position left-or-right + effort-but-actually-slippage-parameter) + (declare (type (or keyword list) left-or-right) + (type (or null number) effort-but-actually-slippage-parameter) + (type (or null number keyword) action-type-or-position)) + "Goal position is given in meters." + + (unless (eq left-or-right :left) + (roslisp:ros-warn (donbot-ll gripper) + "Any gripper except left one is not supported.~%~ + Defaulting to left gripper.") + (setf left-or-right :left)) + + (unless effort-but-actually-slippage-parameter + (roslisp:ros-warn (donbot-ll gripper) + "effort-but-actually-slippage-parameter was not given..~%~ + Defaulting to 0.72.") + (setf effort-but-actually-slippage-parameter 0.72)) + + (etypecase action-type-or-position + (number + (roslisp:ros-warn (donbot-ll gripper) + "Gripper goals with numeric positions are not supported.~%~ + Simply opening the gripper.") + (call-gripper-home-action)) + (keyword + (ecase action-type-or-position + (:open + (call-gripper-home-action)) + (:close + (roslisp:ros-warn (donbot-ll gripper) + "Gripper goals to close gripper are not supported.~%~ + Not doing anything.")) + (:grip + (call-gripper-zero-actions) + (call-gripper-set-object-parameters-service + effort-but-actually-slippage-parameter) + (call-gripper-grasp-action)))))) diff --git a/cram_pr2/cram_pr2_arm_kinematics/src/package.lisp b/cram_donbot/cram_donbot_low_level/src/package.lisp similarity index 90% rename from cram_pr2/cram_pr2_arm_kinematics/src/package.lisp rename to cram_donbot/cram_donbot_low_level/src/package.lisp index 3b2e31ca29..80347b8e72 100644 --- a/cram_pr2/cram_pr2_arm_kinematics/src/package.lisp +++ b/cram_donbot/cram_donbot_low_level/src/package.lisp @@ -1,5 +1,5 @@ ;;; -;;; Copyright (c) 2016, Gayane Kazhoyan +;;; Copyright (c) 2019, Gayane Kazhoyan ;;; All rights reserved. ;;; ;;; Redistribution and use in source and binary forms, with or without @@ -29,7 +29,9 @@ (in-package :cl-user) -(defpackage cram-pr2-arm-kinematics - (:nicknames :pr2-ik-fk) +(defpackage cram-donbot-low-level + (:nicknames #:donbot-ll) (:use #:common-lisp) - (:export #:*use-arm-kinematics-interface*)) + (:export + ;; grippers + #:call-gripper-action)) diff --git a/cram_donbot/cram_donbot_process_modules/CMakeLists.txt b/cram_donbot/cram_donbot_process_modules/CMakeLists.txt new file mode 100644 index 0000000000..4193cefd29 --- /dev/null +++ b/cram_donbot/cram_donbot_process_modules/CMakeLists.txt @@ -0,0 +1,5 @@ +cmake_minimum_required(VERSION 2.8.3) +project(cram_donbot_process_modules) +find_package(catkin REQUIRED) +catkin_package() + diff --git a/cram_donbot/cram_donbot_process_modules/cram-donbot-process-modules.asd b/cram_donbot/cram_donbot_process_modules/cram-donbot-process-modules.asd new file mode 100644 index 0000000000..323f019fb6 --- /dev/null +++ b/cram_donbot/cram_donbot_process_modules/cram-donbot-process-modules.asd @@ -0,0 +1,52 @@ +;;; +;;; Copyright (c) 2019, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Intelligent Autonomous Systems Group/ +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software +;;; without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(defsystem cram-donbot-process-modules + :author "Gayane Kazhoyan" + :maintainer "Gayane Kazhoyan" + :license "BSD" + + :depends-on (cram-process-modules + cram-designators + cram-prolog + + cram-tf + cram-common-designators + + cram-donbot-low-level + + cram-bullet-reasoning-belief-state ; for WORLD-STATE-DETECTING + cram-robosherlock ; for WITH-REAL-ROBOT + cram-giskard) + :components + ((:module "src" + :components + ((:file "package") + (:file "definitions" :depends-on ("package")) + (:file "interface" :depends-on ("package" "definitions")))))) diff --git a/cram_boxy/cram_boxy_designators/package.xml b/cram_donbot/cram_donbot_process_modules/package.xml similarity index 57% rename from cram_boxy/cram_boxy_designators/package.xml rename to cram_donbot/cram_donbot_process_modules/package.xml index daf4cc8e60..597f51d4ea 100644 --- a/cram_boxy/cram_boxy_designators/package.xml +++ b/cram_donbot/cram_donbot_process_modules/package.xml @@ -1,8 +1,8 @@ - cram_boxy_designators + cram_donbot_process_modules 0.7.0 - Definitions of supported designators and their resolving mechanisms for Boxy + CRAM Middle-layer code for Donbot Gayane Kazhoyan Gayane Kazhoyan @@ -10,8 +10,12 @@ catkin + cram_process_modules cram_designators cram_prolog - cram_designator_specification cram_tf + cram_common_designators + cram_donbot_low_level + cram_robosherlock + cram_giskard diff --git a/cram_donbot/cram_donbot_process_modules/src/definitions.lisp b/cram_donbot/cram_donbot_process_modules/src/definitions.lisp new file mode 100644 index 0000000000..0a4c8f5bf6 --- /dev/null +++ b/cram_donbot/cram_donbot_process_modules/src/definitions.lisp @@ -0,0 +1,43 @@ +;;; +;;; Copyright (c) 2019, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :donbot-pm) + +;;;;;;;;;;;;;;;;;;;; GRIPPERS ;;;;;;;;;;;;;;;;;;;;;;;; + +(cpm:def-process-module grippers-pm (motion-designator) + (destructuring-bind (command action-type-or-position which-gripper + &optional effort-but-actually-slippage-param) + (desig:reference motion-designator) + (ecase command + (cram-common-designators:move-gripper-joint + (donbot-ll:call-gripper-action + :action-type-or-position action-type-or-position + :left-or-right which-gripper + :effort-but-actually-slippage-parameter effort-but-actually-slippage-param))))) diff --git a/cram_donbot/cram_donbot_process_modules/src/interface.lisp b/cram_donbot/cram_donbot_process_modules/src/interface.lisp new file mode 100644 index 0000000000..6225399e2f --- /dev/null +++ b/cram_donbot/cram_donbot_process_modules/src/interface.lisp @@ -0,0 +1,62 @@ +;;; +;;; Copyright (c) 2019, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of Willow Garage, Inc. nor the names of its +;;; contributors may be used to endorse or promote products derived from +;;; this software without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :donbot-pm) + +(def-fact-group donbot-matching-pms (cpm:matching-process-module + cpm:available-process-module) + + (<- (cpm:matching-process-module ?motion-designator grippers-pm) + (or (desig:desig-prop ?motion-designator (:type :gripping)) + (desig:desig-prop ?motion-designator (:type :opening-gripper)) + (desig:desig-prop ?motion-designator (:type :closing-gripper)) + (desig:desig-prop ?motion-designator (:type :moving-gripper-joint)))) + + (<- (cpm:matching-process-module ?motion-designator giskard:giskard-pm) + (or (desig:desig-prop ?motion-designator (:type :moving-tcp)) + (desig:desig-prop ?motion-designator (:type :moving-arm-joints)) + (desig:desig-prop ?motion-designator (:type :pulling)) + (desig:desig-prop ?motion-designator (:type :pushing)) + (desig:desig-prop ?motion-designator (:type :going)) + (desig:desig-prop ?motion-designator (:type :moving-torso)) + (desig:desig-prop ?motion-designator (:type :looking)))) + + (<- (cpm:available-process-module ?pm) + (member ?pm (grippers-pm giskard:giskard-pm)) + (not (cpm:projection-running ?_))) + + (<- (cpm:available-process-module btr-belief:world-state-detecting-pm))) + + +(defmacro with-real-robot (&body body) + `(cram-process-modules:with-process-modules-running + (donbot-pm:grippers-pm + rs:robosherlock-perception-pm giskard:giskard-pm + btr-belief:world-state-detecting-pm) + (cpl-impl::named-top-level (:name :top-level) + ,@body))) diff --git a/cram_boxy/cram_boxy_designators/src/package.lisp b/cram_donbot/cram_donbot_process_modules/src/package.lisp similarity index 87% rename from cram_boxy/cram_boxy_designators/src/package.lisp rename to cram_donbot/cram_donbot_process_modules/src/package.lisp index a888a2624e..00e8427c30 100644 --- a/cram_boxy/cram_boxy_designators/src/package.lisp +++ b/cram_donbot/cram_donbot_process_modules/src/package.lisp @@ -1,5 +1,5 @@ ;;; -;;; Copyright (c) 2017, Gayane Kazhoyan +;;; Copyright (c) 2019, Gayane Kazhoyan ;;; All rights reserved. ;;; ;;; Redistribution and use in source and binary forms, with or without @@ -29,9 +29,11 @@ (in-package :cl-user) -(defpackage cram-boxy-designators - (:nicknames #:boxy-desig) - (:use #:common-lisp #:cram-prolog #:cram-designator-specification) +(defpackage cram-donbot-process-modules + (:nicknames #:donbot-pm) + (:use #:common-lisp #:cram-prolog) (:export - ;; motions - #:move-tcp-wiggle)) + ;; definitions + #:grippers-pm + ;; interface + #:with-real-robot)) diff --git a/cram_external_interfaces/cram_giskard/cram-giskard.asd b/cram_external_interfaces/cram_giskard/cram-giskard.asd index 7c3ce5b3b1..c7254bd770 100644 --- a/cram_external_interfaces/cram_giskard/cram-giskard.asd +++ b/cram_external_interfaces/cram_giskard/cram-giskard.asd @@ -33,31 +33,62 @@ :depends-on (roslisp roslisp-utilities + cl-transforms cl-transforms-stamped - cram-tf - cram-common-failures + cram-designators cram-process-modules cram-prolog - cram-common-designators cram-occasions-events ; for updating giskard collision scene on events + + cram-simple-actionlib-client + cram-tf + cram-robot-interfaces + cram-common-failures + cram-common-designators cram-plan-occasions-events + cram-bullet-reasoning ; also for updating giskard collision scene cram-bullet-reasoning-belief-state ; for *kitchen-parameter* + cram-joint-states ; for joint-interface to send current joint state - cram-simple-actionlib-client + giskard_msgs-msg giskard_msgs-srv) :components ((:module "src" :components ((:file "package") - (:file "collision-scene" :depends-on ("package")) (:file "action-client" :depends-on ("package")) - (:file "cartesian-interface" :depends-on ("package" "action-client")) - (:file "joint-interface" :depends-on ("package" "action-client")) - (:file "base-goals" :depends-on ("package" "action-client" "joint-interface")) - (:file "torso-goals" :depends-on ("package" "action-client")) - (:file "process-module" :depends-on ("package" "cartesian-interface" "joint-interface" - "base-goals" "torso-goals")))))) + (:file "hash-table-conversions" :depends-on ("package")) + (:file "making-goal-messages" :depends-on ("package" "hash-table-conversions")) + (:file "arm-goals" :depends-on ("package" + "action-client" + "making-goal-messages")) + (:file "base-goals" :depends-on ("package" + "action-client" + "making-goal-messages")) + (:file "torso-goals" :depends-on ("package" + "making-goal-messages" + "action-client")) + (:file "gripper-goals" :depends-on ("package" + "making-goal-messages" + "action-client")) + (:file "neck-goals" :depends-on ("package" + "making-goal-messages" + "action-client")) + (:file "environment-manipulation-goals" :depends-on ("package" + "making-goal-messages" + "action-client")) + (:file "misc-goals" :depends-on ("package" + "making-goal-messages" + "action-client")) + (:file "collision-scene" :depends-on ("package")) + (:file "process-module" :depends-on ("package" + "arm-goals" + "base-goals" + "torso-goals" + "gripper-goals" + "neck-goals" + "environment-manipulation-goals")))))) diff --git a/cram_external_interfaces/cram_giskard/package.xml b/cram_external_interfaces/cram_giskard/package.xml index acd44d61f5..c4e50aa282 100644 --- a/cram_external_interfaces/cram_giskard/package.xml +++ b/cram_external_interfaces/cram_giskard/package.xml @@ -20,6 +20,7 @@ cram_process_modules cram_prolog cram_common_designators + cram_robot_interfaces cram_occasions_events cram_plan_occasions_events cram_bullet_reasoning diff --git a/cram_external_interfaces/cram_giskard/src/action-client.lisp b/cram_external_interfaces/cram_giskard/src/action-client.lisp index 9209f74121..7dd431c356 100644 --- a/cram_external_interfaces/cram_giskard/src/action-client.lisp +++ b/cram_external_interfaces/cram_giskard/src/action-client.lisp @@ -33,6 +33,53 @@ (actionlib-client:make-simple-action-client 'giskard-action "giskardpy/command" "giskard_msgs/MoveAction" - 60)) + 120)) (roslisp-utilities:register-ros-init-function make-giskard-action-client) + + +(defun call-action (&key action-goal action-timeout check-goal-function) + (declare (type giskard_msgs-msg:movegoal action-goal) + (type (or number null) action-timeout) + (type (or function null) check-goal-function)) + + ;; check if the goal has already been reached + (when (and check-goal-function + (not (funcall check-goal-function))) + (roslisp:ros-warn (giskard action-client) + "Giskard action goal already reached.") + (return-from call-action)) + + ;; call the actionlib action + (multiple-value-bind (result status) + (actionlib-client:call-simple-action-client + 'giskard-action + :action-goal action-goal + :action-timeout action-timeout) + + ;; print a debug statement if the status is unexpected + (case status + (:preempted + (roslisp:ros-warn (giskard action-client) + "Giskard action preempted.~%Result: ~a" result)) + (:timeout + (roslisp:ros-warn (giskard action-client) + "Giskard action timed out.")) + (:aborted + (roslisp:ros-warn (giskard cartesian) + "Giskard action aborted.~%Result: ~a" result))) + + ;; check if the goal was reached, if not, throw a failure + (when check-goal-function + (let ((failure (funcall check-goal-function))) + (when failure + (roslisp:ros-warn (giskard action-client) + "Giskard action goal was not reached.") + (cpl:fail failure)))) + + ;; this is only used by HPN: + ;; return the joint state, which is our observation + ;; (joints:full-joint-states-as-hash-table) + + ;; return the result and status + (values result status))) diff --git a/cram_external_interfaces/cram_giskard/src/arm-goals.lisp b/cram_external_interfaces/cram_giskard/src/arm-goals.lisp new file mode 100644 index 0000000000..cabb227684 --- /dev/null +++ b/cram_external_interfaces/cram_giskard/src/arm-goals.lisp @@ -0,0 +1,270 @@ +;;; +;;; Copyright (c) 2016, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :giskard) + +(defparameter *arm-convergence-delta-xy* 0.03 ;; 0.005 + "in meters") +(defparameter *arm-convergence-delta-theta* 0.5 ;; 0.1 + "in radiants, about 30 degrees") +(defparameter *arm-convergence-delta-joint* 0.17 + "in radiants, about 10 degrees") + +(defun make-arm-cartesian-action-goal (left-pose right-pose + pose-base-frame collision-mode + &key + collision-object-b + collision-object-b-link + collision-object-a + prefer-base + align-planes-left align-planes-right + unmovable-joints) + (declare (type (or null cl-transforms-stamped:pose-stamped) left-pose right-pose) + (type (or null string) pose-base-frame) + (type boolean prefer-base align-planes-left align-planes-right) + (type (or null list) unmovable-joints)) + (let ((arms (append (when left-pose '(:left)) + (when right-pose '(:right))))) + (make-giskard-goal + :constraints (list + (make-avoid-joint-limits-constraint) + (when prefer-base (make-prefer-base-constraint)) + ;; (when align-planes-left + ;; (make-align-planes-constraint + ;; pose-base-frame + ;; "refills_finger" + ;; (cl-transforms-stamped:make-vector-stamped + ;; cram-tf:*robot-base-frame* 0.0 + ;; (cl-transforms:make-3d-vector 0 0 1)) + ;; (cl-transforms-stamped:make-vector-stamped + ;; cram-tf:*robot-base-frame* 0.0 + ;; (cl-transforms:make-3d-vector 0 0 1)))) + ;; (when align-planes-right + ;; (make-align-planes-constraint + ;; pose-base-frame + ;; "refills_finger" + ;; (cl-transforms-stamped:make-vector-stamped + ;; cram-tf:*robot-base-frame* 0.0 + ;; (cl-transforms:make-3d-vector 0 0 1)) + ;; (cl-transforms-stamped:make-vector-stamped + ;; cram-tf:*robot-base-frame* 0.0 + ;; (cl-transforms:make-3d-vector 0 0 1)))) + (when unmovable-joints (make-unmovable-joints-constraint + unmovable-joints))) + :cartesian-constraints (list (when left-pose + (make-simple-cartesian-constraint + pose-base-frame + cram-tf:*robot-left-tool-frame* + left-pose)) + (when right-pose + (make-simple-cartesian-constraint + pose-base-frame + cram-tf:*robot-right-tool-frame* + right-pose))) + :collisions (ecase collision-mode + (:avoid-all (make-avoid-all-collision 0.1)) + (:allow-all (make-allow-all-collision)) + (:allow-hand (list (make-avoid-all-collision 0.05) + (make-allow-hand-collision + arms collision-object-b + collision-object-b-link) + (make-allow-hand-collision + arms (rob-int:get-environment-name)))) + (:allow-arm (list (make-avoid-all-collision 0.05) + (make-allow-arm-collision + arms collision-object-b + collision-object-b-link) + (make-allow-arm-collision + arms (rob-int:get-environment-name)))) + (:allow-attached (list (make-avoid-all-collision 0.02) + (make-allow-attached-collision + collision-object-a + collision-object-b-link))))))) + +(defun make-arm-joint-action-goal (joint-state-left joint-state-right + align-planes-left align-planes-right) + (declare (type list joint-state-left joint-state-right) + (type boolean align-planes-left align-planes-right)) + (make-giskard-goal + :constraints (list + ;; (make-avoid-joint-limits-constraint) + ;; (when align-planes-left + ;; (make-align-planes-constraint + ;; cram-tf:*odom-frame* + ;; "refills_finger" + ;; (cl-transforms-stamped:make-vector-stamped + ;; cram-tf:*robot-base-frame* 0.0 + ;; (cl-transforms:make-3d-vector 0 0 1)) + ;; (cl-transforms-stamped:make-vector-stamped + ;; cram-tf:*robot-base-frame* 0.0 + ;; (cl-transforms:make-3d-vector 0 0 1)))) + ;; (when align-planes-right + ;; (make-align-planes-constraint + ;; cram-tf:*odom-frame* + ;; "refills_finger" + ;; (cl-transforms-stamped:make-vector-stamped + ;; cram-tf:*robot-base-frame* 0.0 + ;; (cl-transforms:make-3d-vector 0 0 1)) + ;; (cl-transforms-stamped:make-vector-stamped + ;; cram-tf:*robot-base-frame* 0.0 + ;; (cl-transforms:make-3d-vector 0 0 1)))) + ) + :joint-constraints (list (make-simple-joint-constraint joint-state-left) + (make-simple-joint-constraint joint-state-right)) + :collisions (make-avoid-all-collision))) + + + +(defun ensure-arm-cartesian-goal-input (frame goal-pose) + (when goal-pose + (cram-tf:ensure-pose-in-frame goal-pose frame))) + +(defun ensure-arm-joint-goal-input (goal-configuration arm) + (if (and (listp goal-configuration) + (or (= (length goal-configuration) 7) + (= (length goal-configuration) 6))) + (get-arm-joint-names-and-positions-list arm goal-configuration) + (progn (roslisp:ros-warn (giskard joint) + "Joint goal ~a was not a list of 7 (or 6). Ignoring." + goal-configuration) + (get-arm-joint-names-and-positions-list arm)))) + + + +(defun ensure-arm-cartesian-goal-reached (goal-pose goal-frame) + (when goal-pose + (unless (cram-tf:tf-frame-converged + goal-frame goal-pose + *arm-convergence-delta-xy* *arm-convergence-delta-theta*) + (make-instance 'common-fail:manipulation-goal-not-reached + :description (format nil "Giskard did not converge to goal:~%~ + ~a should have been at ~a ~ + with delta-xy of ~a and delta-angle of ~a." + goal-frame goal-pose + *arm-convergence-delta-xy* + *arm-convergence-delta-theta*))))) + +(defun ensure-arm-joint-goal-reached (goal-configuration arm) + (when goal-configuration + (let ((current-angles + (cram-tf:normalize-joint-angles + (second (get-arm-joint-names-and-positions-list arm)))) + (goal-angles + (cram-tf:normalize-joint-angles + (mapcar #'second goal-configuration)))) + (unless (cram-tf:values-converged + current-angles goal-angles *arm-convergence-delta-joint*) + (make-instance 'common-fail:manipulation-goal-not-reached + :description (format nil "Giskard did not converge to goal:~%~a (~a)~%~ + should have been at~%~a~%with delta-joint of ~a." + arm current-angles goal-angles + *arm-convergence-delta-joint*)))))) + + + + +(defun call-arm-cartesian-action (&key + action-timeout + goal-pose-left goal-pose-right + pose-base-frame + collision-mode + collision-object-b collision-object-b-link + collision-object-a + move-base prefer-base + align-planes-left align-planes-right + unmovable-joints) + (declare (type (or number null) action-timeout) + (type (or cl-transforms-stamped:pose-stamped null) + goal-pose-left goal-pose-right) + (type (or string null) pose-base-frame) + (type boolean move-base prefer-base align-planes-left align-planes-right) + (type (or list null) unmovable-joints)) + + (unless (or goal-pose-left goal-pose-right) + (roslisp:ros-info (giskard cart) "Got an empty goal...") + ;; return NIL as observation if the goal is empty + (return-from call-arm-cartesian-action)) + + (when prefer-base + (setf move-base T)) + (if (and move-base (not pose-base-frame)) + (setf pose-base-frame cram-tf:*odom-frame*) + (setf pose-base-frame cram-tf:*robot-base-frame*)) + (setf goal-pose-left + (ensure-arm-cartesian-goal-input pose-base-frame goal-pose-left)) + (setf goal-pose-right + (ensure-arm-cartesian-goal-input pose-base-frame goal-pose-right)) + + (cram-tf:visualize-marker + (list goal-pose-left goal-pose-right) + :r-g-b-list '(1 0 1)) + + (call-action + :action-goal (make-arm-cartesian-action-goal + goal-pose-left goal-pose-right + pose-base-frame + collision-mode + :collision-object-b collision-object-b + :collision-object-b-link collision-object-b-link + :collision-object-a collision-object-a + :prefer-base prefer-base + :align-planes-left align-planes-left + :align-planes-right align-planes-right + :unmovable-joints unmovable-joints) + :action-timeout action-timeout + :check-goal-function (lambda () + (or (ensure-arm-cartesian-goal-reached + goal-pose-left cram-tf:*robot-left-tool-frame*) + (ensure-arm-cartesian-goal-reached + goal-pose-right cram-tf:*robot-right-tool-frame*))))) + + + +(defun call-arm-joint-action (&key + action-timeout + goal-configuration-left goal-configuration-right + align-planes-left align-planes-right) + (declare (type (or list null) goal-configuration-left goal-configuration-right) + (type (or number null) action-timeout)) + + (let ((joint-state-left + (ensure-arm-joint-goal-input goal-configuration-left :left)) + (joint-state-right + (ensure-arm-joint-goal-input goal-configuration-right :right))) + + (call-action + :action-goal (make-arm-joint-action-goal + joint-state-left joint-state-right + align-planes-left align-planes-right) + :action-timeout action-timeout + :check-goal-function (lambda () + (or (ensure-arm-joint-goal-reached + goal-configuration-left :left) + (ensure-arm-joint-goal-reached + goal-configuration-right :right)))))) diff --git a/cram_external_interfaces/cram_giskard/src/base-goals.lisp b/cram_external_interfaces/cram_giskard/src/base-goals.lisp index c69d776490..f2f2591bae 100644 --- a/cram_external_interfaces/cram_giskard/src/base-goals.lisp +++ b/cram_external_interfaces/cram_giskard/src/base-goals.lisp @@ -29,202 +29,42 @@ (in-package :giskard) -(defparameter *xy-goal-tolerance* 0.05 "in meters") -(defparameter *yaw-goal-tolerance* 0.1 "in radiants, about 6 degrees.") +(defparameter *base-convergence-delta-xy* 0.05 "in meters") +(defparameter *base-convergence-delta-theta* 0.1 "in radiants, about 6 degrees.") (defun make-giskard-base-action-goal (pose) (declare (type cl-transforms-stamped:pose-stamped pose)) - (roslisp:make-message - 'giskard_msgs-msg:MoveGoal - :type (roslisp:symbol-code 'giskard_msgs-msg:MoveGoal ;; :plan_only - :plan_and_execute - ) - :cmd_seq (vector - (roslisp:make-message - 'giskard_msgs-msg:movecmd - ;; THIS STUFF HAS A STATE - ;; RESET THE STATE EXPLICITLY IF YOU WANT A NON CART MOVEMENT AFTER THIS - :constraints - (vector (roslisp:make-message - 'giskard_msgs-msg:constraint - :type - "UpdateGodMap" - :parameter_value_pair - (let ((stream (make-string-output-stream))) - (yason:encode - (alexandria:alist-hash-table - `(("updates" - . - ,(alexandria:alist-hash-table - `(("rosparam" - . - ,(alexandria:alist-hash-table - `(("joint_weights" - . - ,(alexandria:alist-hash-table - `(("odom_x_joint" . 0.0001) - ("odom_y_joint" . 0.0001) - ("odom_z_joint" . 0.0001)))))))) - :test #'equal)))) - stream) - (get-output-stream-string stream)))) - :cartesian_constraints - (vector (roslisp:make-message - 'giskard_msgs-msg:cartesianconstraint - :type (roslisp:symbol-code - 'giskard_msgs-msg:cartesianconstraint - :translation_3d) - :root_link cram-tf:*odom-frame* - :tip_link cram-tf:*robot-base-frame* - :goal (cl-transforms-stamped:to-msg pose)) - (roslisp:make-message - 'giskard_msgs-msg:cartesianconstraint - :type (roslisp:symbol-code - 'giskard_msgs-msg:cartesianconstraint - :rotation_3d) - :root_link cram-tf:*odom-frame* - :tip_link cram-tf:*robot-base-frame* - :goal (cl-transforms-stamped:to-msg pose))) - :joint_constraints - (let ((left-names-and-positions - (get-arm-joint-names-and-positions-list :left)) - (right-names-and-positions - (get-arm-joint-names-and-positions-list :right))) - (vector (roslisp:make-message - 'giskard_msgs-msg:jointconstraint - :type (roslisp:symbol-code - 'giskard_msgs-msg:jointconstraint - :joint) - :goal_state (roslisp:make-message - 'sensor_msgs-msg:jointstate - :name (apply #'vector - (append (first left-names-and-positions) - (first right-names-and-positions))) - :position (apply #'vector - (append (second left-names-and-positions) - (second right-names-and-positions))))))) - :collisions - (vector (roslisp:make-message - 'giskard_msgs-msg:collisionentry - :type (roslisp:symbol-code - 'giskard_msgs-msg:collisionentry - :avoid_all_collisions) - :min_dist 0.1)))))) + (make-giskard-goal + :constraints (make-cartesian-constraint + cram-tf:*odom-frame* cram-tf:*robot-base-frame* pose + :avoid-collisions-much t) + :joint-constraints (make-current-joint-state-constraint '(:left :right)) + :collisions (make-avoid-all-collision))) -(defun ensure-giskard-base-input-parameters (pose) +(defun ensure-base-goal-input (pose) (cram-tf:ensure-pose-in-frame pose cram-tf:*fixed-frame*)) -(defun ensure-giskard-base-goal-reached (result status goal - convergence-delta-xy convergence-delta-theta) - (when (eql status :preempted) - (roslisp:ros-warn (low-level giskard) "Giskard action preempted with result ~a" result) - (return-from ensure-giskard-base-goal-reached)) - (when (eql status :timeout) - (roslisp:ros-warn (pr2-ll giskard-cart) "Giskard action timed out.")) - (when (eql status :aborted) - (roslisp:ros-warn (pr2-ll giskard-cart) "Giskard action aborted! With result ~a" result) - ;; (cpl:fail 'common-fail:manipulation-goal-not-reached - ;; :description "Giskard did not converge to goal because of collision") - ) - (unless (cram-tf:tf-frame-converged cram-tf:*robot-base-frame* goal - convergence-delta-xy convergence-delta-theta) - (cpl:fail 'common-fail:navigation-goal-not-reached - :description (format nil "Giskard did not converge to goal: -~a should have been at ~a with delta-xy of ~a and delta-angle of ~a." - cram-tf:*robot-base-frame* goal - convergence-delta-xy convergence-delta-theta)))) +(defun ensure-base-goal-reached (goal-pose) + (unless (cram-tf:tf-frame-converged + cram-tf:*robot-base-frame* goal-pose + *base-convergence-delta-xy* *base-convergence-delta-theta*) + (make-instance 'common-fail:navigation-goal-not-reached + :description (format nil "Giskard did not converge to goal:~%~ + ~a should have been at ~a ~ + with delta-xy of ~a and delta-angle of ~a." + cram-tf:*robot-base-frame* goal-pose + *base-convergence-delta-xy* + *base-convergence-delta-theta*)))) -(defun call-giskard-base-action (&key - goal-pose action-timeout - (convergence-delta-xy *xy-goal-tolerance*) - (convergence-delta-theta *yaw-goal-tolerance*)) +(defun call-base-action (&key action-timeout goal-pose) (declare (type cl-transforms-stamped:pose-stamped goal-pose) - (type (or null number) action-timeout convergence-delta-xy convergence-delta-theta)) - (let ((goal-pose - (ensure-giskard-base-input-parameters goal-pose))) - (cram-tf:visualize-marker goal-pose :r-g-b-list '(0 1 0)) - (multiple-value-bind (result status) - (let ((goal (make-giskard-base-action-goal goal-pose))) - (actionlib-client:call-simple-action-client - 'giskard-action - :action-goal goal - :action-timeout action-timeout)) - (ensure-giskard-base-goal-reached result status goal-pose - convergence-delta-xy convergence-delta-theta) - (joints:full-joint-states-as-hash-table)))) + (type (or null number) action-timeout)) + (setf goal-pose (ensure-base-goal-input goal-pose)) + (cram-tf:visualize-marker goal-pose :r-g-b-list '(0 1 0)) - - - - - - -;; header: -;; seq: 17 -;; stamp: -;; secs: 1560439219 -;; nsecs: 637718915 -;; frame_id: '' -;; goal_id: -;; stamp: -;; secs: 1560439219 -;; nsecs: 637681961 -;; id: "/giskard_interactive_marker-17-1560439219.638" -;; goal: -;; type: 1 -;; cmd_seq: -;; - -;; constraints: [] -;; joint_constraints: [] -;; cartesian_constraints: -;; - -;; type: "CartesianPosition" -;; root_link: "odom" -;; tip_link: "base_footprint" -;; goal: -;; header: -;; seq: 0 -;; stamp: -;; secs: 0 -;; nsecs: 0 -;; frame_id: "base_footprint" -;; pose: -;; position: -;; x: 2.50292941928e-08 -;; y: 0.0 -;; z: 0.209769845009 -;; orientation: -;; x: 0.0 -;; y: 0.0 -;; z: 0.0 -;; w: 1.0 -;; - -;; type: "CartesianOrientationSlerp" -;; root_link: "odom" -;; tip_link: "base_footprint" -;; goal: -;; header: -;; seq: 0 -;; stamp: -;; secs: 0 -;; nsecs: 0 -;; frame_id: "base_footprint" -;; pose: -;; position: -;; x: 2.50292941928e-08 -;; y: 0.0 -;; z: 0.209769845009 -;; orientation: -;; x: 0.0 -;; y: 0.0 -;; z: 0.0 -;; w: 1.0 -;; collisions: -;; - -;; type: 1 -;; min_dist: 0.0 -;; robot_links: [''] -;; body_b: "pr2" -;; link_bs: [''] + (call-action + :action-goal (make-giskard-base-action-goal goal-pose) + :action-timeout action-timeout + :check-goal-function (lambda () (ensure-base-goal-reached goal-pose)))) diff --git a/cram_external_interfaces/cram_giskard/src/cartesian-interface.lisp b/cram_external_interfaces/cram_giskard/src/cartesian-interface.lisp deleted file mode 100644 index 9d8b0ab18d..0000000000 --- a/cram_external_interfaces/cram_giskard/src/cartesian-interface.lisp +++ /dev/null @@ -1,393 +0,0 @@ -;;; -;;; Copyright (c) 2016, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Institute for Artificial Intelligence/ -;;; Universitaet Bremen nor the names of its contributors may be used to -;;; endorse or promote products derived from this software without -;;; specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :giskard) - -(defparameter *giskard-convergence-delta-xy* 0.1 ;; 0.005 - "in meters") -(defparameter *giskard-convergence-delta-theta* 0.5 ;; 0.1 - "in radiants, about 6 degrees") - -(defun make-giskard-cartesian-action-goal (left-pose right-pose - pose-base-frame left-tool-frame right-tool-frame - collision-mode - &key - collision-object-b collision-object-b-link - collision-object-a - move-the-ass) - (declare (type (or null cl-transforms-stamped:pose-stamped) left-pose right-pose) - (type string pose-base-frame left-tool-frame right-tool-frame)) - (roslisp:make-message - 'giskard_msgs-msg:MoveGoal - :type (roslisp:symbol-code 'giskard_msgs-msg:MoveGoal ;; :plan_only - :plan_and_execute - ) - :cmd_seq (vector - (roslisp:make-message - 'giskard_msgs-msg:movecmd - ;; THIS STUFF HAS A STATE - ;; RESET THE STATE EXPLICITLY IF YOU WANT A NON CART MOVEMENT AFTER THIS - :constraints - (vector (roslisp:make-message - 'giskard_msgs-msg:constraint - :type - "UpdateGodMap" - :parameter_value_pair - (let ((stream (make-string-output-stream))) - (yason:encode - (alexandria:alist-hash-table - `(("updates" - . - ,(alexandria:alist-hash-table - `(("rosparam" - . - ,(alexandria:alist-hash-table - `(("joint_weights" - . - ,(alexandria:alist-hash-table - `(("odom_x_joint" . ,(if move-the-ass 0.0001 1.0)) - ("odom_y_joint" . ,(if move-the-ass 0.0001 1.0)) - ("odom_z_joint" . ,(if move-the-ass 0.0001 1.0))))))))) - :test #'equal)))) - stream) - (get-output-stream-string stream)))) - :cartesian_constraints - (map 'vector #'identity - (remove nil - (list - (when left-pose - (roslisp:make-message - 'giskard_msgs-msg:cartesianconstraint - :type (roslisp:symbol-code - 'giskard_msgs-msg:cartesianconstraint - :translation_3d) - :root_link pose-base-frame - :tip_link left-tool-frame - :goal (cl-transforms-stamped:to-msg left-pose))) - (when left-pose - (roslisp:make-message - 'giskard_msgs-msg:cartesianconstraint - :type (roslisp:symbol-code - 'giskard_msgs-msg:cartesianconstraint - :rotation_3d) - :root_link pose-base-frame - :tip_link left-tool-frame - :goal (cl-transforms-stamped:to-msg left-pose))) - (when right-pose - (roslisp:make-message - 'giskard_msgs-msg:cartesianconstraint - :type (roslisp:symbol-code - 'giskard_msgs-msg:cartesianconstraint - :translation_3d) - :root_link pose-base-frame - :tip_link right-tool-frame - :goal (cl-transforms-stamped:to-msg right-pose))) - (when right-pose - (roslisp:make-message - 'giskard_msgs-msg:cartesianconstraint - :type (roslisp:symbol-code - 'giskard_msgs-msg:cartesianconstraint - :rotation_3d) - :root_link pose-base-frame - :tip_link right-tool-frame - :goal (cl-transforms-stamped:to-msg right-pose)))))) - :collisions - (case collision-mode - (:allow-all - (vector (roslisp:make-message - 'giskard_msgs-msg:collisionentry - :type (roslisp:symbol-code - 'giskard_msgs-msg:collisionentry - :allow_all_collisions)))) - (:avoid-all - (vector (roslisp:make-message - 'giskard_msgs-msg:collisionentry - :type (roslisp:symbol-code - 'giskard_msgs-msg:collisionentry - :avoid_all_collisions) - :min_dist 0.1))) - (:allow-hand - (vector (roslisp:make-message - 'giskard_msgs-msg:collisionentry - :type (roslisp:symbol-code - 'giskard_msgs-msg:collisionentry - :avoid_all_collisions) - :min_dist 0.05) - (roslisp:make-message - 'giskard_msgs-msg:collisionentry - :type (roslisp:symbol-code - 'giskard_msgs-msg:collisionentry - :allow_collision) - :robot_links (apply - #'vector - (append - (when left-pose - (cut:var-value - '?hand-links - (car (prolog:prolog - `(and (rob-int:robot ?robot) - (rob-int:hand-links ?robot :left - ?hand-links)))))) - (when right-pose - (cut:var-value - '?hand-links - (car (prolog:prolog - `(and (rob-int:robot ?robot) - (rob-int:hand-links ?robot :right - ?hand-links)))))))) - :body_b (if collision-object-b - (roslisp-utilities:rosify-underscores-lisp-name - collision-object-b) - (roslisp:symbol-code - 'giskard_msgs-msg:collisionentry - :all)) - :link_bs (vector (roslisp:symbol-code - 'giskard_msgs-msg:collisionentry - :all)) - ;; (if collision-object-b-link - ;; (vector (roslisp-utilities:rosify-underscores-lisp-name - ;; collision-object-b-link)) - ;; (vector (roslisp:symbol-code - ;; 'giskard_msgs-msg:collisionentry - ;; :all))) - ) - (roslisp:make-message - 'giskard_msgs-msg:collisionentry - :type (roslisp:symbol-code - 'giskard_msgs-msg:collisionentry - :allow_collision) - :robot_links (apply - #'vector - (append - (when left-pose - (cut:var-value - '?hand-links - (car (prolog:prolog - `(and (rob-int:robot ?robot) - (rob-int:hand-links ?robot :left - ?hand-links)))))) - (when right-pose - (cut:var-value - '?hand-links - (car (prolog:prolog - `(and (rob-int:robot ?robot) - (rob-int:hand-links ?robot :right - ?hand-links)))))))) - :body_b (roslisp-utilities:rosify-underscores-lisp-name - :kitchen) - :link_bs (vector (roslisp:symbol-code - 'giskard_msgs-msg:collisionentry - :all))))) - (:allow-attached - (vector - (roslisp:make-message - 'giskard_msgs-msg:collisionentry - :type (roslisp:symbol-code - 'giskard_msgs-msg:collisionentry - :avoid_all_collisions) - :min_dist 0.02) - (roslisp:make-message - 'giskard_msgs-msg:collisionentry - :type (roslisp:symbol-code - 'giskard_msgs-msg:collisionentry - :allow_collision) - :robot_links (if collision-object-a - (vector (roslisp-utilities:rosify-underscores-lisp-name - collision-object-a)) - (vector (roslisp:symbol-code - 'giskard_msgs-msg:collisionentry - :all))) ; collision-object-a = attached-obj - :body_b "kitchen";; (roslisp-utilities:rosify-underscores-lisp-name - ;; collision-object-b-link) - :link_bs (if collision-object-b-link - (vector (roslisp-utilities:rosify-underscores-lisp-name - collision-object-b-link)) - (vector (roslisp:symbol-code - 'giskard_msgs-msg:collisionentry - :all)))))) - (t - (vector (roslisp:make-message - 'giskard_msgs-msg:collisionentry - :type (roslisp:symbol-code - 'giskard_msgs-msg:collisionentry - :avoid_all_collisions) - :min_dist 0.1)))))))) - -(defun ensure-giskard-cartesian-input-parameters (frame left-pose right-pose) - (values (when left-pose - (cram-tf:ensure-pose-in-frame left-pose frame)) - (when right-pose - (cram-tf:ensure-pose-in-frame right-pose frame)))) - -(defun ensure-giskard-cartesian-goal-reached (result status goal-position-left goal-position-right - goal-frame-left goal-frame-right - convergence-delta-xy convergence-delta-theta) - (when (eql status :preempted) - (roslisp:ros-warn (low-level giskard) "Giskard action preempted with result ~a" result) - (return-from ensure-giskard-cartesian-goal-reached)) - (when (eql status :timeout) - (roslisp:ros-warn (pr2-ll giskard-cart) "Giskard action timed out.")) - (when (eql status :aborted) - (roslisp:ros-warn (pr2-ll giskard-cart) "Giskard action aborted! With result ~a" result) - ;; (cpl:fail 'common-fail:manipulation-goal-not-reached - ;; :description "Giskard did not converge to goal because of collision") - ) - (when goal-position-left - (unless (cram-tf:tf-frame-converged goal-frame-left goal-position-left - convergence-delta-xy convergence-delta-theta) - (cpl:fail 'common-fail:manipulation-goal-not-reached - :description (format nil "Giskard did not converge to goal: -~a should have been at ~a with delta-xy of ~a and delta-angle of ~a." - goal-frame-left goal-position-left - convergence-delta-xy convergence-delta-theta)))) - (when goal-position-right - (unless (cram-tf:tf-frame-converged goal-frame-right goal-position-right - convergence-delta-xy convergence-delta-theta) - (cpl:fail 'common-fail:manipulation-goal-not-reached - :description (format nil "Giskard did not converge to goal: -~a should have been at ~a with delta-xy of ~a and delta-angle of ~a." - goal-frame-right goal-position-right - convergence-delta-xy convergence-delta-theta))))) - -(defun call-giskard-cartesian-action (&key - goal-pose-left goal-pose-right action-timeout - collision-mode collision-object-b collision-object-b-link - collision-object-a - move-the-ass - (pose-base-frame ;; cram-tf:*robot-base-frame* - cram-tf:*odom-frame*) - (left-tool-frame cram-tf:*robot-left-tool-frame*) - (right-tool-frame cram-tf:*robot-right-tool-frame*) - (convergence-delta-xy *giskard-convergence-delta-xy*) - (convergence-delta-theta *giskard-convergence-delta-theta*)) - (declare (type (or null cl-transforms-stamped:pose-stamped) goal-pose-left goal-pose-right) - (type (or null number) action-timeout convergence-delta-xy convergence-delta-theta) - (type (or null string) pose-base-frame left-tool-frame right-tool-frame)) - (if (or goal-pose-left goal-pose-right) - (multiple-value-bind (goal-pose-left goal-pose-right) - (ensure-giskard-cartesian-input-parameters pose-base-frame goal-pose-left goal-pose-right) - (cram-tf:visualize-marker (list goal-pose-left goal-pose-right) :r-g-b-list '(1 0 1)) - (multiple-value-bind (result status) - (let ((goal (make-giskard-cartesian-action-goal - goal-pose-left goal-pose-right - pose-base-frame left-tool-frame right-tool-frame - collision-mode - :collision-object-b collision-object-b - :collision-object-b-link collision-object-b-link - :collision-object-a collision-object-a - :move-the-ass move-the-ass))) - (actionlib-client:call-simple-action-client - 'giskard-action - :action-goal goal - :action-timeout action-timeout)) - (ensure-giskard-cartesian-goal-reached result status goal-pose-left goal-pose-right - left-tool-frame right-tool-frame - convergence-delta-xy convergence-delta-theta) - (values result status) - ;; return the joint state, which is our observation - (joints:full-joint-states-as-hash-table))) - ;; return NIL as observation if the goal is empty - (and (roslisp:ros-info (pr2-ll giskard-cart) "Got an empty goal...") - NIL))) - - - - - - - - - -;; header: -;; seq: 17 -;; stamp: -;; secs: 1560439219 -;; nsecs: 637718915 -;; frame_id: '' -;; goal_id: -;; stamp: -;; secs: 1560439219 -;; nsecs: 637681961 -;; id: "/giskard_interactive_marker-17-1560439219.638" -;; goal: -;; type: 1 -;; cmd_seq: -;; - -;; constraints: [] -;; joint_constraints: [] -;; cartesian_constraints: -;; - -;; type: "CartesianPosition" -;; root_link: "odom" -;; tip_link: "base_footprint" -;; goal: -;; header: -;; seq: 0 -;; stamp: -;; secs: 0 -;; nsecs: 0 -;; frame_id: "base_footprint" -;; pose: -;; position: -;; x: 2.50292941928e-08 -;; y: 0.0 -;; z: 0.209769845009 -;; orientation: -;; x: 0.0 -;; y: 0.0 -;; z: 0.0 -;; w: 1.0 -;; - -;; type: "CartesianOrientationSlerp" -;; root_link: "odom" -;; tip_link: "base_footprint" -;; goal: -;; header: -;; seq: 0 -;; stamp: -;; secs: 0 -;; nsecs: 0 -;; frame_id: "base_footprint" -;; pose: -;; position: -;; x: 2.50292941928e-08 -;; y: 0.0 -;; z: 0.209769845009 -;; orientation: -;; x: 0.0 -;; y: 0.0 -;; z: 0.0 -;; w: 1.0 -;; collisions: -;; - -;; type: 1 -;; min_dist: 0.0 -;; robot_links: [''] -;; body_b: "pr2" -;; link_bs: [''] diff --git a/cram_external_interfaces/cram_giskard/src/collision-scene.lisp b/cram_external_interfaces/cram_giskard/src/collision-scene.lisp index 61dcc64eea..a699a95de6 100644 --- a/cram_external_interfaces/cram_giskard/src/collision-scene.lisp +++ b/cram_external_interfaces/cram_giskard/src/collision-scene.lisp @@ -38,17 +38,21 @@ "Initializes *robosherlock-service* ROS publisher" (let (ready) (loop repeat 12 ; for one minute then give up - until (setf ready (roslisp:wait-for-service *giskard-environment-service-name* 5)) - do (roslisp:ros-info (gisk-env-service) "Waiting for giskard environment service.")) + until (setf ready + (roslisp:wait-for-service *giskard-environment-service-name* 5)) + do (roslisp:ros-info (gisk-env-service) + "Waiting for giskard environment service.")) (if ready (prog1 (setf *giskard-environment-service* (make-instance 'roslisp:persistent-service :service-name *giskard-environment-service-name* :service-type 'giskard_msgs-srv:updateworld)) - (roslisp:ros-info (gisk-env-service) "Giskard environment service client created.")) + (roslisp:ros-info (gisk-env-service) + "Giskard environment service client created.")) (progn - (roslisp:ros-error (gisk-env-service) "Giskard environment service doesn't reply. Ignoring.") + (roslisp:ros-error (gisk-env-service) + "Giskard environment service doesn't reply. Ignoring.") nil)))) (defun get-giskard-environment-service () @@ -68,15 +72,20 @@ (defun make-giskard-environment-request (add-or-remove-or-attach-or-detach &key name - (pose (cl-transforms-stamped:make-pose-stamped - "map" - 0.0 - (cl-transforms:make-identity-vector) - (cl-transforms:make-identity-rotation))) - (dimensions '(1.0 1.0 1.0)) + pose + dimensions joint-state-topic) (declare (type keyword add-or-remove-or-attach-or-detach) - (type (or null string) name)) + (type (or null string) name) + (type (or null cl-transforms-stamped:pose-stamped) pose)) + (unless pose + (setf pose (cl-transforms-stamped:make-pose-stamped + "map" + 0.0 + (cl-transforms:make-identity-vector) + (cl-transforms:make-identity-rotation)))) + (unless dimensions + (setf dimensions '(1.0 1.0 1.0))) (ecase add-or-remove-or-attach-or-detach (:add (roslisp:make-request @@ -109,7 +118,7 @@ 'giskard_msgs-msg:worldbody :urdf_body) :name name - :urdf (roslisp:get-param cram-bullet-reasoning-belief-state::*kitchen-parameter* nil) + :urdf (roslisp:get-param rob-int:*environment-description-parameter* nil) :joint_state_topic joint-state-topic) :pose (cl-transforms-stamped:to-msg pose))) (:remove @@ -186,34 +195,54 @@ 'giskard_msgs-srv:error_msg) nil)))) +;;;;;;;;;;;;;;;;;;;;;;;; UTILS ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defun reset-collision-scene () + (call-giskard-environment-service + :remove-all) + (when (btr:get-environment-object) + (call-giskard-environment-service + :add-environment + :name (roslisp-utilities:rosify-underscores-lisp-name + (rob-int:get-environment-name)) + :pose (cl-transforms-stamped:pose->pose-stamped + cram-tf:*fixed-frame* 0.0 (btr:pose (btr:get-environment-object))) + :joint-state-topic "kitchen/joint_states"))) ;;;;;;;;;;;;;;;;;;;;;;;; EVENT HANDLERS ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; (defmethod coe:on-event giskard-attach-object ((event cpoe:object-attached-robot)) (unless cram-projection:*projection-environment* - (let* ((object-name + (let* ((arm + (cpoe:event-arm event)) + (object-name (cpoe:event-object-name event)) (object-name-string (roslisp-utilities:rosify-underscores-lisp-name object-name)) (btr-object (btr:object btr:*current-bullet-world* object-name)) - (link (cut:var-value - '?ee-link - (car (prolog:prolog - `(and (cram-robot-interfaces:robot ?robot) - (cram-robot-interfaces:end-effector-link - ?robot ,(cpoe:event-arm event) - ?ee-link))))))) + (link (if (cpoe:event-arm event) + (cut:var-value + '?ee-link + (car (prolog:prolog + `(and (rob-int:robot ?robot) + (rob-int:end-effector-link ?robot ,arm ?ee-link))))) + (cpoe:event-link event)))) + (when (cut:is-var link) (error "[GISKARD OBJECT-ATTACHED] Couldn't find robot's EE link.")) (unless btr-object (error "[GISKARD OBJECT-ATTACHED] there was no corresponding btr object.")) + ;; TODO: hack for pivoting!! + (when (string-equal link "ur5_wrist_3_link") + (setf link "refills_finger")) + (let* ((map-to-ee-transform (cl-transforms-stamped:lookup-transform cram-tf:*transformer* cram-tf:*fixed-frame* link - :timeout 2 + :timeout cram-tf:*tf-default-timeout* :time 0)) (ee-to-map-transform (cram-tf:transform-stamped-inv map-to-ee-transform)) (map-to-obj-transform (cram-tf:pose->transform-stamped @@ -225,10 +254,26 @@ link object-name-string ee-to-map-transform map-to-obj-transform)) (ee-to-object-pose (cram-tf:strip-transform-stamped ee-to-object-transform))) + ;; TODO: another hack for pivoting!! + ;; take the object pose just directly from TF, + ;; giskard is publishing the tf frame + ;; giskard only publishes TF for attached objects, + ;; not the other objects in the collision scene + (handler-case + (setf ee-to-object-pose + (cram-tf:strip-transform-stamped + (cl-transforms-stamped:lookup-transform + cram-tf:*transformer* + link + object-name-string + :timeout cram-tf:*tf-default-timeout* + :time (roslisp:ros-time)))) + (cl-transforms-stamped:transform-stamped-error ())) - ;; (call-giskard-environment-service - ;; :remove - ;; :name object-name-string) + ;; remove the object first, maybe it was already attached to something + (call-giskard-environment-service + :remove + :name object-name-string) (call-giskard-environment-service :attach :name object-name-string @@ -239,20 +284,35 @@ (defmethod coe:on-event giskard-detach-object ((event cpoe:object-detached-robot)) (unless cram-projection:*projection-environment* - (let* ((object-name (cpoe:event-object-name event)) - (object-name-string (roslisp-utilities:rosify-underscores-lisp-name object-name))) - (call-giskard-environment-service - :detach - :name object-name-string)))) + (let* ((object-name + (cpoe:event-object-name event)) + (object-name-string + (roslisp-utilities:rosify-underscores-lisp-name object-name)) + (btr-object + (btr:object btr:*current-bullet-world* object-name))) + (when btr-object + (let ((attached-to-another-link-as-well? + (btr:object-attached (btr:get-robot-object) btr-object))) + (unless attached-to-another-link-as-well? + (call-giskard-environment-service + :detach + :name object-name-string))))))) (defmethod coe:on-event giskard-perceived ((event cpoe:object-perceived-event)) (unless cram-projection:*projection-environment* - (let* ((object-name (desig:desig-prop-value (cpoe:event-object-designator event) :name)) - (object-name-string (roslisp-utilities:rosify-underscores-lisp-name object-name)) - (btr-object (btr:object btr:*current-bullet-world* object-name))) + (let* ((object-name + (desig:desig-prop-value (cpoe:event-object-designator event) :name)) + (object-name-string + (roslisp-utilities:rosify-underscores-lisp-name object-name)) + (btr-object + (btr:object btr:*current-bullet-world* object-name)) + (robot-links-object-is-attached-to + (btr:object-attached (btr:get-robot-object) btr-object))) + ;; to update an object pose, first remove the old object together with the pose (call-giskard-environment-service :remove :name object-name-string) + ;; add it at the new perceived pose (call-giskard-environment-service :add :name object-name-string @@ -260,16 +320,39 @@ cram-tf:*fixed-frame* 0.0 (btr:pose btr-object)) :dimensions (with-slots (cl-transforms:x cl-transforms:y cl-transforms:z) (btr:calculate-bb-dims btr-object) - (list cl-transforms:x cl-transforms:y cl-transforms:z)))))) + (list cl-transforms:x cl-transforms:y cl-transforms:z))) + ;; reattach the object if it was attached somewhere + (when robot-links-object-is-attached-to + (let* ((link (car robot-links-object-is-attached-to)) + (map-to-link-transform + (cl-transforms-stamped:lookup-transform + cram-tf:*transformer* + cram-tf:*fixed-frame* + link + :timeout cram-tf:*tf-default-timeout* + :time 0)) + (link-to-map-transform + (cram-tf:transform-stamped-inv map-to-link-transform)) + (map-to-obj-transform + (cram-tf:pose->transform-stamped + cram-tf:*fixed-frame* + object-name-string + 0.0 + (btr:pose btr-object))) + (link-to-object-transform + (cram-tf:multiply-transform-stampeds + link object-name-string + link-to-map-transform map-to-obj-transform)) + (link-to-object-pose + (cram-tf:strip-transform-stamped link-to-object-transform))) + (call-giskard-environment-service + :attach + :name object-name-string + :pose link-to-object-pose + :dimensions (with-slots (cl-transforms:x cl-transforms:y cl-transforms:z) + (btr:calculate-bb-dims btr-object) + (list cl-transforms:x cl-transforms:y cl-transforms:z)))))))) (defmethod coe:clear-belief giskard-clear () (unless cram-projection:*projection-environment* - (call-giskard-environment-service - :remove-all) - (when (btr:get-environment-object) - (call-giskard-environment-service - :add-environment - :name (roslisp-utilities:rosify-underscores-lisp-name (btr:name (btr:get-environment-object))) - :pose (cl-transforms-stamped:pose->pose-stamped - cram-tf:*fixed-frame* 0.0 (btr:pose (btr:get-environment-object))) - :joint-state-topic "kitchen/joint_states")))) + (reset-collision-scene))) diff --git a/cram_external_interfaces/cram_giskard/src/environment-manipulation-goals.lisp b/cram_external_interfaces/cram_giskard/src/environment-manipulation-goals.lisp new file mode 100644 index 0000000000..e673d307e3 --- /dev/null +++ b/cram_external_interfaces/cram_giskard/src/environment-manipulation-goals.lisp @@ -0,0 +1,181 @@ +;;; +;;; Copyright (c) 2020, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :giskard) + +(defun make-environment-manipulation-goal (open-or-close arm + handle-link joint-state + prefer-base) + (declare (type keyword open-or-close arm) + (type symbol handle-link) + (type (or number null) joint-state) + (type boolean prefer-base)) + (make-giskard-goal + :constraints (list + (when prefer-base (make-prefer-base-constraint)) + (make-open-or-close-constraint + open-or-close arm handle-link joint-state)) + :collisions (make-constraints-vector + (make-avoid-all-collision 0.05) + (ecase open-or-close + (:open (make-allow-hand-collision + (list arm) (rob-int:get-environment-name) handle-link)) + (:close (make-allow-arm-collision + (list arm) (rob-int:get-environment-name))))))) + +(defun call-environment-manipulation-action (&key + action-timeout + open-or-close arm + handle-link joint-angle + prefer-base) + (declare (type keyword open-or-close arm) + (type symbol handle-link) + (type (or number null) joint-angle action-timeout) + (type boolean prefer-base)) + + (call-action + :action-goal (make-environment-manipulation-goal + open-or-close arm handle-link joint-angle prefer-base) + :action-timeout action-timeout)) + + +#+the-plan +( + (setf (btr:joint-state (btr:get-environment-object) "iai_fridge_door_joint") + 0.0) + (btr-belief::publish-environment-joint-state + (btr:joint-states (btr:get-environment-object))) + (pr2-pms:with-real-robot + (exe:perform + (desig:an action + (type parking-arms)))) + (pr2-pms:with-real-robot + (exe:perform + (desig:an action + (type releasing) + (gripper right)))) + (giskard::call-grasp-bar-action :arm :right :bar-length 0.8) + (pr2-pms:with-real-robot + (exe:perform + (desig:an action + (type gripping) + (gripper right)))) + (giskard::call-environment-manipulation-action :open-or-close :open + :arm :right + :handle-link :iai-fridge-door-handle) + (giskard:call-giskard-cartesian-action + :goal-pose-right (cl-transforms-stamped:make-pose-stamped "r_gripper_tool_frame" 0.0 (cl-transforms:make-3d-vector -0.1 0 0) (cl-transforms:make-identity-rotation)) + :collision-mode :allow-all) + (coe:on-event (make-instance 'cpoe:robot-state-changed)) + (setf (btr:joint-state (btr:get-environment-object) + "iai_fridge_door_joint") 1.45) + (btr-belief::publish-environment-joint-state + (btr:joint-states (btr:get-environment-object))) + (giskard::call-environment-manipulation-action :open-or-close :close + :arm :right + :handle-link :iai-fridge-door-handle) + (pr2-pms:with-real-robot + (exe:perform + (desig:an action + (type releasing) + (gripper right)))) + (pr2-pms:with-real-robot + (exe:perform + (desig:an action + (type parking-arms)))) + (setf (btr:joint-state (btr:get-environment-object) "iai_fridge_door_joint") + 0.0) + (btr-belief::publish-environment-joint-state + (btr:joint-states (btr:get-environment-object))) + ) + +#+the-dishwasher-plan +( + (setf (btr:joint-state (btr:get-environment-object) + "sink_area_dish_washer_door_joint") + 0.0) + (btr-belief::publish-environment-joint-state + (btr:joint-states (btr:get-environment-object))) + (pr2-pms:with-real-robot + (exe:perform + (desig:an action + (type parking-arms)))) + (pr2-pms:with-real-robot + (exe:perform + (desig:an action + (type releasing) + (gripper right)))) + (giskard::call-grasp-bar-action + :arm :right + :bar-axis (cl-transforms-stamped:make-vector-stamped + "iai_kitchen/sink_area_dish_washer_door_handle" 0.0 + (cl-transforms:make-3d-vector 0 1 0)) + :bar-perpendicular-axis + (cl-transforms-stamped:make-vector-stamped + "iai_kitchen/sink_area_dish_washer_door_handle" 0.0 + (cl-transforms:make-3d-vector 0 0 1)) + :bar-center (cl-transforms-stamped:make-point-stamped + "iai_kitchen/sink_area_dish_washer_door_handle" 0.0 + (cl-transforms:make-3d-vector 0.0 0 0)) + :bar-length 0.2) + (pr2-pms:with-real-robot + (exe:perform + (desig:an action + (type gripping) + (gripper right)))) + (giskard::call-environment-manipulation-action + :open-or-close :open + :arm :right + :handle-link :sink-area-dish-washer-door-handle + :joint-state (cram-math:degrees->radians 35)) + (coe:on-event (make-instance 'cpoe:robot-state-changed)) + (setf (btr:joint-state (btr:get-environment-object) + "sink_area_dish_washer_door_joint") + (cram-math:degrees->radians 35)) + (btr-belief::publish-environment-joint-state + (btr:joint-states (btr:get-environment-object))) + (giskard::call-environment-manipulation-action + :open-or-close :close + :arm :right + :handle-link :sink-area-dish-washer-door-handle) + (pr2-pms:with-real-robot + (exe:perform + (desig:an action + (type releasing) + (gripper right)))) + (pr2-pms:with-real-robot + (exe:perform + (desig:an action + (type parking-arms)))) + (setf (btr:joint-state (btr:get-environment-object) + "sink_area_dish_washer_door_joint") + (cram-math:degrees->radians 0)) + (btr-belief::publish-environment-joint-state + (btr:joint-states (btr:get-environment-object))) + ) diff --git a/cram_external_interfaces/cram_giskard/src/gripper-goals.lisp b/cram_external_interfaces/cram_giskard/src/gripper-goals.lisp new file mode 100644 index 0000000000..61bc26cc05 --- /dev/null +++ b/cram_external_interfaces/cram_giskard/src/gripper-goals.lisp @@ -0,0 +1,137 @@ +;;; +;;; Copyright (c) 2016, Gayane Kazhoyan +;;; 2020, Arthur Niedzwiecki +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :giskard) + +(defparameter *gripper-convergence-delta-joint* 0.005 "In meters.") + +(defun make-gripper-action-goal (arm joint-angle effort) + (declare (type keyword arm) + (type number joint-angle) + (ignore effort)) + (make-giskard-goal + :joint-constraints (make-gripper-joint-state-constraint arm joint-angle) + :collisions (make-allow-all-collision))) + +(defun ensure-gripper-goal-input (action-type-or-position arm effort) + (declare (type (or number keyword) action-type-or-position) + (type keyword arm) + (type (or number null) effort)) + (let* ((bindings + (car (prolog:prolog + `(and (rob-int:robot ?robot) + (rob-int:gripper-joint ?robot ,arm ?gripper-joint) + (rob-int:joint-lower-limit ?robot ?gripper-joint ?lower-limit) + (rob-int:joint-upper-limit ?robot ?gripper-joint ?upper-limit) + (rob-int:gripper-meter-to-joint-multiplier ?robot ?mult))))) + (gripper-joint + (cut:var-value '?gripper-joint bindings)) + (gripper-lower-limit + (cut:var-value '?lower-limit bindings)) + (gripper-upper-limit + (cut:var-value '?upper-limit bindings)) + (gripper-multiplier + (cut:var-value '?mult bindings))) + (when (cut:is-var gripper-joint) + (error "[giskard] Robot gripper joint was not defined.")) + (let ((position + (etypecase action-type-or-position + (number + (cond + ((< action-type-or-position gripper-lower-limit) + (roslisp:ros-warn (giskard gripper) + "POSITION (~a) cannot be < ~a. Clipping." + action-type-or-position gripper-lower-limit) + gripper-lower-limit) + ((> action-type-or-position gripper-upper-limit) + (roslisp:ros-warn (giskard gripper) + "POSITION (~a) shouldn't be > ~a. Clipping." + action-type-or-position gripper-upper-limit) + gripper-upper-limit) + (t + ;; in case the gripper is commanded in radian or so + (* gripper-multiplier action-type-or-position)))) + (keyword + (ecase action-type-or-position + (:open gripper-upper-limit) + (:close gripper-lower-limit) + (:grip gripper-lower-limit))))) + (effort + (or effort + (etypecase action-type-or-position + (number 30.0) + (keyword (ecase action-type-or-position + (:open 30.0) + (:close 30.0) + (:grip 15.0))))))) + (list position effort)))) + +(defun ensure-gripper-goal-reached (arm joint-angle) + (when (and joint-angle arm) + (let ((gripper-joint + (cut:var-value + '?gripper-joint + (car (prolog:prolog + `(and (rob-int:robot ?robot) + (rob-int:gripper-joint ?robot ,arm ?gripper-joint))))))) + (when (cut:is-var gripper-joint) + (error "[giskard] Robot gripper joint was not defined.")) + (let ((current-state (car (joints:joint-positions (list gripper-joint)))) + (goal-state joint-angle)) + (unless (cram-tf:values-converged current-state + goal-state + *gripper-convergence-delta-joint*) + (make-instance 'common-fail:manipulation-goal-not-reached + :description (format nil "Giskard did not converge to goal:~%~ + arm: ~a, current state: ~a, goal state: ~a, ~ + delta joint: ~a." + arm current-state goal-state + *gripper-convergence-delta-joint*))))))) + +(defun call-gripper-action (&key + action-timeout + action-type-or-position arm effort) + (declare (type (or number null) action-timeout effort) + (type keyword arm) + (type (or number keyword) action-type-or-position)) + + (let* ((position-and-effort + (ensure-gripper-goal-input action-type-or-position arm effort)) + (goal-joint-angle + (first position-and-effort)) + (effort + (second position-and-effort))) + + (call-action + :action-goal (make-gripper-action-goal arm goal-joint-angle effort) + :action-timeout action-timeout + ;; :check-goal-function (lambda () + ;; (ensure-gripper-goal-reached arm goal-joint-angle)) + ))) diff --git a/cram_external_interfaces/cram_giskard/src/hash-table-conversions.lisp b/cram_external_interfaces/cram_giskard/src/hash-table-conversions.lisp new file mode 100644 index 0000000000..175ab1b4ad --- /dev/null +++ b/cram_external_interfaces/cram_giskard/src/hash-table-conversions.lisp @@ -0,0 +1,177 @@ +;;; +;;; Copyright (c) 2020, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :giskard) + +(defun alist->json-string (alist) + (let ((stream (make-string-output-stream))) + (yason:encode (cut:recursive-alist-hash-table alist :test #'equal) + stream) + (get-output-stream-string stream))) + +(defun hash-table->json-string (hash-table) + (let ((stream (make-string-output-stream))) + (yason:encode hash-table + stream) + (get-output-stream-string stream))) + + +(defgeneric to-hash-table (object) + (:documentation "Converts the object into a (nested) hash table.")) + +(defun make-point-hash-table (x y z) + (alexandria:alist-hash-table + `(("x" . ,x) + ("y" . ,y) + ("z" . ,z)) + :test #'equal)) + +(defun make-quaternion-hash-table (x y z w) + (alexandria:alist-hash-table + `(("x" . ,x) + ("y" . ,y) + ("z" . ,z) + ("w" . ,w)) + :test #'equal)) + +(defun make-header-hash-table (stamp frame-id) + (cut:recursive-alist-hash-table + `(("stamp" + . (("secs" . ,(floor stamp)) + ("nsecs" . ,(* (nth-value 1 (floor stamp)) 1.0d6)))) + ("frame_id" . ,frame-id) + ("seq" . 0)) + :test #'equal)) + +(defmethod to-hash-table ((object cl-transforms:3d-vector)) + (with-slots ((x cl-transforms:x) (y cl-transforms:y) (z cl-transforms:z)) + object + (make-point-hash-table x y z))) + +(defmethod to-hash-table ((object cl-transforms:quaternion)) + (with-slots ((x cl-transforms:x) (y cl-transforms:y) (z cl-transforms:z) + (w cl-transforms:w)) + object + (make-quaternion-hash-table x y z w))) + +(defmethod to-hash-table ((object cl-transforms:pose)) + (with-slots ((origin cl-transforms:origin) + (orientation cl-transforms:orientation)) + object + (cut:recursive-alist-hash-table + `(("origin" + . ,(to-hash-table origin)) + ("orientation" + . ,(to-hash-table orientation))) + :test #'equal))) + +(defmethod to-hash-table ((object cl-transforms:transform)) + (with-slots ((origin cl-transforms:translation) + (orientation cl-transforms:rotation)) + object + (cut:recursive-alist-hash-table + `(("translation" + . ,(to-hash-table origin)) + ("rotation" + . ,(to-hash-table orientation))) + :test #'equal))) + +(defmethod to-hash-table ((object cl-transforms-stamped:stamped)) + (with-slots ((stamp cl-transforms-stamped:stamp) + (frame-id cl-transforms-stamped:frame-id)) + object + (cut:recursive-alist-hash-table + `(("header" + . ,(make-header-hash-table stamp frame-id)))))) + +(defmethod to-hash-table ((object cl-transforms-stamped:vector-stamped)) + (with-slots ((x cl-transforms:x) (y cl-transforms:y) (z cl-transforms:z) + (stamp cl-transforms-stamped:stamp) + (frame-id cl-transforms-stamped:frame-id)) + object + (cut:recursive-alist-hash-table + `(("header" + . ,(make-header-hash-table stamp frame-id)) + ("vector" + . ,(make-point-hash-table x y z))) + :test #'equal))) + +(defmethod to-hash-table ((object cl-transforms-stamped:point-stamped)) + (with-slots ((x cl-transforms:x) (y cl-transforms:y) (z cl-transforms:z) + (stamp cl-transforms-stamped:stamp) + (frame-id cl-transforms-stamped:frame-id)) + object + (cut:recursive-alist-hash-table + `(("header" + . ,(make-header-hash-table stamp frame-id)) + ("point" + . ,(make-point-hash-table x y z))) + :test #'equal))) + +(defmethod to-hash-table ((object cl-transforms-stamped:pose-stamped)) + (with-slots ((origin cl-transforms:origin) + (orientation cl-transforms:orientation) + (stamp cl-transforms-stamped:stamp) + (frame-id cl-transforms-stamped:frame-id)) + object + (with-slots ((x cl-transforms:x) (y cl-transforms:y) (z cl-transforms:z)) + origin + (with-slots ((q1 cl-transforms:x) (q2 cl-transforms:y) + (q3 cl-transforms:z) (w cl-transforms:w)) + orientation + (cut:recursive-alist-hash-table + `(("header" + . ,(make-header-hash-table stamp frame-id)) + ("pose" + . (("position" + . ,(make-point-hash-table x y z)) + ("orientation" + . ,(make-quaternion-hash-table q1 q2 q3 w))))) + :test #'equal))))) + +(defmethod to-hash-table ((object cl-transforms-stamped:transform-stamped)) + (with-slots ((origin cl-transforms:translation) + (orientation cl-transforms:rotation) + (stamp cl-transforms-stamped:stamp) + (frame-id cl-transforms-stamped:frame-id)) + object + (with-slots ((x cl-transforms:x) (y cl-transforms:y) (z cl-transforms:z)) + origin + (with-slots ((q1 cl-transforms:x) (q2 cl-transforms:y) + (q3 cl-transforms:z) (w cl-transforms:w)) + orientation + (cut:recursive-alist-hash-table + `(("header" + . ,(make-header-hash-table stamp frame-id)) + ("transform" + . (("translation" + . ,(make-point-hash-table x y z)) + ("rotation" + . ,(make-quaternion-hash-table q1 q2 q3 w))))) + :test #'equal))))) diff --git a/cram_external_interfaces/cram_giskard/src/joint-interface.lisp b/cram_external_interfaces/cram_giskard/src/joint-interface.lisp deleted file mode 100644 index fbb01df1ad..0000000000 --- a/cram_external_interfaces/cram_giskard/src/joint-interface.lisp +++ /dev/null @@ -1,146 +0,0 @@ -;;; -;;; Copyright (c) 2016, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Institute for Artificial Intelligence/ -;;; Universitaet Bremen nor the names of its contributors may be used to -;;; endorse or promote products derived from this software without -;;; specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :giskard) - -(defparameter *giskard-convergence-delta-joint* 0.17 "in radiants, about 10 degrees") - -(defun make-giskard-joint-action-goal (joint-state-left joint-state-right) - (declare (type list joint-state-left joint-state-right)) - (roslisp:make-message - 'giskard_msgs-msg:MoveGoal - :type (roslisp:symbol-code 'giskard_msgs-msg:MoveGoal :plan_and_execute) - :cmd_seq (vector - (roslisp:make-message - 'giskard_msgs-msg:movecmd - :joint_constraints (vector (roslisp:make-message - 'giskard_msgs-msg:jointconstraint - :type (roslisp:symbol-code - 'giskard_msgs-msg:jointconstraint - :joint) - :goal_state (roslisp:make-message - 'sensor_msgs-msg:jointstate - :name (apply #'vector - (first - joint-state-left)) - :position (apply #'vector - (second - joint-state-left)))) - (roslisp:make-message - 'giskard_msgs-msg:jointconstraint - :type (roslisp:symbol-code - 'giskard_msgs-msg:jointconstraint - :joint) - :goal_state (roslisp:make-message - 'sensor_msgs-msg:jointstate - :name (apply #'vector - (first - joint-state-right)) - :position (apply #'vector - (second - joint-state-right))))) - ;; :collisions (vector (roslisp:make-message - ;; 'giskard_msgs-msg:collisionentry - ;; :type (roslisp:symbol-code - ;; 'giskard_msgs-msg:collisionentry - ;; :avoid_all_collisions))) - )))) - -(defun get-arm-joint-names-and-positions-list (arm &optional joint-states) - (if joint-states - (list (mapcar #'first joint-states) - (mapcar #'second joint-states)) - (let ((joint-names - (cut:var-value '?joints - (cut:lazy-car - (prolog:prolog - `(cram-robot-interfaces:arm-joints - ,(intern "PR2" :cram-pr2-description) ,arm ?joints)))))) - (list joint-names - (joints:joint-positions joint-names))))) - -(defun ensure-giskard-joint-input-parameters (left-goal right-goal) - (flet ((ensure-giskard-joint-goal (goal arm) - (if (and (listp goal) (= (length goal) 7)) - (get-arm-joint-names-and-positions-list arm goal) - (and (roslisp:ros-warn (low-level giskard) - "Joint goal ~a was not a list of 7. Ignoring." - goal) - (get-arm-joint-names-and-positions-list arm))))) - (values (ensure-giskard-joint-goal left-goal :left) - (ensure-giskard-joint-goal right-goal :right)))) - -(defun ensure-giskard-joint-goal-reached (status - goal-configuration-left goal-configuration-right - convergence-delta-joint) - (when (eql status :preempted) - (roslisp:ros-warn (low-level giskard) "Giskard action preempted.") - (return-from ensure-giskard-joint-goal-reached)) - (when (eql status :timeout) - (roslisp:ros-warn (pr2-ll giskard-joint) "Giskard action timed out.")) - (flet ((ensure-giskard-joint-arm-goal-reached (arm goal-configuration) - (when goal-configuration - (let ((configuration (second (get-arm-joint-names-and-positions-list arm)))) - (unless (cram-tf:values-converged (joints:normalize-joint-angles - configuration) - (joints:normalize-joint-angles - (mapcar #'second goal-configuration)) - convergence-delta-joint) - (cpl:fail 'common-fail:manipulation-goal-not-reached - :description (format nil "Giskard did not converge to goal:~%~ - ~a (~a)~%should have been at~%~a~%~ - with delta-joint of ~a." - arm - (joints:normalize-joint-angles - configuration) - (joints:normalize-joint-angles - (mapcar #'second goal-configuration)) - convergence-delta-joint))))))) - (when goal-configuration-left - (ensure-giskard-joint-arm-goal-reached :left goal-configuration-left)) - (when goal-configuration-right - (ensure-giskard-joint-arm-goal-reached :right goal-configuration-right)))) - -(defun call-giskard-joint-action (&key - goal-configuration-left goal-configuration-right action-timeout - (convergence-delta-joint *giskard-convergence-delta-joint*)) - (declare (type list goal-configuration-left goal-configuration-right) - (type (or null number) action-timeout convergence-delta-joint)) - (multiple-value-bind (joint-state-left joint-state-right) - (ensure-giskard-joint-input-parameters goal-configuration-left goal-configuration-right) - (multiple-value-bind (result status) - (actionlib-client:call-simple-action-client - 'giskard-action - :action-goal (make-giskard-joint-action-goal joint-state-left joint-state-right) - :action-timeout action-timeout) - (ensure-giskard-joint-goal-reached status goal-configuration-left goal-configuration-right - convergence-delta-joint) - (values result status) - ;; return the joint state, which is our observation - (joints:full-joint-states-as-hash-table)))) diff --git a/cram_external_interfaces/cram_giskard/src/making-goal-messages.lisp b/cram_external_interfaces/cram_giskard/src/making-goal-messages.lisp new file mode 100644 index 0000000000..70d3a64292 --- /dev/null +++ b/cram_external_interfaces/cram_giskard/src/making-goal-messages.lisp @@ -0,0 +1,438 @@ +;;; +;;; Copyright (c) 2020, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :giskard) + +(defparameter *avoid-joint-limits-percentage* 40) +(defparameter *prefer-base-low-cost* 0.0001) +(defparameter *avoid-collisions-distance* 0.10 "In cm, not used atm") +(defparameter *unmovable-joint-weight* 9001) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; UTILS ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defun make-constraints-vector (&rest entries) + (if (vectorp (car entries)) + (car entries) + (if (every #'listp entries) + (apply #'vector (alexandria:flatten entries)) + (apply #'vector (remove NIL entries))))) + +(defun make-giskard-goal (&key constraints joint-constraints cartesian-constraints + collisions (goal-type :plan_and_execute)) + (roslisp:make-message + 'giskard_msgs-msg:MoveGoal + :type (roslisp:symbol-code 'giskard_msgs-msg:MoveGoal goal-type) + :cmd_seq (vector + (roslisp:make-message + 'giskard_msgs-msg:movecmd + :constraints (make-constraints-vector constraints) + :cartesian_constraints (make-constraints-vector cartesian-constraints) + :joint_constraints (make-constraints-vector joint-constraints) + :collisions (make-constraints-vector collisions))))) + +(defun cram-name-list->ros-frame-vector (cram-names-list) + "@artnie used this function but actually other CRAM users probably don't need it..." + (if cram-names-list + (make-constraints-vector + (mapcar (lambda (symbol) + (roslisp-utilities:rosify-underscores-lisp-name symbol)) + (if (listp cram-names-list) + cram-names-list + (list cram-names-list)))) + (vector (roslisp:symbol-code 'giskard_msgs-msg:collisionentry :all)))) + +(defun get-arm-joint-names-and-positions-list (arm &optional joint-states) + "Returns a list of two elements: (joint-names joint-positions)" + (if joint-states + (list (mapcar #'first joint-states) + (mapcar #'second joint-states)) + (let ((joint-names + (cut:var-value + '?joints + (cut:lazy-car + (prolog:prolog + `(and (rob-int:robot ?robot) + (rob-int:arm-joints ?robot ,arm ?joints))))))) + (unless (cut:is-var joint-names) + (list joint-names + (joints:joint-positions joint-names)))))) + +(defun get-neck-joint-names-and-positions-list (&optional joint-states) + "Returns a list of two elements: (joint-names joint-positions)" + (if joint-states + (list (mapcar #'first joint-states) + (mapcar #'second joint-states)) + (let ((joint-names + (cut:var-value + '?joints + (cut:lazy-car + (prolog:prolog + `(and (rob-int:robot ?robot) + (rob-int:robot-neck-joints ?robot . ?joints))))))) + (unless (cut:is-var joint-names) + (list joint-names + (joints:joint-positions joint-names)))))) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; JSON CONSTRAINTS ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defun make-avoid-joint-limits-constraint (&optional (percentage + *avoid-joint-limits-percentage*)) + (declare (type number percentage)) + (roslisp:make-message + 'giskard_msgs-msg:constraint + :type + "AvoidJointLimits" + :parameter_value_pair + (alist->json-string + `(("percentage" . ,percentage))))) + +(defun make-prefer-base-constraint (&optional (base-weight + *prefer-base-low-cost*)) + (roslisp:make-message + 'giskard_msgs-msg:constraint + :type + "UpdateGodMap" + :parameter_value_pair + (alist->json-string + `(("updates" + . (("rosparam" + . (("general_options" + . (("joint_weights" + . (("odom_x_joint" . ,base-weight) + ("odom_y_joint" . ,base-weight) + ("odom_z_joint" . ,base-weight))))))))))))) + +(defun make-align-planes-constraint (root-frame tip-frame root-vector tip-vector) + (declare (type string root-frame tip-frame) + (type cl-transforms-stamped:vector-stamped root-vector tip-vector)) + (roslisp:make-message + 'giskard_msgs-msg:constraint + :type + "AlignPlanes" + :parameter_value_pair + (alist->json-string + `(("root" . ,root-frame) + ("tip" . ,tip-frame) + ("root_normal" . ,(to-hash-table root-vector)) + ("tip_normal" . ,(to-hash-table tip-vector)))))) + +(defun make-align-planes-tool-frame-constraint (arm root-vector tip-vector) + (declare (type keyword arm) + (type cl-transforms-stamped:vector-stamped root-vector tip-vector)) + (let ((tool-frame + (cut:var-value + '?frame + (car (prolog:prolog + `(and (rob-int:robot ?robot) + (rob-int:robot-tool-frame ?robot ,arm ?frame))))))) + (when (cut:is-var tool-frame) + (error "[giskard] Tool frame was not defined.")) + (make-align-planes-constraint + cram-tf:*odom-frame* tool-frame root-vector tip-vector))) + +(defun make-pointing-constraint (root-frame tip-frame goal-pose + &optional pointing-vector) + (declare (type string root-frame tip-frame) + (type cl-transforms-stamped:pose-stamped goal-pose) + (type (or cl-transforms-stamped:vector-stamped null) pointing-vector)) + (roslisp:make-message + 'giskard_msgs-msg:constraint + :type + "Pointing" + :parameter_value_pair + (alist->json-string + `(("root" . ,root-frame) + ("tip" . ,tip-frame) + ("goal_point" . ,(to-hash-table + (cram-tf:pose-stamped->point-stamped + goal-pose))) + ,@(when pointing-vector + `(("pointing_axis" . ,(to-hash-table pointing-vector)))))))) + +(defun make-open-or-close-constraint (open-or-close arm handle-link goal-joint-state) + (declare (type keyword open-or-close arm) + (type keyword handle-link) + (type (or number null) goal-joint-state)) + (let ((tool-frame + (cut:var-value + '?frame + (car (prolog:prolog + `(and (rob-int:robot ?robot) + (rob-int:robot-tool-frame ?robot ,arm ?frame))))))) + (when (cut:is-var tool-frame) + (error "[giskard] Tool frame was not defined.")) + (roslisp:make-message + 'giskard_msgs-msg:constraint + :type + (roslisp-utilities:rosify-lisp-name open-or-close) + :parameter_value_pair + (alist->json-string + `(("object_name" . ,(roslisp-utilities:rosify-underscores-lisp-name + (rob-int:get-environment-name))) + ("tip" . ,tool-frame) + ("handle_link" . ,(roslisp-utilities:rosify-underscores-lisp-name + handle-link)) + ,@(when goal-joint-state + `(("goal_joint_state" . ,goal-joint-state)))))))) + +(defun make-grasp-bar-constraint (arm root-link + tip-grasp-axis + bar-axis bar-center bar-length) + (let ((tool-frame + (cut:var-value + '?frame + (car (prolog:prolog + `(and (rob-int:robot ?robot) + (rob-int:robot-tool-frame ?robot ,arm ?frame))))))) + (when (cut:is-var tool-frame) + (error "[giskard] Tool frame was not defined.")) + (roslisp:make-message + 'giskard_msgs-msg:constraint + :type + "GraspBar" + :parameter_value_pair + (alist->json-string + `(("tip_grasp_axis" + . ,(to-hash-table tip-grasp-axis)) + ("bar_axis" + . ,(to-hash-table bar-axis)) + ("bar_center" + . ,(to-hash-table bar-center)) + ("tip" + . ,tool-frame) + ("bar_length" + . ,bar-length) + ("root" + . ,root-link)))))) + +(defun make-cartesian-constraint (root-frame tip-frame goal-pose + &key max-velocity avoid-collisions-much) + (declare (type string root-frame tip-frame) + (type cl-transforms-stamped:pose-stamped goal-pose) + (type (or number null) max-velocity) + (type boolean avoid-collisions-much)) + (roslisp:make-message + 'giskard_msgs-msg:constraint + :type + "CartesianPose" + :parameter_value_pair + (alist->json-string + `(("root_link" . ,root-frame) + ("tip_link" . ,tip-frame) + ("goal" . ,(to-hash-table goal-pose)) + ,@(when max-velocity + `(("translation_max_velocity" . ,max-velocity))) + ,@(when avoid-collisions-much + `(("weight" . ,(roslisp-msg-protocol:symbol-code + 'giskard_msgs-msg:constraint + :weight_below_ca)))))))) + +(defun make-joint-constraint (joint-state weights) + (declare (type list joint-state weights)) + "`joint-state' is a list of two elements: (joint-names joint-positions). +`weights' is a list of the same length as `joint-names' and `joint-positions'." + (mapcar (lambda (joint-name joint-position weight) + (roslisp:make-message + 'giskard_msgs-msg:constraint + :type + "JointPosition" + :parameter_value_pair + (alist->json-string + `(("joint_name" . ,joint-name) + ("goal" . ,joint-position) + ("weight" . ,weight))))) + (first joint-state) + (second joint-state) + weights)) + +(defun make-unmovable-joints-constraint (joint-names + &optional (weight *unmovable-joint-weight*)) + (make-joint-constraint + (list joint-names + (joints:joint-positions joint-names)) + (make-list (length joint-names) :initial-element weight ))) + + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; NON-JSON CONSTRAINTS ;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defun make-simple-cartesian-constraint (root-link tip-link pose-stamped) + (declare (type string root-link tip-link) + (type cl-transforms-stamped:pose-stamped pose-stamped)) + (list (roslisp:make-message + 'giskard_msgs-msg:cartesianconstraint + :type (roslisp:symbol-code + 'giskard_msgs-msg:cartesianconstraint + :translation_3d) + :root_link root-link + :tip_link tip-link + :goal (cl-transforms-stamped:to-msg pose-stamped)) + (roslisp:make-message + 'giskard_msgs-msg:cartesianconstraint + :type (roslisp:symbol-code + 'giskard_msgs-msg:cartesianconstraint + :rotation_3d) + :root_link root-link + :tip_link tip-link + :goal (cl-transforms-stamped:to-msg pose-stamped)))) + +(defun make-simple-joint-constraint (joint-state) + (declare (type list joint-state)) + "`joint-state' is a list of two elements: (joint-names joint-positions)." + (roslisp:make-message + 'giskard_msgs-msg:jointconstraint + :type (roslisp:symbol-code + 'giskard_msgs-msg:jointconstraint + :joint) + :goal_state (roslisp:make-message + 'sensor_msgs-msg:jointstate + :name (apply #'vector (first joint-state)) + :position (apply #'vector (second joint-state))))) + +(defun make-current-joint-state-constraint (arms) + (let* ((joint-names-and-positions-lists + (mapcar #'get-arm-joint-names-and-positions-list arms)) + (joint-names + (mapcan #'first joint-names-and-positions-lists)) + (joint-positions + (mapcan #'second joint-names-and-positions-lists))) + (make-simple-joint-constraint (list joint-names joint-positions)))) + +(defun make-gripper-joint-state-constraint (arm joint-angle) + (let ((gripper-joint + (cut:var-value + '?joint + (car (prolog:prolog + `(and (rob-int:robot ?robot) + (rob-int:gripper-joint ?robot ,arm ?joint))))))) + (when (cut:is-var gripper-joint) + (error "[giskard] Robot gripper joint was not defined.")) + (make-simple-joint-constraint `((,gripper-joint) (,joint-angle))))) + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; COLLISIONS ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; + +(defun make-allow-all-collision () + (roslisp:make-message + 'giskard_msgs-msg:collisionentry + :type (roslisp:symbol-code + 'giskard_msgs-msg:collisionentry + :allow_all_collisions))) + +(defun make-avoid-all-collision (&optional (minimal-distance + *avoid-collisions-distance*)) + (declare (type number minimal-distance)) + (roslisp:make-message + 'giskard_msgs-msg:collisionentry + :type (roslisp:symbol-code + 'giskard_msgs-msg:collisionentry + :avoid_all_collisions) + :min_dist minimal-distance)) + +(defun make-allow-robot-links-collision (links body-b &optional body-b-link) + (declare (type list links) + (type (or null keyword) body-b body-b-link)) + (roslisp:make-message + 'giskard_msgs-msg:collisionentry + :type (roslisp:symbol-code + 'giskard_msgs-msg:collisionentry + :allow_collision) + :robot_links (make-constraints-vector links) + :body_b (if body-b + (roslisp-utilities:rosify-underscores-lisp-name body-b) + (roslisp:symbol-code 'giskard_msgs-msg:collisionentry :all)) + :link_bs (vector + (if body-b-link + (roslisp-utilities:rosify-underscores-lisp-name body-b-link) + (roslisp:symbol-code 'giskard_msgs-msg:collisionentry :all))))) + +(defun make-allow-arm-collision (arms body-b &optional body-b-link) + (declare (type list arms) + (type (or null keyword) body-b body-b-link)) + (let ((arm-links + (mapcan (lambda (arm) + (cut:var-value + '?arm-links + (car + (prolog:prolog + `(and (rob-int:robot ?robot) + (rob-int:arm-links ?robot ,arm ?arm-links)))))) + arms))) + (make-allow-robot-links-collision arm-links body-b body-b-link))) + +(defun make-allow-hand-collision (arms body-b &optional body-b-link) + (declare (type list arms) + (type (or null keyword) body-b body-b-link)) + (let ((hand-links + (mapcan (lambda (hand) + (cut:var-value + '?hand-links + (car + (prolog:prolog + `(and (rob-int:robot ?robot) + (rob-int:hand-links ?robot ,hand ?hand-links)))))) + arms))) + (make-allow-robot-links-collision hand-links body-b body-b-link))) + +(defun make-allow-fingers-collision (arms body-b &optional body-b-link) + (declare (type list arms) + (type (or null keyword) body-b body-b-link)) + (let ((finger-links + (mapcan (lambda (arm) + (cut:var-value + '?finger-links + (car + (prolog:prolog + `(and (rob-int:robot ?robot) + (rob-int:hand-links ?robot ,arm ?hand-links) + (setof ?finger-link + (and (member ?finger-link ?hand-links) + (rob-int:hand-finger-link + ?robot ,arm ?finger-link)) + ?finger-links)))))) + arms))) + (make-allow-robot-links-collision finger-links body-b body-b-link))) + +(defun make-allow-attached-collision (object-name environment-link) + (declare (type (or symbol null) object-name) + (type (or string null) environment-link)) + "`object-name' is the name of the attached object." + (roslisp:make-message + 'giskard_msgs-msg:collisionentry + :type (roslisp:symbol-code + 'giskard_msgs-msg:collisionentry + :allow_collision) + :robot_links (vector + (if object-name + (roslisp-utilities:rosify-underscores-lisp-name object-name) + (roslisp:symbol-code 'giskard_msgs-msg:collisionentry :all))) + :body_b (roslisp-utilities:rosify-underscores-lisp-name + (rob-int:get-environment-name)) + :link_bs (vector + (if environment-link + (roslisp-utilities:rosify-underscores-lisp-name environment-link) + (roslisp:symbol-code 'giskard_msgs-msg:collisionentry :all))))) diff --git a/cram_external_interfaces/cram_giskard/src/misc-goals.lisp b/cram_external_interfaces/cram_giskard/src/misc-goals.lisp new file mode 100644 index 0000000000..70e5f064f3 --- /dev/null +++ b/cram_external_interfaces/cram_giskard/src/misc-goals.lisp @@ -0,0 +1,159 @@ +;;; +;;; Copyright (c) 2020, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :giskard) + +(defun make-grasp-bar-goal (arm + tip-grasp-axis bar-axis + tip-finger-axis bar-perpendicular-axis + bar-center + bar-length + root-link) + (declare (type keyword arm) + (type cl-transforms-stamped:vector-stamped + tip-grasp-axis bar-axis tip-finger-axis bar-perpendicular-axis) + (type cl-transforms-stamped:point-stamped bar-center) + (type string root-link) + (type number bar-length)) + (make-giskard-goal + :constraints (make-constraints-vector + (make-prefer-base-constraint) + (make-align-planes-tool-frame-constraint + arm bar-perpendicular-axis tip-finger-axis) + (make-grasp-bar-constraint + arm root-link tip-grasp-axis bar-axis bar-center bar-length)))) + +(defun call-grasp-bar-action (&key + arm root-link + tip-grasp-axis tip-finger-axis + bar-axis bar-perpendicular-axis + bar-center bar-length + action-timeout) + (declare (type (or keyword list) arm) + (type (or cl-transforms-stamped:vector-stamped null) + tip-grasp-axis bar-axis) + (type (or cl-transforms-stamped:point-stamped null) bar-center) + (type (or string null) root-link) + (type (or number null) bar-length action-timeout)) + + (call-action + :action-goal (print + (make-grasp-bar-goal + arm + tip-grasp-axis bar-axis + tip-finger-axis bar-perpendicular-axis + bar-center + bar-length root-link)) + :action-timeout action-timeout)) + + + +#+test-for-grasp-bar-action +( + (defun call-grasp-fridge-handle-action () + (call-grasp-bar-action + :arm :right + :tip-grasp-axis (cl-transforms-stamped:make-vector-stamped + (ecase arm + (:left cram-tf:*robot-left-tool-frame*) + (:right cram-tf:*robot-right-tool-frame*)) + 0.0 + (cl-transforms:make-3d-vector 0 0 1)) + :tip-finger-axis (cl-transforms-stamped:make-vector-stamped + (ecase arm + (:left cram-tf:*robot-left-tool-frame*) + (:right cram-tf:*robot-right-tool-frame*)) + 0.0 + (cl-transforms:make-3d-vector 0 1 0)) + :bar-axis (cl-transforms-stamped:make-vector-stamped + "iai_kitchen/iai_fridge_door_handle" 0.0 + (cl-transforms:make-3d-vector 0 0 -1)) + :bar-perpendicular-axis (cl-transforms-stamped:make-vector-stamped + "iai_kitchen/iai_fridge_door_handle" 0.0 + (cl-transforms:make-3d-vector 0 1 0)) + :bar-center (cl-transforms-stamped:make-point-stamped + "iai_kitchen/iai_fridge_door_handle" 0.0 + (cl-transforms:make-3d-vector 0 0 0)) + :bar-length 0.8 + :root-link cram-tf:*odom-frame*)) + + (defun call-grasp-dishwasher-handle-action () + (call-grasp-bar-action + :arm :right + :tip-grasp-axis (cl-transforms-stamped:make-vector-stamped + (ecase arm + (:left cram-tf:*robot-left-tool-frame*) + (:right cram-tf:*robot-right-tool-frame*)) + 0.0 + (cl-transforms:make-3d-vector 0 0 1)) + :tip-finger-axis (cl-transforms-stamped:make-vector-stamped + (ecase arm + (:left cram-tf:*robot-left-tool-frame*) + (:right cram-tf:*robot-right-tool-frame*)) + 0.0 + (cl-transforms:make-3d-vector 0 1 0)) + :bar-axis (cl-transforms-stamped:make-vector-stamped + "iai_kitchen/sink_area_dish_washer_door_handle" 0.0 + (cl-transforms:make-3d-vector 0 1 0)) + :bar-perpendicular-axis (cl-transforms-stamped:make-vector-stamped + "iai_kitchen/sink_area_dish_washer_door_handle" 0.0 + (cl-transforms:make-3d-vector 0 0 1)) + :bar-center (cl-transforms-stamped:make-point-stamped + "iai_kitchen/sink_area_dish_washer_door_handle" 0.0 + (cl-transforms:make-3d-vector 0.0 0 0)) + :bar-length 0.2 + :root-link cram-tf:*odom-frame*)) + + (defun call-grasp-dishwasher-tray-handle-action () + (call-grasp-bar-action + :arm :right + :tip-grasp-axis (cl-transforms-stamped:make-vector-stamped + (ecase arm + (:left cram-tf:*robot-left-tool-frame*) + (:right cram-tf:*robot-right-tool-frame*)) + 0.0 + (cl-transforms:make-3d-vector 0 0 1)) + :tip-finger-axis (cl-transforms-stamped:make-vector-stamped + (ecase arm + (:left cram-tf:*robot-left-tool-frame*) + (:right cram-tf:*robot-right-tool-frame*)) + 0.0 + (cl-transforms:make-3d-vector 0 1 0)) + :bar-axis (cl-transforms-stamped:make-vector-stamped + "iai_kitchen/sink_area_dish_washer_tray_handle_front_side" 0.0 + (cl-transforms:make-3d-vector 0 -1 0)) + :bar-perpendicular-axis (cl-transforms-stamped:make-vector-stamped + "iai_kitchen/sink_area_dish_washer_tray_handle_front_side" 0.0 + (cl-transforms:make-3d-vector 0 0 -1)) + :bar-center (cl-transforms-stamped:make-point-stamped + "iai_kitchen/sink_area_dish_washer_tray_handle_front_side" 0.0 + (cl-transforms:make-3d-vector 0.06 0 -0)) + :bar-length 0.20 + :root-link cram-tf:*odom-frame*)) + ) diff --git a/cram_external_interfaces/cram_giskard/src/neck-goals.lisp b/cram_external_interfaces/cram_giskard/src/neck-goals.lisp new file mode 100644 index 0000000000..0fb85bbf78 --- /dev/null +++ b/cram_external_interfaces/cram_giskard/src/neck-goals.lisp @@ -0,0 +1,174 @@ +;;; +;;; Copyright (c) 2020, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :giskard) + +(defparameter *neck-convergence-delta-xy* 0.01 "in meters") +(defparameter *neck-convergence-delta-joint* 0.1 "In radians, about 6 degrees") +(defparameter *cam* "ur5_wrist_3_link") +(defparameter *donbot-camera-offset* (cl-transforms:make-transform + (cl-transforms:make-3d-vector -0.3 0.8 0.4) + (cl-transforms:make-identity-rotation))) + +(defun make-neck-action-goal (goal-pose + &key + (root-link cram-tf:*robot-base-frame*) + camera-link + camera-offset) + (declare (type cl-transforms-stamped:pose-stamped goal-pose)) + (make-giskard-goal + :constraints (list (make-align-planes-constraint + root-link + camera-link + (cl-transforms-stamped:make-vector-stamped + cram-tf:*fixed-frame* 0.0 + (cl-transforms:make-3d-vector 1 0 0)) + (cl-transforms-stamped:make-vector-stamped + camera-link 0.0 + (cl-transforms:make-3d-vector 0 -1 0))) + (make-pointing-constraint + root-link + camera-link + goal-pose + ;; (cl-transforms-stamped:make-vector-stamped + ;; "rs_camera_depth_optical_frame" 0.0 + ;; (cl-transforms:make-3d-vector 0 0 1)) + )) + :cartesian-constraints (when camera-offset + (make-simple-cartesian-constraint + root-link camera-link + (cram-tf:strip-transform-stamped + (cram-tf:apply-transform + (cl-transforms-stamped:transform->transform-stamped + cram-tf:*fixed-frame* cram-tf:*fixed-frame* 0.0 + *donbot-camera-offset*) + (cram-tf:pose-stamped->transform-stamped + goal-pose "goal_pose"))))) + :collisions (make-avoid-all-collision))) + +(defun make-neck-joint-action-goal (joint-state) + (declare (type list joint-state)) + (make-giskard-goal + :joint-constraints (make-simple-joint-constraint joint-state) + :collisions (make-avoid-all-collision))) + + + + +(defun ensure-neck-goal-input () + (if (eq (rob-int:get-robot-name) :iai-donbot) + (list *cam* *donbot-camera-offset*) + (let ((camera-frame + (cut:var-value + '?frame + (car (prolog:prolog `(and (rob-int:robot ?robot) + (rob-int:camera-frame ?robot ?frame))))))) + (when (cut:is-var camera-frame) + (error "[giskard] Robot camera frame was not defined.")) + (list camera-frame)))) + +(defun ensure-neck-joint-goal-input (goal-configuration) + (if (and (listp goal-configuration) + (or (= (length goal-configuration) 7) + (= (length goal-configuration) 6))) + (get-neck-joint-names-and-positions-list goal-configuration) + (progn (roslisp:ros-warn (giskard neck) + "Joint goal ~a was not a list of 7 (or 6). Ignoring." + goal-configuration) + (get-neck-joint-names-and-positions-list)))) + + + + +(defun ensure-neck-goal-reached (goal-pose goal-frame) + "@artnie-s function, I actually doubt very much that it makes sense :)" + (when goal-pose + (let* ((pose-in-frame + (cram-tf:ensure-pose-in-frame goal-pose goal-frame)) + (goal-dist + (max (abs (cl-transforms:x (cl-transforms:origin pose-in-frame))) + (abs (cl-transforms:y (cl-transforms:origin pose-in-frame)))))) + (unless (<= goal-dist *neck-convergence-delta-xy*) + (make-instance 'common-fail:manipulation-goal-not-reached + :description (format nil "Giskard did not converge to goal:~%~ + ~a should have been at ~a with delta-xy of ~a." + goal-frame goal-pose + *neck-convergence-delta-xy*)))))) + +(defun ensure-neck-joint-goal-reached (goal-configuration) + (when goal-configuration + (let ((current-angles + (cram-tf:normalize-joint-angles + (second (get-neck-joint-names-and-positions-list)))) + (goal-angles + (cram-tf:normalize-joint-angles + (mapcar #'second goal-configuration)))) + (unless (cram-tf:values-converged + current-angles goal-angles *neck-convergence-delta-joint*) + (make-instance 'common-fail:manipulation-goal-not-reached + :description (format nil "Giskard did not converge to goal:~%~ + Neck current angles: ~a~%~ + Neck goal angles: ~a~%~ + Convergence delta: ~a. " + current-angles goal-angles + *neck-convergence-delta-joint*)))))) + + + +(defun call-neck-action (&key action-timeout goal-pose) + (declare (type (or number null) action-timeout) + (type cl-transforms-stamped:pose-stamped goal-pose)) + + (let* ((camera-frame-and-offset (ensure-neck-goal-input)) + (camera-frame (first camera-frame-and-offset)) + (camera-offset (second camera-frame-and-offset))) + + (cram-tf:visualize-marker (list goal-pose) :r-g-b-list '(0 0 1)) + + (call-action + :action-goal (make-neck-action-goal goal-pose + :camera-link camera-frame + :camera-offset camera-offset) + :action-timeout action-timeout + ;; :check-goal-function (lambda () (ensure-neck-goal-reached + ;; goal-pose camera-frame)) + ))) + +(defun call-neck-joint-action (&key action-timeout goal-configuration) + (declare (type (or number null) action-timeout) + (type (or list null) goal-configuration)) + + (let ((joint-state + (ensure-neck-joint-goal-input goal-configuration))) + + (call-action + :action-goal (make-neck-joint-action-goal joint-state) + :action-timeout action-timeout + :check-goal-function (lambda () + (ensure-neck-joint-goal-reached goal-configuration))))) diff --git a/cram_external_interfaces/cram_giskard/src/package.lisp b/cram_external_interfaces/cram_giskard/src/package.lisp index dceff78c27..c0d4412d24 100644 --- a/cram_external_interfaces/cram_giskard/src/package.lisp +++ b/cram_external_interfaces/cram_giskard/src/package.lisp @@ -33,9 +33,23 @@ (:nicknames #:giskard) (:use #:common-lisp) (:export - ;; cartesian-interface - #:call-giskard-cartesian-action - ;; joint-interface - #:call-giskard-joint-action + ;; arm-goals + #:call-arm-cartesian-action + #:call-arm-joint-action + ;; base-goals + #:call-base-action + ;; torso-goals + #:call-torso-action + ;; gripper-goals + #:call-gripper-action + ;; neck-goals + #:call-neck-action + #:call-neck-joint-action + ;; environment-manipulation-goals + #:call-environment-manipulation-action + ;; misc-goals + #:call-grasp-bar-action + ;; collision-scene + #:reset-collision-scene ;; process-module #:giskard-pm)) diff --git a/cram_external_interfaces/cram_giskard/src/process-module.lisp b/cram_external_interfaces/cram_giskard/src/process-module.lisp index 4c53f98e7c..a08c17e71a 100644 --- a/cram_external_interfaces/cram_giskard/src/process-module.lisp +++ b/cram_external_interfaces/cram_giskard/src/process-module.lisp @@ -30,57 +30,56 @@ (in-package :giskard) (cpm:def-process-module giskard-pm (motion-designator) - (destructuring-bind (command argument-1 &rest rest-arguments) + (destructuring-bind (command argument-1 &rest rest-args) (desig:reference motion-designator) (ecase command (cram-common-designators:move-tcp - (call-giskard-cartesian-action :goal-pose-left argument-1 - :goal-pose-right (first rest-arguments) - :collision-mode (second rest-arguments) - :collision-object-b (third rest-arguments) - :collision-object-b-link (fourth rest-arguments) - :collision-object-a (fifth rest-arguments) - :move-the-ass (sixth rest-arguments))) + (giskard:call-arm-cartesian-action + :goal-pose-left argument-1 + :goal-pose-right (first rest-args) + :collision-mode (second rest-args) + :collision-object-b (third rest-args) + :collision-object-b-link (fourth rest-args) + :collision-object-a (fifth rest-args) + :move-base (sixth rest-args) + :prefer-base (seventh rest-args) + :align-planes-left (eighth rest-args) + :align-planes-right (ninth rest-args))) (cram-common-designators:move-joints - (call-giskard-joint-action :goal-configuration-left argument-1 - :goal-configuration-right (first rest-arguments))) + (giskard:call-arm-joint-action + :goal-configuration-left argument-1 + :goal-configuration-right (first rest-args) + :align-planes-left (second rest-args) + :align-planes-right (third rest-args))) + (cram-common-designators:move-arm-pull + (giskard:call-environment-manipulation-action + :open-or-close :open + :arm argument-1 + :handle-link (fifth rest-args) + :joint-angle (second rest-args) + :prefer-base (eighth rest-args))) + (cram-common-designators:move-arm-push + (giskard:call-environment-manipulation-action + :open-or-close :close + :arm argument-1 + :handle-link (fifth rest-args) + :joint-angle (second rest-args) + :prefer-base (eighth rest-args))) + (cram-common-designators:move-head + (when argument-1 + (giskard:call-neck-action + :goal-pose argument-1)) + (when (car rest-args) + (giskard:call-neck-joint-action + :goal-configuration (car rest-args)))) (cram-common-designators:move-base - (call-giskard-base-action :goal-pose argument-1)) + (giskard:call-base-action + :goal-pose argument-1)) (cram-common-designators:move-torso - (call-giskard-torso-action :goal-joint-state argument-1))))) - -(prolog:def-fact-group giskard-pm (cpm:matching-process-module - cpm:available-process-module) - - (prolog:<- (cpm:matching-process-module ?motion-designator giskard-pm) - (or (desig:desig-prop ?motion-designator (:type :moving-tcp)) - (desig:desig-prop ?motion-designator (:type :moving-arm-joints)) - (desig:desig-prop ?motion-designator (:type :going)) - (desig:desig-prop ?motion-designator (:type :moving-torso)))) - - (prolog:<- (cpm:available-process-module giskard-pm) - (prolog:not (cpm:projection-running ?_)))) - -;;; The examples below are deprecated, so the designator changed, but the idea is the same -;;; Examples: -;; -;; (cram-process-modules:with-process-modules-running -;; (giskard::giskard-pm) -;; (cpl:top-level -;; (cpm:pm-execute-matching -;; (desig:a motion (type moving-tcp) (right-pose ((0.5 0.5 1.5) (0 0 0 1))))))) -;; -;; (cram-process-modules:with-process-modules-running -;; (giskard::giskard-pm) -;; (cpl:top-level -;; (cpm:pm-execute-matching -;; (desig:a motion -;; (to move-arm) -;; (right ((0.5 -0.5 1.5) (0 0 0 1))) -;; (left ((0.5 0.5 1.5) (0 0 0 1))))))) -;; -;; (cram-process-modules:with-process-modules-running -;; (giskard::giskard-pm) -;; (cpl:top-level -;; (cpm:pm-execute-matching -;; (desig:a motion (to move-arm) (right (((1 1 1) (0 0 0 1)) nil ((1 1 1) (0 0 0 1)))))))) + (giskard:call-torso-action + :goal-joint-state argument-1)) + (cram-common-designators:move-gripper-joint + (giskard:call-gripper-action + :action-type-or-position argument-1 + :arm (first rest-args) + :effort (second rest-args)))))) diff --git a/cram_external_interfaces/cram_giskard/src/torso-goals.lisp b/cram_external_interfaces/cram_giskard/src/torso-goals.lisp index 9d5ed85ad2..4321854573 100644 --- a/cram_external_interfaces/cram_giskard/src/torso-goals.lisp +++ b/cram_external_interfaces/cram_giskard/src/torso-goals.lisp @@ -31,163 +31,66 @@ (defparameter *torso-convergence-delta-joint* 0.01 "in meters") -(defun make-giskard-torso-action-goal (joint-angle) +(defun make-torso-action-goal (joint-angle) (declare (type number joint-angle)) - (roslisp:make-message - 'giskard_msgs-msg:MoveGoal - :type (roslisp:symbol-code 'giskard_msgs-msg:MoveGoal ;; :plan_only - :plan_and_execute - ) - :cmd_seq (vector - (roslisp:make-message - 'giskard_msgs-msg:movecmd - :joint_constraints - (vector (roslisp:make-message - 'giskard_msgs-msg:jointconstraint - :type (roslisp:symbol-code - 'giskard_msgs-msg:jointconstraint - :joint) - :goal_state (roslisp:make-message - 'sensor_msgs-msg:jointstate - :name (vector cram-tf:*robot-torso-joint*) - :position (vector joint-angle)))))))) + (make-giskard-goal + :joint-constraints (make-simple-joint-constraint + `((,cram-tf:*robot-torso-joint*) (,joint-angle))))) -(defun ensure-torso-input-parameters (position) +(defun ensure-torso-goal-input (position) (declare (type (or keyword number) position)) (let* ((bindings (car (prolog:prolog `(and (rob-int:robot ?robot) - (btr:bullet-world ?w) (rob-int:robot-torso-link-joint ?robot ?_ ?joint) (rob-int:joint-lower-limit ?robot ?joint ?lower) (rob-int:joint-upper-limit ?robot ?joint ?upper))))) (lower-limit - (+ (cut:var-value '?lower bindings) 0.01)) ; don't push the robot so hard + (cut:var-value '?lower bindings)) (upper-limit - (- (cut:var-value '?upper bindings) 0.01)) ; no don't do it - (cropped-joint-angle - (etypecase position - (number (if (< position lower-limit) - lower-limit - (if (> position upper-limit) - upper-limit - position))) - (keyword (ecase position - (:upper-limit upper-limit) - (:lower-limit lower-limit) - (:middle (/ (- upper-limit lower-limit) 2))))))) - cropped-joint-angle)) - - - -(defun ensure-giskard-torso-goal-reached (result status goal convergence-delta) - (when (eql status :preempted) - (roslisp:ros-warn (low-level giskard) "Giskard action preempted with result ~a" result) - (return-from ensure-giskard-torso-goal-reached)) - (when (eql status :timeout) - (roslisp:ros-warn (pr2-ll giskard-cart) "Giskard action timed out.")) - (when (eql status :aborted) - (roslisp:ros-warn (pr2-ll giskard-cart) "Giskard action aborted! With result ~a" result) - ;; (cpl:fail 'common-fail:manipulation-goal-not-reached - ;; :description "Giskard did not converge to goal because of collision") - ) - (let ((current-position (car (joints:joint-positions (list cram-tf:*robot-torso-joint*))))) - (unless (cram-tf:values-converged current-position goal convergence-delta) - (cpl:fail 'common-fail:torso-goal-not-reached - :description (format nil "Giskard did not converge to torso goal:~ - goal: ~a, current: ~a, delta: ~a." - goal current-position convergence-delta))))) - -(defun call-giskard-torso-action (&key - goal-joint-state action-timeout - (convergence-delta *torso-convergence-delta-joint*)) + (cut:var-value '?upper bindings)) + (torso-joint + (cut:var-value '?joint bindings))) + (if (and (not (cut:is-var lower-limit)) + (not (cut:is-var upper-limit)) + lower-limit + upper-limit) + (progn + ;; don't push the robot so hard + (setf lower-limit (+ lower-limit 0.01) + upper-limit (- upper-limit 0.01)) + (etypecase position + (number (if (< position lower-limit) + lower-limit + (if (> position upper-limit) + upper-limit + position))) + (keyword (ecase position + (:upper-limit upper-limit) + (:lower-limit lower-limit) + (:middle (/ (- upper-limit lower-limit) 2)))))) + (or (car (joints:joint-positions (list torso-joint))) 0.0)))) + +(defun ensure-torso-goal-reached (goal) + (let ((current-position + (car (joints:joint-positions (list cram-tf:*robot-torso-joint*))))) + (when current-position + (unless (cram-tf:values-converged + current-position goal *torso-convergence-delta-joint*) + (make-instance 'common-fail:torso-goal-not-reached + :description (format nil "Giskard did not converge to torso goal:~ + goal: ~a, current: ~a, delta: ~a." + goal current-position + *torso-convergence-delta-joint*)))))) + +(defun call-torso-action (&key action-timeout goal-joint-state) (declare (type (or number keyword) goal-joint-state) - (type (or null number) action-timeout convergence-delta)) - (let ((goal-joint-state (ensure-torso-input-parameters goal-joint-state))) - (multiple-value-bind (result status) - (let ((goal (make-giskard-torso-action-goal goal-joint-state))) - (actionlib-client:call-simple-action-client - 'giskard-action - :action-goal goal - :action-timeout action-timeout)) - (ensure-giskard-torso-goal-reached result status goal-joint-state convergence-delta) - (values result status) - ;; return the joint state, which is our observation - (joints:full-joint-states-as-hash-table)))) - - - - - - - + (type (or number null) action-timeout)) + (setf goal-joint-state (ensure-torso-goal-input goal-joint-state)) -;; header: -;; seq: 17 -;; stamp: -;; secs: 1560439219 -;; nsecs: 637718915 -;; frame_id: '' -;; goal_id: -;; stamp: -;; secs: 1560439219 -;; nsecs: 637681961 -;; id: "/giskard_interactive_marker-17-1560439219.638" -;; goal: -;; type: 1 -;; cmd_seq: -;; - -;; constraints: [] -;; joint_constraints: [] -;; cartesian_constraints: -;; - -;; type: "CartesianPosition" -;; root_link: "odom" -;; tip_link: "base_footprint" -;; goal: -;; header: -;; seq: 0 -;; stamp: -;; secs: 0 -;; nsecs: 0 -;; frame_id: "base_footprint" -;; pose: -;; position: -;; x: 2.50292941928e-08 -;; y: 0.0 -;; z: 0.209769845009 -;; orientation: -;; x: 0.0 -;; y: 0.0 -;; z: 0.0 -;; w: 1.0 -;; - -;; type: "CartesianOrientationSlerp" -;; root_link: "odom" -;; tip_link: "base_footprint" -;; goal: -;; header: -;; seq: 0 -;; stamp: -;; secs: 0 -;; nsecs: 0 -;; frame_id: "base_footprint" -;; pose: -;; position: -;; x: 2.50292941928e-08 -;; y: 0.0 -;; z: 0.209769845009 -;; orientation: -;; x: 0.0 -;; y: 0.0 -;; z: 0.0 -;; w: 1.0 -;; collisions: -;; - -;; type: 1 -;; min_dist: 0.0 -;; robot_links: [''] -;; body_b: "pr2" -;; link_bs: [''] + (call-action + :action-goal (make-torso-action-goal goal-joint-state) + :action-timeout action-timeout + :check-goal-function (lambda () (ensure-torso-goal-reached goal-joint-state)))) diff --git a/cram_external_interfaces/cram_hpn/src/setup.lisp b/cram_external_interfaces/cram_hpn/src/setup.lisp index 7e24d73bed..88f542146f 100644 --- a/cram_external_interfaces/cram_hpn/src/setup.lisp +++ b/cram_external_interfaces/cram_hpn/src/setup.lisp @@ -66,45 +66,30 @@ name-to-pose))) (defun spawn-kitchen () - (let ((kitchen (or btr-belief:*kitchen-urdf* - (let ((kitchen-urdf-string - (roslisp:get-param btr-belief:*kitchen-parameter* nil))) - (when kitchen-urdf-string - (setf btr-belief:*kitchen-urdf* - (cl-urdf:parse-urdf kitchen-urdf-string))))))) - (assert - (cut:force-ll - (prolog `(and - (btr:bullet-world ?w) - (btr:assert ?w (btr:object :urdf :kitchen ((0 0 0) (0 0 0 1)) - :collision-group :static-filter - :collision-mask (:default-filter - :character-filter) - ,@(when kitchen - `(:urdf ,kitchen)) - :compound T)))))))) + (let ((kitchen-urdf-string + (roslisp:get-param rob-int:*environment-description-parameter* nil))) + (when kitchen-urdf-string + (setf rob-int:*environment-urdf* + (cl-urdf:parse-urdf kitchen-urdf-string)))) + (assert + (cut:force-ll + (prolog `(and + (btr:bullet-world ?w) + (btr:assert ?w (btr:object :urdf :kitchen ((0 0 0) (0 0 0 1)) + :collision-group :static-filter + :collision-mask (:default-filter + :character-filter) + ,@(when rob-int:*environment-urdf* + `(:urdf ,rob-int:*environment-urdf*)) + :compound T))))))) (defun init-projection () - (def-fact-group costmap-metadata (costmap:costmap-size - costmap:costmap-origin - costmap:costmap-resolution - costmap:orientation-samples - costmap:orientation-sample-step) - (<- (costmap:costmap-size 12 12)) - (<- (costmap:costmap-origin -6 -6)) - (<- (costmap:costmap-resolution 0.04)) - (<- (costmap:orientation-samples 2)) - (<- (costmap:orientation-sample-step 0.3))) - - (setf cram-bullet-reasoning-belief-state:*robot-parameter* "robot_description") - (setf cram-bullet-reasoning-belief-state:*kitchen-parameter* "kitchen_description") - (setf btr:*current-bullet-world* (make-instance 'btr:bt-reasoning-world)) - (let ((robot (or rob-int:*robot-urdf* - (setf rob-int:*robot-urdf* - (cl-urdf:parse-urdf - (btr-belief::replace-all - (roslisp:get-param btr-belief:*robot-parameter*) "\\" " ")))))) + (let ((robot (setf rob-int:*robot-urdf* + (cl-urdf:parse-urdf + (cut:replace-all + (roslisp:get-param rob-int:*robot-description-parameter*) + "\\" " "))))) ;; set robot's URDF root link to *robot-base-frame* as that's how going actions works (setf (slot-value rob-int:*robot-urdf* 'cl-urdf:root-link) @@ -154,7 +139,7 @@ (let ((aabb (btr:aabb (btr:rigid-body (btr:get-environment-object) - (intern (format nil "KITCHEN.~(~a~)" name) :keyword))))) + (intern (format nil "ENVIRONMENT.~(~a~)" name) :keyword))))) (btr:add-object btr:*current-bullet-world* :box-item name diff --git a/cram_external_interfaces/cram_ik_interface/cram-ik-interface.asd b/cram_external_interfaces/cram_ik_interface/cram-ik-interface.asd index 35b042f95c..45442766a5 100644 --- a/cram_external_interfaces/cram_ik_interface/cram-ik-interface.asd +++ b/cram_external_interfaces/cram_ik_interface/cram-ik-interface.asd @@ -36,7 +36,9 @@ cl-transforms-stamped cram-tf moveit_msgs-msg - moveit_msgs-srv) + moveit_msgs-srv + ;; for representing joint states + sensor_msgs-msg) :components ((:module "src" :components diff --git a/cram_external_interfaces/cram_ik_interface/package.xml b/cram_external_interfaces/cram_ik_interface/package.xml index 652ed989cf..6b9b1981d6 100644 --- a/cram_external_interfaces/cram_ik_interface/package.xml +++ b/cram_external_interfaces/cram_ik_interface/package.xml @@ -19,4 +19,5 @@ cl_tf cram_tf moveit_msgs + sensor_msgs diff --git a/cram_external_interfaces/cram_ik_interface/src/ik.lisp b/cram_external_interfaces/cram_ik_interface/src/ik.lisp index 173755d63a..bc177314b6 100644 --- a/cram_external_interfaces/cram_ik_interface/src/ik.lisp +++ b/cram_external_interfaces/cram_ik_interface/src/ik.lisp @@ -30,6 +30,7 @@ (in-package :ik) (defparameter *ik-service-name* "kdl_ik_service/get_ik") +(defparameter *float-comparison-precision* 0.001d0) (defun call-ik-service (cartesian-pose base-link end-effector-link seed-state-msg) (declare (type cl-transforms-stamped:pose-stamped cartesian-pose) @@ -62,12 +63,7 @@ :no_ik_solution)) nil) (T - (error 'simple-error - :format-control "IK service failed: ~a" - :format-arguments (list - (roslisp-msg-protocol:code-symbol - 'moveit_msgs-msg:moveiterrorcodes - response-error-code)))))) + nil))) ;; PR2's IK kinematics solver sends garbage sometimes (simple-error (e) (declare (ignore e)) @@ -77,17 +73,31 @@ base-link end-effector-link seed-state-msg resampling-step resampling-axis - current-value lower-limit upper-limit) + current-value lower-limit upper-limit + &optional solution-valid-p) + (declare (type (or function null) solution-valid-p)) + "Calls the IK service to achieve the specified `cartesian-pose' by manipulating +the joints from `base-link' to `end-effector-link'. +`solution-valid-p' is a predicate that gets the joint state message as input +and returns T or NIL according to some validation criteria. +Mostly this is a collision check. +Returns two values: resulting joint state message and torso value. +If not valid solution was found, returns NIL." (labels ((call-ik-service-with-resampling-inner (cartesian-pose &key test-value current-value) (let ((ik-solution-msg - (call-ik-service cartesian-pose base-link end-effector-link seed-state-msg))) - (if ik-solution-msg + (call-ik-service cartesian-pose base-link end-effector-link + seed-state-msg))) + (if (and ik-solution-msg + ;; if `solution-valid-p' is bound, call it + ;; otherwise assume that the solution is valid + (or (not solution-valid-p) + (funcall solution-valid-p ik-solution-msg))) (values ik-solution-msg (or test-value current-value)) (when (or (not test-value) (> test-value lower-limit)) - ;; When we have no ik solution and have a valid test value to try, - ;; use it to resample. + ;; When we have no ik solution and have + ;; a valid test value to try, use it to resample. (let* ((next-test-value (if test-value (max lower-limit (- test-value resampling-step)) @@ -101,11 +111,7 @@ (pseudo-pose (cram-tf:translate-pose cartesian-pose - (ecase resampling-axis - (:x :x-offset) - (:y :y-offset) - (:z :z-offset)) - (- offset next-offset)))) + resampling-axis (- offset next-offset)))) (call-ik-service-with-resampling-inner pseudo-pose :test-value next-test-value @@ -120,3 +126,205 @@ :test-value nil :current-value current-value)) (roslisp:set-debug-level nil old-debug-lvl))))) + + +(defun get-joint-values-to-sample (lower-lim upper-lim sampling-step) + (declare (type number lower-lim upper-lim sampling-step)) + "Returns a list of values such that they lie within [`lower-lim'; `upper-lim'] +and the distance between the steps is `sampling-step'. +0.0 is always added to the list. +The values are sorted in ascending order based on their absolute magnitude. +E.g., if `lower-lim' = -4 and `upper-lim' = 4 and `sampling-step' = 1, +then return = (0.0 -1 1 -2 2 -3 3 -4 4)" + (remove-duplicates + (cons 0.0 + (sort + (loop for x = lower-lim then (+ x sampling-step) + until (> x upper-lim) + collect x) + (lambda (x y) + (< (abs x) (abs y))))) + ;; remove duplicates in case current value is + ;; exactly one of the sampling values + :test (lambda (x y) + (< (abs (- x y)) + *float-comparison-precision*)) + :from-end t)) + + +(defmacro find-ik-for ((goal-pose base-link tip-link seed-state-message + &optional solution-valid-p) + &body body) + "Method to find inverse kinematics for a given cartesian pose using resampling +Syntax: + (ik::find-ik-for (goal-pose base-link tip-link seed-state-message) + (ik::with-resampling (current-value resampling-axis + upper-limit lower-limit resampling-step) + (ik::with-resampling current-value2 resampling-axis2 ...) + ....)) +Resampling axis can only be :X, :Y or :Z" + `(let ((offseted-goal-pose ,goal-pose) + (base-link-evaled ,base-link) + (tip-link-evaled ,tip-link) + (seed-state-msg-evaled ,seed-state-message) + (solution-valid-p-evaled ,solution-valid-p) + (old-debug-level (roslisp:debug-level nil)) + new-joint-values) + (macrolet + ((with-resampling (&whole whole-form + (resampling-axis upper-limit lower-limit + resampling-step + &key (disable-resampling nil)) + &body body) + (let ((form-length (length whole-form))) + ;; Formulating a list of joint values to sample + `(let* ((original-goal-pose + offseted-goal-pose) + (sampling-values + (if ,disable-resampling + ;; stay at the default value if resampling is disalbled + (list 0.0d0) + (get-joint-values-to-sample + ,lower-limit ,upper-limit ,resampling-step))) + (result + (loop for value in sampling-values + do (setf offseted-goal-pose + (cram-tf:translate-pose + original-goal-pose + ,resampling-axis + (- value))) + (if (assoc ,resampling-axis new-joint-values) + (setf (cdr (assoc ,resampling-axis + new-joint-values)) + value) + (setf new-joint-values + (cons (cons ,resampling-axis value) + new-joint-values))) + (multiple-value-bind + (solution-msg joint-values) + + ;; Checking if the arguments contain + ;; &body clause or not. 2 is the + ;; current number of arguments without + ;; including the body. One being the + ;; form itself and the second being the + ;; list of values in the paranthesis. + (if (> ,form-length 2) + ;; If body is provided, call it + ;; with the current offseted value + ;; of pose (for retaining the loop + ;; value on nested calls). + (progn ,@body) + ;; else make the ik-service call + (call-ik-service + offseted-goal-pose + base-link-evaled + tip-link-evaled + seed-state-msg-evaled)) + ;; now we either got a solution from the + ;; ik service call, if we're leaf, + ;; or from our nested form. + ;; it can also be that we get NIL back + + ;; if we did get an answer, + ;; first, perform the collision check, + ;; and if that is successful, break the loop + (when solution-msg + ;; if collision check is not defined + ;; or the collision check is successful + ;; break the loop + ;; otherwise, we simply continue our loop + (let ((result-joint-values + (cons + (cons ,resampling-axis value) + joint-values))) + (when (or (not solution-valid-p-evaled) + (funcall solution-valid-p-evaled + solution-msg + new-joint-values)) + (return (list solution-msg + result-joint-values))))))))) + (setf offseted-goal-pose original-goal-pose) + (values (first result) (second result)))))) + (unwind-protect + (progn + (roslisp:set-debug-level nil 9) + ,@body) + (roslisp:set-debug-level nil old-debug-level))))) + + +(defmacro find-joint-values-for ((solution-valid-p) + &body body) + "Method to find joint-values by resamping and checking against +a validation function +Syntax: + (ik:find-joint-values-for (validation-function) + (ik::with-resampling (resampling-axis upper-limit + lower-limit resampling-step) + (ik::with-resampling (resampling-axis2 ...) + ....)) +Resampling axis can only be :X, :Y or :Z" + `(let ((solution-valid-p-evaled ,solution-valid-p) + (old-debug-level (roslisp:debug-level nil)) + (new-joint-values)) + (macrolet + ((with-resampling ((resampling-axis upper-limit lower-limit resampling-step) + &body body) + ;; Formulating a list of joint values to sample + `(let ((sampling-values + (get-joint-values-to-sample + ,lower-limit ,upper-limit ,resampling-step))) + + (loop for value in sampling-values + do (if (assoc ,resampling-axis new-joint-values) + (setf (cdr (assoc ,resampling-axis new-joint-values)) + value) + (setf new-joint-values + (cons (cons ,resampling-axis value) + new-joint-values))) + (let ((result-joint-values + (cons (cons ,resampling-axis value) + (progn ,@body)))) + ;; Return the joint values when the + ;; validation function passes, else + ;; continue the loop. + (when (funcall solution-valid-p-evaled new-joint-values) + (return result-joint-values))))))) + + (unwind-protect + (progn + (roslisp:set-debug-level nil 9) + ,@body) + (roslisp:set-debug-level nil old-debug-level))))) + + + +#+below-is-stuff-for-caching +((defun arm-pose-hash-code (arm-pose-list) + (let* ((pose (second arm-pose-list)) + (pose-list (cram-tf:pose->flat-list pose)) + (sum (abs (apply #'+ pose-list))) + (sum-big-precise-num (* sum 100000000)) + (pose-hash-code (floor sum-big-precise-num)) + (arm (first arm-pose-list)) + (overall-hash-code (ecase arm + (:left (+ pose-hash-code 10000)) + (:right (+ pose-hash-code 20000))))) + overall-hash-code)) + (defun arm-poses-equal-accurate (arm-pose-list-1 arm-pose-list-2) + (let* ((pose-1 (second arm-pose-list-1)) + (pose-2 (second arm-pose-list-2)) + (arm-1 (first arm-pose-list-1)) + (arm-2 (first arm-pose-list-2))) + (if (eql arm-1 arm-2) + (cram-tf:poses-equal-p pose-1 pose-2 0.000001d0 0.000010d0) + nil))) + (sb-ext:define-hash-table-test arm-poses-equal-accurate arm-pose-hash-code) + (defvar *ik-solution-cache* (make-hash-table :test 'arm-poses-equal-accurate)) + (setf (gethash (list left-or-right cartesian-pose) *ik-solution-cache*) + (list ik-solution-position resulting-torso-angle)) + (let ((hashed-result + (gethash (list left-or-right cartesian-pose) *ik-solution-cache*))) + (if hashed-result + (values (first hashed-result) (second hashed-result)) + (call-ik-stuff)))) diff --git a/cram_external_interfaces/cram_ik_interface/src/package.lisp b/cram_external_interfaces/cram_ik_interface/src/package.lisp index 95f952713c..fa08e54bd9 100644 --- a/cram_external_interfaces/cram_ik_interface/src/package.lisp +++ b/cram_external_interfaces/cram_ik_interface/src/package.lisp @@ -32,4 +32,8 @@ (:use #:common-lisp) (:export ;; ik - #:call-ik-service #:call-ik-service-with-resampling)) + #:call-ik-service + #:call-ik-service-with-resampling + #:find-ik-for + #:find-joint-values-for + #:with-resampling)) diff --git a/cram_external_interfaces/cram_joint_states/cram-joint-states.asd b/cram_external_interfaces/cram_joint_states/cram-joint-states.asd index de9c00baeb..f48b8fb682 100644 --- a/cram_external_interfaces/cram_joint_states/cram-joint-states.asd +++ b/cram_external_interfaces/cram_joint_states/cram-joint-states.asd @@ -35,9 +35,11 @@ roslisp-utilities cl-transforms cram-language ; for fluents + cram-tf sensor_msgs-msg) :components ((:module "src" :components ((:file "package") - (:file "joint-states" :depends-on ("package")))))) + (:file "joint-states" :depends-on ("package")) + (:file "monitoring" :depends-on ("package" "joint-states")))))) diff --git a/cram_external_interfaces/cram_joint_states/package.xml b/cram_external_interfaces/cram_joint_states/package.xml index 6976cecc34..02bac33325 100644 --- a/cram_external_interfaces/cram_joint_states/package.xml +++ b/cram_external_interfaces/cram_joint_states/package.xml @@ -14,5 +14,6 @@ roslisp_utilities cl_transforms cram_language + cram_tf sensor_msgs diff --git a/cram_external_interfaces/cram_joint_states/src/joint-states.lisp b/cram_external_interfaces/cram_joint_states/src/joint-states.lisp index eee51c0993..5f91623ef9 100644 --- a/cram_external_interfaces/cram_joint_states/src/joint-states.lisp +++ b/cram_external_interfaces/cram_joint_states/src/joint-states.lisp @@ -32,26 +32,28 @@ (defvar *joint-state-sub* nil "Subscriber for robot's joint state topic.") -(defvar *joint-state-sub-counter* 0 - "Counter to decrease the frequency of the subscriber callback") - -(defparameter *joint-state-sub-frequency-cut* 100 "in times") +(defparameter *joint-state-frequency* 10.0d0 + "How often to update the fluent in Hz") +(defvar *joint-state-timestamp* 0.0d0 + "Timestamp of the last fluent update in secs.") (defvar *robot-joint-states-msg* (cpl:make-fluent :name :robot-joint-states) "ROS message containing robot's current joint states.") (defun init-joint-state-sub () - "Initializes *joint-state-sub*" - (flet ((joint-state-sub-cb (joint-state-msg) - (incf *joint-state-sub-counter*) - (if (> *joint-state-sub-counter* *joint-state-sub-frequency-cut*) - (progn - (setf *joint-state-sub-counter* 0) - (setf (cpl:value *robot-joint-states-msg*) joint-state-msg))))) - (setf *joint-state-sub* - (roslisp:subscribe "joint_states" - "sensor_msgs/JointState" - #'joint-state-sub-cb)))) + "Initializes *joint-state-sub*, +updating `*robot-joint-states-msg*' with frequency given in `*joint-state-frequency*'." + (let ((update-every-?-secs (the double-float (/ 1.0d0 *joint-state-frequency*)))) + (declare (double-float update-every-?-secs)) + (flet ((joint-state-sub-cb (joint-state-msg) + (when (> (the double-float (- (roslisp:ros-time) *joint-state-timestamp*)) + update-every-?-secs) + (setf *joint-state-timestamp* (the double-float (roslisp:ros-time))) + (setf (cpl:value *robot-joint-states-msg*) joint-state-msg)))) + (setf *joint-state-sub* + (roslisp:subscribe "joint_states" + "sensor_msgs/JointState" + #'joint-state-sub-cb))))) (defun destroy-joint-state-sub () (setf *joint-state-sub* nil)) @@ -132,9 +134,6 @@ as multiple values." (roslisp:msg-slot-value last-joint-state-msg :header) :stamp)))) -(defun normalize-joint-angles (list-of-angles) - (mapcar #'cl-transforms:normalize-angle list-of-angles)) - (defun full-joint-states-as-hash-table (&optional state-fluent) (let ((last-joint-state-msg (cpl:value (or state-fluent *robot-joint-states-msg*)))) diff --git a/cram_external_interfaces/cram_joint_states/src/monitoring.lisp b/cram_external_interfaces/cram_joint_states/src/monitoring.lisp new file mode 100644 index 0000000000..b044da6fb6 --- /dev/null +++ b/cram_external_interfaces/cram_joint_states/src/monitoring.lisp @@ -0,0 +1,44 @@ +;;; +;;; Copyright (c) 2020, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :joints) + +(defun monitor-joint-state (joint-name comparison-function) + (unless joint-name + (setf joint-name "r_gripper_joint")) + (unless comparison-function + (setf comparison-function (lambda (joint-angle) (< joint-angle 0.002)))) + (cpl:wait-for + (cpl:fl-funcall (lambda (joint-state-msg-fluent) + (funcall comparison-function + (car (joints:joint-positions + (list joint-name) + joint-state-msg-fluent)))) + *robot-joint-states-msg*)) + (print "DONE")) diff --git a/cram_external_interfaces/cram_joint_states/src/package.lisp b/cram_external_interfaces/cram_joint_states/src/package.lisp index ba7b313d70..9ffae64b72 100644 --- a/cram_external_interfaces/cram_joint_states/src/package.lisp +++ b/cram_external_interfaces/cram_joint_states/src/package.lisp @@ -42,5 +42,4 @@ #:joint-states #:joint-positions #:joint-velocities - #:normalize-joint-angles #:full-joint-states-as-hash-table)) diff --git a/cram_external_interfaces/cram_nav_pcontroller/src/process-module.lisp b/cram_external_interfaces/cram_nav_pcontroller/src/process-module.lisp index 63189f6fb4..9971f71518 100644 --- a/cram_external_interfaces/cram_nav_pcontroller/src/process-module.lisp +++ b/cram_external_interfaces/cram_nav_pcontroller/src/process-module.lisp @@ -51,7 +51,7 @@ ;; ;; (cl-tf::with-tf-broadcasting ;; ((cl-tf:make-transform-broadcaster) -;; (cl-tf:make-transform-stamped +;; (cl-transforms-stamped:make-transform-stamped ;; "map" ;; "odom_combined" ;; 0.0 diff --git a/cram_external_interfaces/cram_robosherlock/cram-robosherlock.asd b/cram_external_interfaces/cram_robosherlock/cram-robosherlock.asd index dc25d41257..b90fa7762e 100644 --- a/cram_external_interfaces/cram_robosherlock/cram-robosherlock.asd +++ b/cram_external_interfaces/cram_robosherlock/cram-robosherlock.asd @@ -42,7 +42,6 @@ cram-designators cram-process-modules cram-prolog - cram-manipulation-interfaces cram-common-designators cram-simple-actionlib-client ;; robosherlock_msgs-srv diff --git a/cram_external_interfaces/cram_robosherlock/package.xml b/cram_external_interfaces/cram_robosherlock/package.xml index ec08ff0302..ecb7f27897 100644 --- a/cram_external_interfaces/cram_robosherlock/package.xml +++ b/cram_external_interfaces/cram_robosherlock/package.xml @@ -22,7 +22,6 @@ cram_process_modules cram_prolog cram_common_designators - cram_manipulation_interfaces cram_simple_actionlib_client robosherlock_msgs diff --git a/cram_external_interfaces/cram_robosherlock/src/package.lisp b/cram_external_interfaces/cram_robosherlock/src/package.lisp index 3d8fc9988b..5a17a501a1 100644 --- a/cram_external_interfaces/cram_robosherlock/src/package.lisp +++ b/cram_external_interfaces/cram_robosherlock/src/package.lisp @@ -31,7 +31,7 @@ (defpackage cram-robosherlock (:nicknames #:rs) - (:use #:common-lisp #:cram-manipulation-interfaces) + (:use #:common-lisp) (:export ;; robosherlock-json #:call-robosherlock-service diff --git a/cram_external_interfaces/cram_robosherlock/src/robosherlock-ros.lisp b/cram_external_interfaces/cram_robosherlock/src/robosherlock-ros.lisp index 163d70f7fb..e098ff10c0 100644 --- a/cram_external_interfaces/cram_robosherlock/src/robosherlock-ros.lisp +++ b/cram_external_interfaces/cram_robosherlock/src/robosherlock-ros.lisp @@ -29,11 +29,13 @@ (in-package :rs) +(defparameter *ros-action* "RoboSherlock/query_action") + (defun make-robosherlock-action-client () (actionlib-client:make-simple-action-client 'robosherlock-action - "RoboSherlock/query_action" "robosherlock_msgs/RSQueryAction" - 5)) + *ros-action* "robosherlock_msgs/RSQueryAction" + 120)) (roslisp-utilities:register-ros-init-function make-robosherlock-action-client) @@ -74,27 +76,39 @@ (destructuring-bind (key &rest values) key-value-pair (let ((value (car values))) - ;; below are the only keys supported by RS at the moment - ;; TODO: make sure that an already perceived object doesn't get reperceived with its original SHAPE and SIZE... + ;; below are the only keys supported by RS atm (if (or (eql key :type) (eql key :shape) (eql key :color) (eql key :location) - (eql key :size)) + (eql key :size) + (eql key :material)) (list key - (etypecase value ; RS is only case-sensitive on "TYPE"s - (keyword (remove #\- - (if (eql key :type) - (string-capitalize (symbol-name value)) - (string-downcase (symbol-name value))))) - (string value) - (list (mapcar (lambda (item) - (etypecase item - (keyword - (string-downcase (symbol-name item))) - (string - item))) - value)) + (etypecase value + ;; RS is only case-sensitive on "TYPE"s + (keyword + (remove #\- + (if (eql key :type) + (string-capitalize + (symbol-name + (case value + ;; (:bowl :ikea-red-bowl) + ;; (:cup :ikea-red-cup) + ;; (:spoon :soup-spoon) + (t value)))) + (string-downcase + (symbol-name value))))) + (string + value) + (list + (mapcar (lambda (item) + (etypecase item + (keyword + (string-downcase + (symbol-name item))) + (string + item))) + value)) (desig:location-designator (desig:desig-prop-value (or (desig:desig-prop-value value :on) @@ -118,8 +132,9 @@ (if (string-equal string "") nil (roslisp-utilities:lispify-ros-underscore-name string :keyword)))) - `((:name ,(to-keyword ;; (roslisp:msg-slot-value message :uid) - (format nil "~a-1" (roslisp:msg-slot-value message :type)))) + `((:name ,(to-keyword + ;; (roslisp:msg-slot-value message :uid) + (format nil "~a-1" (roslisp:msg-slot-value message :type)))) (:type ,(to-keyword (roslisp:msg-slot-value message :type))) (:shape ,(map 'list #'to-keyword (roslisp:msg-slot-value message :shape))) (:color ,(map 'list #'to-keyword (roslisp:msg-slot-value message :color))) @@ -139,20 +154,25 @@ :description "couldn't find the object")) (etypecase quantifier (keyword (ecase quantifier - ((:a :an) (parse-result (aref result 0)) - ;; this case should return a lazy list but I don't like them so... - ) + ;; this case should return a lazy list + ;; but I don't like them so... + ((:a :an) (parse-result (aref result 0))) (:the (if (= number-of-objects 1) (parse-result (aref result 0)) (cpl:fail 'common-fail:perception-low-level-failure - :description "There was more than one of THE object"))) + :description (format nil + "There was more ~ + than one of THE ~ + object")))) (:all (map 'list #'parse-result result)))) (number (if (= number-of-objects quantifier) (map 'list #'parse-result result) (cpl:fail 'common-fail:perception-low-level-failure - :description (format nil "perception returned ~a objects ~ - although there should've been ~a" - number-of-objects quantifier)))))))) + :description (format nil "perception returned ~a ~ + objects although there ~ + should've been ~a" + number-of-objects + quantifier)))))))) (defun map-rs-color-to-rgb-list (rs-color) (when (stringp rs-color) @@ -177,7 +197,7 @@ (if cad-model :templatealignment (if (eq type :spoon) - :2destimate + :3destimate ;:2destimate (if obj-part :handleannotator :3destimate))))) @@ -213,14 +233,40 @@ (ecase (second (find :type rs-answer :key #'car)) (:KoellnMuesliKnusperHonigNuss :breakfast-cereal) + (:muesli + :breakfast-cereal) + (:milk + :milk) (:CupEcoOrange :cup) (:EdekaRedBowl :bowl) + (:IkeaRedBowl + :bowl) + (:SoupSpoon + :spoon) + (:spoon + :spoon) + (:IkeaRedCup + :cup) + (:bowl + :bowl) + (:cup + :cup) + (:mug + :cup) (:WeideMilchSmall :milk) (:BLUEPLASTICSPOON - :spoon)))) + :spoon) + (:BALEAREINIGUNGSMILCHVITAL + :balea-bottle) + (:DENKMITGESCHIRRREINIGERNATURE + :dish-washer-tabs) + (:GarnierMineralUltraDry + :deodorant) + (:DMRoteBeteSaftBio + :juice-box)))) (setf rs-answer (subst-if `(:type ,cram-type) (lambda (x) @@ -241,8 +287,11 @@ ;; (find :color keyword-key-value-pairs-list :key #'car)) ;; (setf rs-answer (remove :color rs-answer :key #'car))) (setf rs-answer (remove :color rs-answer :key #'car)) ; <- if we don't do this - ; might end up asking about mutliple colors + ; might end up asking about mutliple colors + (setf rs-answer (remove :material rs-answer :key #'car)) ; <- if we don't do this + ; might end up asking about different materials (setf rs-answer (remove :shape rs-answer :key #'car)); <- SHAPE comes from original query + (setf rs-answer (remove :size rs-answer :key #'car)) ; <- don't care about size ;; (when (and (find :pose rs-answer :key #'car) ;; (find :pose keyword-key-value-pairs-list :key #'car)) ;; (remove :pose keyword-key-value-pairs-list :key #'car)) diff --git a/cram_external_interfaces/kdl_ik_service/README.md b/cram_external_interfaces/kdl_ik_service/README.md new file mode 100644 index 0000000000..4a30abfee4 --- /dev/null +++ b/cram_external_interfaces/kdl_ik_service/README.md @@ -0,0 +1,106 @@ +# KDL_IK_SERVICE + +Service to solve the Inverse Kinematics of the robot joint states from CRAM. + +The service can take in the base link and the tip link of the robotic appendage to be moved, the goal position of the tip link with respect to the base link and the current state of all the non-fixed joints between the base link and tip-link. + +### Format: +The service takes in requests in the form of *moveit_msgs/GetPositionIK*. For the full format structure, call the following command from the terminal: +```rossrv show moveit_msgs/GetPositionIK ``` +While not all the arguments are mandatory, it is essential to provide the ones marked below for the service to work +``` +ik_request: + pose_stamped: + header: + frame_id: '' + pose: + position: + x: + y: + z: + orientation: + x: + y: + z: + w: + ik_link_name: '' +``` +*Note: Replace the values in the angluar brackets(<>) with the actual values for testing* + +### Example: +Let's try this using the boxy robot. Bring up the boxy URDF and the IK service using the command +```roslaunch cram_boxy_assembly_demo sandbox.launch``` +in the terminal. + +We will try to move the left arm including the torso joint. Thus our base link is *base_footprint* and our tip link is *left_arm_7_link* + +Our goal pose is : +* position (x: 1.1285, y: 0.0999, z: 1.3212) +* orientation quaternion (x: 1, y: 0, z: 0, w: 0) +in the frame *base_footprint* + +Plug in the values as per the format provided above and invoke the service call in a fresh terminal window as shown below: +``` +rosservice call /kdl_ik_service/get_ik " +ik_request: + pose_stamped: + header: + frame_id: 'base_footprint' + pose: + position: + x: 1.285 + y: 0.0999 + z: 1.3212 + orientation: + x: 1 + y: 0 + z: 0 + w: 0 + ik_link_name: 'left_arm_7_link' +" +``` + +A response would be provided in the command line inlcluding the IK solution. + +#### Providing the seed state: +Since no joint state is provided for the IK solver in the previous situation, it is assumed that all the joint values are at 0. + +To provide the seed state of the robot joints along with the input request the input command can be modified as below: +``` +rosservice call /kdl_ik_service/get_ik " +ik_request: + robot_state: + joint_state: + name: + ['triangle_base_joint', + 'left_arm_0_joint', + 'left_arm_1_joint', + 'left_arm_2_joint', + 'left_arm_3_joint', + 'left_arm_4_joint', + 'left_arm_5_joint', + 'left_arm_6_joint'] + position: + [0, -1.858, 0.70751, 0.9614, -2.5922, -2.5922, -1.94065, 2] + pose_stamped: + header: + frame_id: 'base_footprint' + pose: + position: + x: 1.285 + y: 0.0999 + z: 1.3212 + orientation: + x: 1 + y: 0 + z: 0 + w: 0 + ik_link_name: 'left_arm_7_link' +" +``` +* The values under ```ik_request['robot_state']['joint_state']['position']``` are the values of the __non-fixed joints__ starting from the *base_footprint*. The values are ordered and read sequentially. +* The names under ```ik_request['robot_state']['joint_state']['name']``` are the names of the __non-fixed joints__ starting from *base_footprint* in order, and corresponds to the respective joint values. It is optional and is not used to calculate the IK, but is helpful in organizing the results. + +```lisp +Note: The results obtained are sensitive to the input seed state. If you get any invalid result with the existing seed state, try applying 0 as the seed state +``` \ No newline at end of file diff --git a/cram_external_interfaces/kdl_ik_service/launch/kdl_ik.launch b/cram_external_interfaces/kdl_ik_service/launch/kdl_ik.launch index 877ceb2116..cd83044f94 100644 --- a/cram_external_interfaces/kdl_ik_service/launch/kdl_ik.launch +++ b/cram_external_interfaces/kdl_ik_service/launch/kdl_ik.launch @@ -1,3 +1,5 @@ + + diff --git a/cram_external_interfaces/kdl_ik_service/scripts/start_ros_server.py b/cram_external_interfaces/kdl_ik_service/scripts/start_ros_server.py index d746d95251..4c9f9b7e05 100755 --- a/cram_external_interfaces/kdl_ik_service/scripts/start_ros_server.py +++ b/cram_external_interfaces/kdl_ik_service/scripts/start_ros_server.py @@ -8,11 +8,13 @@ def callback(request): # print "Got request %s"%(request) + debug_mode = rospy.get_param("ik_debug", False) + ik_logger = Logger(debug_mode) response = moveit_msgs.srv.GetPositionIKResponse() end_effector_link = request.ik_request.ik_link_name - print end_effector_link + ik_logger.log(end_effector_link) pose_stamped = request.ik_request.pose_stamped transform_stamped = geometry_msgs.msg.TransformStamped @@ -24,27 +26,27 @@ def callback(request): transform_stamped.transform.translation.y = pose_stamped.pose.position.y transform_stamped.transform.translation.z = pose_stamped.pose.position.z transform_stamped.transform.rotation = pose_stamped.pose.orientation - print transform_stamped + ik_logger.log(transform_stamped) base_link = transform_stamped.header.frame_id - print base_link + ik_logger.log(base_link) joint_state = request.ik_request.robot_state.joint_state - print joint_state + ik_logger.log(joint_state) timeout = request.ik_request.timeout - print timeout + ik_logger.log(timeout) response.solution.joint_state = joint_state - new_joint_state_vector, success = kdl_ik_service.ik.calculate_ik(base_link, end_effector_link, joint_state.position, transform_stamped) - print new_joint_state_vector + new_joint_state_vector, success = kdl_ik_service.ik.calculate_ik(base_link, end_effector_link, joint_state.position, transform_stamped, ik_logger.log) + ik_logger.log(new_joint_state_vector) response.solution.joint_state.position = new_joint_state_vector if success: response.error_code.val = response.error_code.SUCCESS else: response.error_code.val = response.error_code.NO_IK_SOLUTION - print response + ik_logger.log(response) return response @@ -55,5 +57,14 @@ def server_main(): rospy.spin() +class Logger(object): + def __init__(self, display_output=False): + self.display_output = display_output + + def log(self, line): + if self.display_output: + print line + + if __name__ == "__main__": server_main() diff --git a/cram_external_interfaces/kdl_ik_service/src/kdl_ik_service/ik.py b/cram_external_interfaces/kdl_ik_service/src/kdl_ik_service/ik.py index 7535e66100..d8cd27ef46 100644 --- a/cram_external_interfaces/kdl_ik_service/src/kdl_ik_service/ik.py +++ b/cram_external_interfaces/kdl_ik_service/src/kdl_ik_service/ik.py @@ -5,9 +5,33 @@ import tf2_kdl import math +# ======================== Hacks (TBF) =============================================================== +def hacky_urdf_parser_fix(urdf_str): + """ + Simon's function to get rid of transmission tags in the URDF. + The urdf_parser_py parser really doesn't like it when transmission XML nodes + don't have a hardwareInterface tag, which our transmissions of Boxy don't have. + So just throw those guys the hell out of the URDF string... + """ + # TODO this function is inefficient but the tested urdfs's aren't big enough for it to be a problem + fixed_urdf = '' + delete = False + black_list = ['transmission', 'gazebo'] + black_open = ['<{}'.format(x) for x in black_list] + black_close = [' 0: + delete = True + if len([x for x in black_close if x in line]) > 0: + delete = False + continue + if not delete: + fixed_urdf += line + '\n' + return fixed_urdf + # ================================= API =================================================== -def calculate_ik(base_link, tip_link, seed_joint_state, goal_transform_geometry_msg): +def calculate_ik(base_link, tip_link, seed_joint_state, goal_transform_geometry_msg, log_fun): """ Calculates the Inverse Kinematics from base_link to tip_link according to the given goal_transform_geometry_msg. The initial joint states would be considered from seed_joint_state. @@ -16,12 +40,13 @@ def calculate_ik(base_link, tip_link, seed_joint_state, goal_transform_geometry_ tip_link eg. - "left_arm_7_link" or "right_arm_7_link" """ robot_urdf_string = rospy.get_param('robot_description') - urdf_obj = urdf_parser_py.urdf.URDF.from_xml_string(robot_urdf_string) + robot_urdf_string_fixed = hacky_urdf_parser_fix(robot_urdf_string) + urdf_obj = urdf_parser_py.urdf.URDF.from_xml_string(robot_urdf_string_fixed) _, kdl_tree = kdl_parser_py.urdf.treeFromUrdfModel(urdf_obj) kdl_chain = kdl_tree.getChain(base_link, tip_link) num_joints = kdl_chain.getNrOfJoints() - print "number of joints: " + str(num_joints) + log_fun("number of joints: " + str(num_joints)) # Get Joint limits kdl_joint_limits_min, kdl_joint_limits_max = get_kdl_joint_limit_arrays(kdl_chain, urdf_obj) @@ -40,14 +65,22 @@ def calculate_ik(base_link, tip_link, seed_joint_state, goal_transform_geometry_ result_joint_state_kdl = solve_ik(ik_solver, num_joints, seed_joint_state_kdl, goal_frame_kdl) # check if calculated joint state results in the correct end-effector position using FK - goal_pose_reached = check_ik_result_using_fk(fk_solver, result_joint_state_kdl, goal_frame_kdl) + goal_pose_reached = check_ik_result_using_fk(fk_solver, result_joint_state_kdl, goal_frame_kdl,log_fun) + + if not goal_pose_reached: + # try with joint seed states as 0 + log_fun("Cannot reach goal using the IK solution with the provided seed state. Trying with zeros") + result_joint_state_kdl_with_zero_seed = solve_ik(ik_solver, num_joints, PyKDL.JntArray(num_joints), goal_frame_kdl) + goal_pose_reached = check_ik_result_using_fk(fk_solver, result_joint_state_kdl_with_zero_seed, goal_frame_kdl, + log_fun) + result_joint_state_kdl = result_joint_state_kdl_with_zero_seed if goal_pose_reached else result_joint_state_kdl # check if calculated joint state is within joint limits joints_within_limits = check_result_joints_are_within_limits(num_joints, result_joint_state_kdl, kdl_joint_limits_min, kdl_joint_limits_max) - print "Result Joint State Within Limits: " + str(joints_within_limits) - print "Can Reach Goal Pose With Solution: " + str(goal_pose_reached) + log_fun("Result Joint State Within Limits: " + str(joints_within_limits)) + log_fun("Can Reach Goal Pose With Solution: " + str(goal_pose_reached)) result_joint_state_vector = get_list_from_kdl_jnt_array(num_joints, result_joint_state_kdl) goal_pose_reached_successfully = goal_pose_reached and joints_within_limits @@ -119,17 +152,17 @@ def solve_ik(ik_solver, num_joints, seed_joint_state_kdl, goal_frame_kdl): return result_joint_state_kdl -def check_ik_result_using_fk(fk_solver, result_joint_state_kdl, goal_frame_kdl): +def check_ik_result_using_fk(fk_solver, result_joint_state_kdl, goal_frame_kdl, log_fun): fk_frame_kdl = PyKDL.Frame() fk_solver.JntToCart(result_joint_state_kdl, fk_frame_kdl) distance_vec = PyKDL.diff(fk_frame_kdl.p, goal_frame_kdl.p) norm = math.sqrt(PyKDL.dot(distance_vec, distance_vec)) - print "distance norm: " + str(norm) + log_fun("distance norm: " + str(norm)) relative_rotation = fk_frame_kdl.M.Inverse() * goal_frame_kdl.M distance_angle, _ = relative_rotation.GetRotAngle() - print "distance angle: " + str(distance_angle) + log_fun("distance angle: " + str(distance_angle)) goal_pose_reached = (norm < 0.005) and (abs(distance_angle) < 0.1) return goal_pose_reached diff --git a/cram_hsrb/README.md b/cram_hsrb/README.md new file mode 100644 index 0000000000..1dcfc0ba3f --- /dev/null +++ b/cram_hsrb/README.md @@ -0,0 +1,18 @@ + +### cram_hsrb + +HSR-specific code, including CRAM simulation-related code, demo code, +and, in future, HSR hardware-specific code. + +*What will you need to use cram_hsrb:* +[1.Toyota Research Institue HSR description](https://github.com/ToyotaResearchInstitute/hsr_description) + +[2.Toyota Research Institue HSR meshes](https://github.com/ToyotaResearchInstitute/hsr_meshes) + +*To start the demo you will need to:* + +`roslaunch cram_hsrb_pick_demo sandbox.launch` + +Load the package **cram_hsrb_pick_demo** + +You can start the demo with: `(demo::spawn-pickup-cylinder-air)` diff --git a/cram_pr2/cram_urdf_bringup/CMakeLists.txt b/cram_hsrb/cram_hsrb/CMakeLists.txt similarity index 60% rename from cram_pr2/cram_urdf_bringup/CMakeLists.txt rename to cram_hsrb/cram_hsrb/CMakeLists.txt index 2c091a1130..19174955be 100644 --- a/cram_pr2/cram_urdf_bringup/CMakeLists.txt +++ b/cram_hsrb/cram_hsrb/CMakeLists.txt @@ -1,4 +1,4 @@ cmake_minimum_required(VERSION 2.8.3) -project(cram_urdf_bringup) +project(cram_hsrb) find_package(catkin REQUIRED) -catkin_package() +catkin_metapackage() diff --git a/cram_hsrb/cram_hsrb/package.xml b/cram_hsrb/cram_hsrb/package.xml new file mode 100644 index 0000000000..2156000480 --- /dev/null +++ b/cram_hsrb/cram_hsrb/package.xml @@ -0,0 +1,21 @@ + + cram_hsrb + 0.7.0 + Metapackage for hsrb robot's code + Vanessa Hassouna + Gayane Kazhoyan + BSD + + http://cram-system.org + https://github.com/cram2/cram_common/issues + https://github.com/cram2/cram_common + + catkin + + cram_hsrb_description + cram_hsrb_pick_demo + + + + + diff --git a/cram_boxy/cram_boxy_projection/CMakeLists.txt b/cram_hsrb/cram_hsrb_description/CMakeLists.txt similarity index 73% rename from cram_boxy/cram_boxy_projection/CMakeLists.txt rename to cram_hsrb/cram_hsrb_description/CMakeLists.txt index 174dc0a635..68870db4d7 100644 --- a/cram_boxy/cram_boxy_projection/CMakeLists.txt +++ b/cram_hsrb/cram_hsrb_description/CMakeLists.txt @@ -1,4 +1,4 @@ cmake_minimum_required(VERSION 2.8.3) -project(cram_boxy_projection) +project(cram_hsrb_description) find_package(catkin REQUIRED) catkin_package() diff --git a/cram_hsrb/cram_hsrb_description/cram-hsrb-description.asd b/cram_hsrb/cram_hsrb_description/cram-hsrb-description.asd new file mode 100644 index 0000000000..4e17234ff4 --- /dev/null +++ b/cram_hsrb/cram_hsrb_description/cram-hsrb-description.asd @@ -0,0 +1,43 @@ +;;; Copyright (c) 2019, Gayane Kazhoyan +;; 2019, Vanessa Hassouna +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Intelligent Autonomous Systems Group/ +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software +;;; without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(defsystem cram-hsrb-description + :author "Vanessa Hassouna" + :license "BSD" + + :depends-on (cram-prolog + cram-location-costmap ; to specify robot-specific costmap metadata + cram-robot-interfaces) + + :components + ((:module "src" + :components + ((:file "package") + (:file "general-knowledge" :depends-on ("package")) + (:file "arms" :depends-on ("package")))))) diff --git a/cram_hsrb/cram_hsrb_description/package.xml b/cram_hsrb/cram_hsrb_description/package.xml new file mode 100644 index 0000000000..d5e5ac66f2 --- /dev/null +++ b/cram_hsrb/cram_hsrb_description/package.xml @@ -0,0 +1,16 @@ + + cram_hsrb_description + 0.7.0 + + Prolog predicates describing hsrb robot + + Vanessa Hassouna + Gayane Kazhoyan + BSD + + catkin + + cram_prolog + cram_location_costmap + cram_robot_interfaces + diff --git a/cram_hsrb/cram_hsrb_description/src/arms.lisp b/cram_hsrb/cram_hsrb_description/src/arms.lisp new file mode 100644 index 0000000000..d842163f03 --- /dev/null +++ b/cram_hsrb/cram_hsrb_description/src/arms.lisp @@ -0,0 +1,105 @@ +;;; +;;; Copyright (c) 2019, Vanessa Hassouna +;;; Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :cram-hsrb-description) + +(defparameter *tcp-in-ee-pose* + (cl-transforms:make-pose + (cl-transforms:make-3d-vector 0.0d0 0.0d0 0.23090001999999998d0) + (cl-transforms:make-quaternion 0.0d0 + 0.0d0 + 0.7071067811865475d0 + 0.7071067811865476d0))) + +(defparameter *standard-to-hsrb-gripper-transform* + (cl-transforms-stamped:make-identity-transform)) + + +(def-fact-group hsrb-arm-facts (arm + arm-joints arm-links + hand-links hand-link hand-finger-link + gripper-joint + gripper-meter-to-joint-multiplier + standard<-particular-gripper-transform + end-effector-link + robot-tool-frame + tcp-in-ee-pose + robot-joint-states) + + (<- (arm :hsrb :left)) + + (<- (arm-joints :hsrb :left ("arm_flex_joint" + "arm_roll_joint" + "wrist_flex_joint" + "wrist_roll_joint"))) + + (<- (arm-links :hsrb :left ("arm_flex_link" + "arm_roll_link" + "wrist_flex_link" + "wrist_roll_link"))) + + (<- (hand-links :hsrb :left ("hand_l_distal_link" + "hand_l_spring_proximal_link" + "hand_palm_link" + "hand_r_distal_link" + "hand_r_spring_proximal_link"))) + + (<- (hand-link :hsrb :left ?link) + (bound ?link) + (lisp-fun search "hand" ?link ?pos) + (lisp-pred identity ?pos)) + + (<- (hand-finger-link :hsrb ?arm ?link) + (bound ?link) + (hand-link :hsrb ?arm ?link) + (lisp-fun search "palm" ?link ?pos) + (not (lisp-pred identity ?pos))) + + (<- (gripper-joint :hsrb :left "hand_motor_joint")) + + (<- (gripper-meter-to-joint-multiplier :hsrb 1.0)) + + (<- (standard<-particular-gripper-transform :hsrb ?transform) + (symbol-value *standard-to-hsrb-gripper-transform* ?transform)) + + (<- (end-effector-link :hsrb :left "wrist_roll_link")) + + (<- (robot-tool-frame :hsrb :left "gripper_tool_frame")) + + (<- (tcp-in-ee-pose :hsrb ?pose) + (symbol-value *tcp-in-ee-pose* ?pose)) + + (<- (robot-joint-states :hsrb :arm :left :carry + (("arm_flex_joint" 0) + ("arm_roll_joint" 1.5) + ("wrist_flex_joint" -1.85) + ("wrist_roll_joint" 0)))) + (<- (robot-joint-states :hsrb :arm :left :park ?joint-states) + (robot-joint-states :hsrb :arm :left :carry ?joint-states))) diff --git a/cram_hsrb/cram_hsrb_description/src/general-knowledge.lisp b/cram_hsrb/cram_hsrb_description/src/general-knowledge.lisp new file mode 100644 index 0000000000..0714947b51 --- /dev/null +++ b/cram_hsrb/cram_hsrb_description/src/general-knowledge.lisp @@ -0,0 +1,82 @@ +;;; +;;; Copyright (c) 2019, Vanessa Hassouna +;;; Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :hsrb-descr) + +(defparameter *forward-looking-position-in-base-frame* + (cl-transforms:make-3d-vector 10.0 0.0 1.5)) + +(def-fact-group hsrb-metadata (robot-odom-frame + robot-base-frame robot-torso-link-joint + arm + camera-frame + camera-horizontal-angle camera-vertical-angle + robot-neck-links robot-neck-joints + robot-joint-states robot-pose) + + (<- (robot-odom-frame :hsrb "odom")) + (<- (robot-base-frame :hsrb "base_footprint")) + (<- (robot-torso-link-joint :hsrb "arm_lift_link" "arm_lift_joint")) + + (<- (camera-frame :hsrb "head_center_camera_frame")) + (<- (camera-frame :hsrb "head_rgbd_sensor_link")) + + ;; These are values taken from the Kinect's wikipedia page for the 360 variant + (<- (camera-horizontal-angle :hsrb 0.99483)) + (<- (camera-vertical-angle :hsrb 0.75049)) + + (<- (robot-neck-links :hsrb "head_pan_link" "head_tilt_link")) + (<- (robot-neck-joints :hsrb "head_pan_joint" "head_tilt_joint")) + + (<- (robot-joint-states :hsrb :neck ?_ :forward ((?pan_joint 0.0) (?tilt_joint 0.0))) + (robot-neck-joints :hsrb ?pan_joint ?tilt_joint)) + + (<- (robot-pose :hsrb :neck ?_ :forward ?pose-stamped) + (robot-base-frame :hsrb ?base-frame) + (lisp-fun cl-transforms:make-identity-rotation ?identity-quaternion) + (symbol-value *forward-looking-position-in-base-frame* ?forward-point) + (lisp-fun cl-transforms-stamped:make-pose-stamped + ?base-frame 0.0 ?forward-point ?identity-quaternion + ?pose-stamped))) + +(def-fact-group location-costmap-metadata (costmap:costmap-padding + costmap:costmap-manipulation-padding + costmap:costmap-in-reach-distance + costmap:costmap-reach-minimal-distance + costmap:orientation-samples + costmap:orientation-sample-step + costmap:visibility-costmap-size) + (<- (costmap:costmap-padding :hsrb 0.2)) + (<- (costmap:costmap-manipulation-padding :hsrb 0.3)) + (<- (costmap:costmap-in-reach-distance :hsrb 0.5)) + (<- (costmap:costmap-reach-minimal-distance :hsrb 0.2)) + (<- (costmap:orientation-samples :hsrb 3)) + (<- (costmap:orientation-sample-step :hsrb 0.3)) + (<- (costmap:visibility-costmap-size :hsrb 2))) diff --git a/cram_hsrb/cram_hsrb_description/src/package.lisp b/cram_hsrb/cram_hsrb_description/src/package.lisp new file mode 100644 index 0000000000..0061783061 --- /dev/null +++ b/cram_hsrb/cram_hsrb_description/src/package.lisp @@ -0,0 +1,35 @@ +;;; +;;; Copyright (c) 2019, Gayane Kazhoyan +;; Vanessa Hassouna +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :cl-user) + +(defpackage cram-hsrb-description + (:nicknames #:hsrb-descr) + (:use #:common-lisp #:cram-prolog #:cram-robot-interfaces)) diff --git a/cram_knowrob/cram_cloud_logger/cram-cloud-logger.asd b/cram_knowrob/cram_cloud_logger/cram-cloud-logger.asd index 2c4004954a..fdf2c40572 100644 --- a/cram_knowrob/cram_cloud_logger/cram-cloud-logger.asd +++ b/cram_knowrob/cram_cloud_logger/cram-cloud-logger.asd @@ -8,18 +8,22 @@ :cram-utilities :cram-manipulation-interfaces :cram-executive - :cram-projection) + :cram-projection + :cram-physics-utils) :components - ((:module "src" + ((:module "src" :components ((:file "package") + (:module "mapper" + :components + ((:file "cram-2-knowrob-mapper"))) (:file "utils" :depends-on ("package")) + (:file "failure-handler" :depends-on ("mapper")) (:file "cloud-logger-client" :depends-on ("package" "utils")) - (:file "object-interface" :depends-on ("package" "utils" "cloud-logger-client")) (:file "cloud-logger-query-handler" :depends-on ("package" "cloud-logger-client" "utils")) (:file "prolog-query-handler" :depends-on ("package" "utils" "cloud-logger-client")) (:file "knowrob-action-name-handler" :depends-on ("package" "utils")) (:file "logging-functions" :depends-on ("package" "cloud-logger-query-handler")) (:file "action-parameter-handler" :depends-on ("package" "logging-functions")) - (:file "utils-for-perform" :depends-on ("package" "cloud-logger-query-handler" "prolog-query-handler" "object-interface" "knowrob-action-name-handler" "action-parameter-handler" "utils")) - (:file "failure-handler" :depends-on ("package" "utils-for-perform")))))) + (:file "utils-for-perform" :depends-on ("package" "cloud-logger-query-handler" "prolog-query-handler" "knowrob-action-name-handler" "action-parameter-handler" "utils" "failure-handler")) + (:file "object-interface" :depends-on ("package" "utils" "cloud-logger-client" "utils-for-perform")))))) diff --git a/cram_knowrob/cram_cloud_logger/src/action-parameter-handler.lisp b/cram_knowrob/cram_cloud_logger/src/action-parameter-handler.lisp index ff1bc3e1c2..947ec08d04 100644 --- a/cram_knowrob/cram_cloud_logger/src/action-parameter-handler.lisp +++ b/cram_knowrob/cram_cloud_logger/src/action-parameter-handler.lisp @@ -11,10 +11,11 @@ (let ((logging-function (get-logging-function-for-action-designator-parameter parameter-name)) (logging-args (list action-designator-logging-id parameter-value))) (execute-logging-function-with-arguments - logging-function logging-args)))) + action-designator-logging-id parameter-name logging-function logging-args)))) action-designator-parameters)) -(defun execute-logging-function-with-arguments - (logging-parameter-function logging-parameter-function-arguments) - (when logging-parameter-function - (apply logging-parameter-function logging-parameter-function-arguments))) +(defun execute-logging-function-with-arguments (action-designator-logging-id parameter-name logging-parameter-function logging-parameter-function-arguments) + (if logging-parameter-function + (apply logging-parameter-function logging-parameter-function-arguments) + (let ((parameter-name-str (write-to-string parameter-name))) + (when (string-not-equal ":TYPE" parameter-name-str) (send-comment action-designator-logging-id (concatenate 'string "Unknown Parameter: " parameter-name-str " -####- " (write-to-string (cadr logging-parameter-function-arguments)))))))) diff --git a/cram_knowrob/cram_cloud_logger/src/cloud-logger-client.lisp b/cram_knowrob/cram_cloud_logger/src/cloud-logger-client.lisp index 1349a84aa8..71947f1268 100644 --- a/cram_knowrob/cram_cloud_logger/src/cloud-logger-client.lisp +++ b/cram_knowrob/cram_cloud_logger/src/cloud-logger-client.lisp @@ -3,11 +3,14 @@ (defparameter *cloud-logger-client* nil) (defparameter *is-client-connected* nil) -(defparameter *is-logging-enabled* nil) +;;(defparameter *is-logging-enabled* nil) +(defvar *my-mutex* (sb-thread:make-mutex)) ;; Sebastian's setup on his PC (defparameter *host* "'https://localhost'") +;;(defparameter *host* "'https://192.168.101.42'") (defparameter *cert-path* "'/home/koralewski/Desktop/localhost.pem'") +;;(defparameter *cert-path* "'/home/ease/asil.pem'") ;;LOCAL PC ;;(defparameter *api-key* "'0nYZRYs5AxDeZAWhWBKYmLF1IJCtRM7gkYTqSV3Noyhl5V3yyxzSaA7Nxi8FFQsC'") ;;AI PC @@ -15,6 +18,7 @@ ;;(defparameter *api-key* "'DiI6fqr5I2ObbeMyI9cDyzjoEHjfz3E48O45M3bKAZh465PUvNtOPB9v8xodMCQT'") ;; Gaya's token on Asil's PC +;;(defparameter *api-key* "'MxtU9V2cdstw3ocKXbicBGp7fAeLNxjIvcmY4CJV96DeZd7obfgvw0mR3X5j8Yrz'") ;; Asil's host ;;(defparameter *host* "'https://192.168.101.42'") ;; Asil's certificate on ease@pr2a @@ -73,7 +77,8 @@ (defun send-prolog-query-1 (prolog-query) ;;(print prolog-query) (when *is-logging-enabled* - (handler-case + (sb-thread:with-mutex (*my-mutex*) + (handler-case (let ((query-id (get-id-from-query-result (json-prolog:prolog-simple-1 (concatenate 'string "send_prolog_query('" @@ -83,7 +88,7 @@ query-result)) (simple-error (e) (roslisp:ros-error (ccl) "error in json prolog: ~a~%" e) - (cpl:fail 'ccl-failure :format-control "Error in json prolog."))))) + (cpl:fail 'ccl-failure :format-control "Error in json prolog.")))))) (defun send-prolog-query (prolog-query) (json-prolog:prolog-simple diff --git a/cram_knowrob/cram_cloud_logger/src/cloud-logger-query-handler.lisp b/cram_knowrob/cram_cloud_logger/src/cloud-logger-query-handler.lisp index 097112fcb4..317eac47c0 100644 --- a/cram_knowrob/cram_cloud_logger/src/cloud-logger-query-handler.lisp +++ b/cram_knowrob/cram_cloud_logger/src/cloud-logger-query-handler.lisp @@ -1,5 +1,126 @@ (in-package :ccl) +(defun get-parent-folder-path() + (namestring (physics-utils:parse-uri "package://cram_cloud_logger/src"))) + +(defun send-load-neem-generation-interface () + (let ((path-to-interface-file (concatenate 'string "'"(get-parent-folder-path) "/neem-interface.pl'"))) + (ccl::send-query-1-without-result "ensure_loaded" path-to-interface-file))) + +(defun init-logging () + (send-load-neem-generation-interface)) + ;;(ccl::send-query-1-without-result "ros_logger_start" "")) + +(defun finish-logging () + (print "Finished")) + ;;(ccl::send-query-1-without-result "ros_logger_stop" "")) + +(defun get-grasp-type-lookup-table() + (let ((lookup-table (make-hash-table :test 'equal))) + (setf (gethash ":TOP" lookup-table) "TopGrasp") + (setf (gethash ":TOP-FRONT" lookup-table) "TopFrontGrasp") + (setf (gethash ":TOP-LEFT" lookup-table) "TopLeftGrasp") + (setf (gethash ":TOP-RIGHT" lookup-table) "TopRightGrasp") + (setf (gethash ":BOTTOM" lookup-table) "BottomGrasp") + (setf (gethash ":LEFT" lookup-table) "LeftGrasp") + (setf (gethash ":LEFT-SIDE" lookup-table) "LeftSideGrasp") + (setf (gethash ":RIGHT-SIDE" lookup-table) "RightSideGrasp") + (setf (gethash ":RIGHT" lookup-table) "RightGrasp") + (setf (gethash ":FRONT" lookup-table) "FrontGrasp") + (setf (gethash ":BACK" lookup-table) "BackGrasp") + lookup-table)) + +(defparameter *grasp-type-lookup-table* (get-grasp-type-lookup-table)) + +(defun start-situation (situation-uri) + (attach-time-to-situation "mem_event_begin" situation-uri)) + +(defun stop-situation (situation-uri) + (attach-time-to-situation "mem_event_end" situation-uri)) + +(defun attach-time-to-situation (predicate-name situation-uri) + (send-query-1-without-result predicate-name situation-uri)) + +(defun attach-event-to-situation (event-prolog-url situation-prolog-url) + (get-url-from-send-query-1 "SubAction" "add_subaction_with_task" situation-prolog-url "SubAction" event-prolog-url)) + +(defun send-belief-perceived-at (object-type transform object-id) + (send-query-1-without-result "belief_perceived_at" object-type transform object-id) + object-id) + +(defun send-belief-new-object-query (object-type) + (get-url-from-send-query-1 "Object" "belief_new_object" object-type "Object")) + +(defun set-event-status-to-succeeded (event-prolog-url) + (send-query-1-without-result "mem_event_set_succeeded" event-prolog-url)) + +(defun set-event-status-to-failed (event-prolog-url) + (send-query-1-without-result "mem_event_set_failed" event-prolog-url)) + +(defun send-attach-object-as-parameter-to-situation (object-url parameter-type-url event-prolog-url) + (break) + (send-query-1-without-result "add_participant_with_role" event-prolog-url object-url parameter-type-url)) + +(defun set-event-diagnosis (event-prolog-url diagnosis-url) + (send-query-1-without-result "mem_event_add_diagnosis" event-prolog-url diagnosis-url)) + +(defun start-episode () + (when *episode-name* + (progn + (print "Previous episode recording is still running. Stopping the recording ...") + (stop-episode))) + (ccl::clear-detected-objects) + (setf ccl::*episode-name* (get-url-from-send-query-1 "RootAction" "mem_episode_start" "RootAction"))) + +(defun stop-episode () + (send-query-1-without-result "mem_episode_stop" (concatenate 'string "'" (uiop:getenv "KNOWROB_MEMORY_DIR") "'")) + (setf ccl::*episode-name* nil)) + +(defun send-query-1-without-result (query-name &rest query-parameters) + (let ((query (create-query query-name query-parameters))) + (send-query-1 query) + (print "DONE REASONING"))) + +(defun send-query-1 (query) + (print query) + (json-prolog:prolog-simple-1 query)) + +(defun get-url-from-send-query-1 (url-parameter query-name &rest query-parameters) + (let* ((query (create-query query-name query-parameters)) + (query-result (send-query-1 query))) + (when (eq query-result nil) (break)) + (print "GOT-RESULT") + (ccl::get-url-variable-result-as-str-from-json-prolog-result url-parameter query-result))) + +(defun send-comment (action-inst comment) + (send-query-1-without-result "add_comment" action-inst (concatenate 'string "'"comment"'"))) + ;;(print "COMMENT")) + +(defun send-object-action-parameter (action-inst object-designator) + (let* ((object-name (get-designator-property-value-str object-designator :NAME)) + (object-ease-id (get-ease-object-id-of-detected-object-by-name object-name))) + (when object-ease-id + (send-query-1-without-result "add_participant_with_role" action-inst object-ease-id "'http://www.ease-crc.org/ont/SOMA.owl#AffectedObject'")))) + + +(defun send-grasp-action-parameter (action-inst grasp) + (let ((grasp-type (gethash (write-to-string grasp) *grasp-type-lookup-table*))) + (send-parameter action-inst grasp-type))) + +(defun send-parameter(action-inst region-type) + (let ((region-type-url (concatenate 'string "'""http://www.ease-crc.org/ont/SOMA.owl#" region-type "'"))) + (send-query-1-without-result "add_grasping_parameter" action-inst region-type-url))) + + + + + + + + + + +;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; CLOUD LOGGER RELATED STUFF (OLD) ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; (defun send-cram-start-parent-action (owl-action-class task-context start-time prev-action parent-task action-inst) (send-prolog-query-1 @@ -67,13 +188,6 @@ (defun export-belief-state-to-owl (&optional (filename (concatenate 'string "default_belief_state_" (write-to-string (truncate (cram-utilities:current-timestamp))) ".owl"))) (json-prolog:prolog-simple-1 (concatenate 'string "rdf_save(" (concatenate 'string "'/home/ease/logs/" filename "'" "," "[graph('belief_state')])")))) - -(defun send-grasp-action-parameter (action-inst grasp) - (let ((a (convert-to-prolog-str action-inst)) - (b "knowrob:grasp") - (c (create-owl-literal "xsd:string" (convert-to-prolog-str (write-to-string grasp))))) - (send-rdf-query a b c))) - (defun send-task-success (action-inst is-sucessful) (let ((a (convert-to-prolog-str action-inst)) (b "knowrob:taskSuccess") @@ -102,22 +216,22 @@ (defun send-rdf-query (a b c) (send-prolog-query-1 (create-rdf-assert-query a b c))) -(defun send-object-action-parameter (action-inst object-designator) - (let ((object-instance-id (symbol-name (desig:desig-prop-value object-designator :NAME)))) - (when (not (string-equal object-instance-id "nil")) - (progn - (send-rdf-query - (convert-to-prolog-str action-inst) - "knowrob:objectActedOn" - (convert-to-prolog-str object-instance-id))))) +;;(defun send-object-action-parameter (action-inst object-designator) +;; (let ((object-instance-id (symbol-name (desig:desig-prop-value object-designator :NAME)))) +;; (when (not (string-equal object-instance-id "nil")) +;; (progn +;; (send-rdf-query +;; (convert-to-prolog-str action-inst) +;; "knowrob:objectActedOn" +;; (convert-to-prolog-str object-instance-id))))) - (let ((object-type (symbol-name (desig:desig-prop-value object-designator :TYPE)))) - (when (not (string-equal object-type "nil")) - (progn - (send-rdf-query - (convert-to-prolog-str action-inst) - "knowrob:objectType" - (convert-to-prolog-str object-type)))))) +;; (let ((object-type (symbol-name (desig:desig-prop-value object-designator :TYPE)))) +;; (when (not (string-equal object-type "nil")) +;; (progn +;; (send-rdf-query +;; (convert-to-prolog-str action-inst) +;; "knowrob:objectType" +;; (convert-to-prolog-str object-type)))))) @@ -152,7 +266,7 @@ (let ((x (cl-transforms:x 3d-vector)) (y (cl-transforms:y 3d-vector)) (z (cl-transforms:z 3d-vector))) - (concatenate 'string (format nil "~F" x) " " (format nil "~F" y) " " (format nil "~F" z)))) + (concatenate 'string "["(format nil "~F" x) "," (format nil "~F" y) "," (format nil "~F" z)"]"))) (defun send-create-quaternion (quaternion) @@ -160,7 +274,7 @@ (y (cl-transforms:y quaternion)) (z (cl-transforms:z quaternion)) (w (cl-transforms:w quaternion))) - (concatenate 'string (format nil "~F" x) " " (format nil "~F" y) " " (format nil "~F" z) " " (format nil "~F" w)))) + (concatenate 'string "["(format nil "~F" x) "," (format nil "~F" y) "," (format nil "~F" z) "," (format nil "~F" w) "]"))) (defun send-create-transform-pose-stamped (transform-pose) (let ((pose-stamped-instance-id (send-instance-from-class "Pose")) diff --git a/cram_knowrob/cram_cloud_logger/src/failure-handler.lisp b/cram_knowrob/cram_cloud_logger/src/failure-handler.lisp index 5274b5e5dc..0336d355d5 100644 --- a/cram_knowrob/cram_cloud_logger/src/failure-handler.lisp +++ b/cram_knowrob/cram_cloud_logger/src/failure-handler.lisp @@ -1,10 +1,54 @@ (in-package :ccl) -(defmethod cpl:fail :around (&rest args) - (call-next-method) - ;; (if *is-logging-enabled* - ;; (progn - ;; (log-failure (car ccl::*action-parents*) (car args)) - ;; (call-next-method)) - ;; (call-next-method)) - ) +(defun init-failure-mapper () + (let ((failure-mapper (make-instance 'ccl::cram-2-knowrob-mapper)) + (definition + '(("cram-common-failures:low-level-failure" "LowLevelFailure") + ("cram-common-failures:actionlib-action-timed-out" "ActionlibTimeout") + ("cram-common-failures:navigation-high-level-failure" "NavigationHighLevelFailure") + ("cram-common-failures:navigation-goal-in-collision" "NavigationGoalInCollision") + ("cram-common-failures:looking-high-level-failure" "LookingHighLevelFailure") + ("cram-common-failures:object-unreachable" "ObjectUnreachable") + ("cram-common-failures:manipulation-goal-in-collision" "ManipulationGoalInCollision") + ("cram-common-failures:object-unfetchable" "ObjectUnfetchable") + ("cram-common-failures:fetching-failed" "FetchingFailed") + ("cram-common-failures:object-undeliverable" "ObjectUndeliverable") + ("cram-common-failures:delivering-failed" "DeliveringFailed") + ("cram-common-failures:object-nowhere-to-be-found" "ObjectNowhereToBeFound") + ("cram-common-failures:searching-failed" "SearchingFailed") + ("cram-common-failures:environment-manipulation-impossible" "EnvironmentManipulationImpossible") + ("cram-common-failures:environment-unreachable" "EnvironmentUnreachable") + ("cram-common-failures:manipulation-low-level-failure" "ManipulationLowLevelFailure") + ("cram-common-failures:gripper-low-level-failure" "GripperLowLevelFailure") + ("cram-common-failures:gripper-closed-completely" "GripperClosedCompletely") + ("cram-common-failures:gripper-goal-not-reached" "GripperGoalNotReached") + ("cram-common-failures:manipulation-goal-not-reached" "ManipulationGoalNotReached") + ("cram-common-failures:manipulation-pose-unreachable" "ManipulationPoseUnreachable") + ("cram-common-failures:navigation-low-level-failure" "NavigationLowLevelFailure") + ("cram-common-failures:navigation-pose-unreachable" "NavigationPoseUnreachable") + ("cram-common-failures:navigation-goal-not-reached" "NavigationGoalNotReached") + ("cram-common-failures:perception-low-level-failure" "PerceptionLowLevelFailure") + ("cram-common-failures:perception-object-not-found" "PerceptionObjectNotFound") + ("cram-common-failures:perception-object-not-in-world" "PerceptionObjectNotInWorld") + ("cram-common-failures:ptu-low-level-failure" "PTULowLevelFailure") + ("cram-common-failures:ptu-goal-unreachable" "PTUGoalNotReached") + ("cram-common-failures:ptu-goal-not-reached" "PTUGoalUnreachable") + ("cram-common-failures:torso-low-level-failure" "TorsoLowLevelFailure") + ("cram-common-failures:torso-goal-unreachable" "TorsoGoalUnreachable") + ("cram-common-failures:torso-goal-not-reached" "TorsoGoalNotReached") + ("cram-designators:designator-error" "DesignatorError") + ("cram-executive:designator-reference-failure" "DesignatorReferenceFailure") + ("cram-executive:designator-goal-parsing-failure" "DesignatorGoalParsingFailure")))) + (ccl::add-definition-to-mapper definition failure-mapper) + failure-mapper)) + +(defparameter *failure-mapper* (init-failure-mapper)) + +(defun get-failure-uri (cram-failure-name) + (concatenate 'string "'http://www.ease-crc.org/ont/cram_failures.owl#CRAM" (get-failure-name cram-failure-name) "'")) + +(defun get-failure-name (cram-failure-name) + (let* ((lower-cram-failure-name (string-downcase cram-failure-name)) + (knowrob-failure-name (get-definition-from-mapper lower-cram-failure-name *failure-mapper*))) + (when (not knowrob-failure-name) (setf knowrob-failure-name "Failure")) + knowrob-failure-name)) diff --git a/cram_knowrob/cram_cloud_logger/src/knowrob-action-name-handler.lisp b/cram_knowrob/cram_cloud_logger/src/knowrob-action-name-handler.lisp index 1c3f7719e8..496ee9c760 100644 --- a/cram_knowrob/cram_cloud_logger/src/knowrob-action-name-handler.lisp +++ b/cram_knowrob/cram_cloud_logger/src/knowrob-action-name-handler.lisp @@ -1,64 +1,45 @@ (in-package :ccl) +(defun init-action-name-mapper () + (let ((action-name-mapper (make-instance 'ccl::cram-2-knowrob-mapper)) + (definition + '(("reaching" "Reaching") + ("retracting" "Retracting") + ("lifting" "Lifting") + ("putting" "Lowering") + ("setting-gripper" "Positioning") + ("positioning-arm" "Positioning") + ("opening" "Opening") + ("opening-gripper" "Opening") + ("closing" "Closing") + ("detecting" "Detecting") + ("placing" "Placing") + ("picking-up" "PickingUp") + ("releasing" "Releasing") + ("grasping" "Grasping") + ("gripping" "Grasping") + ("looking" "LookingAt") + ("going" "MovingTo") + ("navigating" "Navigating") + ("searching" "LookingFor") + ("fetching" "PickingUp") + ("delivering" "PuttingDown") + ("transporting" "Transporting") + ("turning-towards" "LookingFor") + ("sealing" "Sealing") + ("pushing" "Pushing") + ("pulling" "Pulling") + ("accessing" "Accessing")))) + (ccl::add-definition-to-mapper definition action-name-mapper) + action-name-mapper)) + +(defparameter *action-name-mapper* (init-action-name-mapper)) + (defun get-knowrob-action-name-uri (cram-action-name designator) - (concatenate 'string "knowrob:" (convert-to-prolog-str (get-knowrob-action-name cram-action-name designator)))) + (concatenate 'string "'http://www.ease-crc.org/ont/EASE-ACT.owl#" (get-knowrob-action-name cram-action-name designator) "'")) (defun get-knowrob-action-name (cram-action-name designator) - (let ((knowrob-action-name cram-action-name)) - (cond ((string-equal cram-action-name "reaching") - (setf knowrob-action-name "Reaching")) - ((string-equal cram-action-name "retracting") - (setf knowrob-action-name "Retracting")) - ((string-equal cram-action-name "lifting") - (setf knowrob-action-name "LiftingAnArm")) - ((string-equal cram-action-name "putting") - (setf knowrob-action-name "LoweringAnArm")) - ((string-equal cram-action-name "setting-gripper") - (setf knowrob-action-name "SettingAGripper")) - ((string-equal cram-action-name "opening") - (setf knowrob-action-name "OpeningAGripper")) - ((string-equal cram-action-name "closing") - (setf knowrob-action-name "ClosingAGripper")) - ((string-equal cram-action-name "detecting") - (setf knowrob-action-name "VisualPerception")) - ((string-equal cram-action-name "placing") - (setf knowrob-action-name "ReleasingGraspOfSomething")) - ((string-equal cram-action-name "picking-up") - (setf knowrob-action-name "AcquireGraspOfSomething")) - ((string-equal cram-action-name "releasing") - (setf knowrob-action-name "OpeningAGripper")) - ((string-equal cram-action-name "gripping") - (setf knowrob-action-name "ClosingAGripper")) - ((string-equal cram-action-name "looking") - (setf knowrob-action-name "LookingAtLocation")) - ((string-equal cram-action-name "going") - (setf knowrob-action-name "BaseMovement")) - ((string-equal cram-action-name "navigating") - (setf knowrob-action-name "MovingToLocation")) - ((string-equal cram-action-name "searching") - (setf knowrob-action-name "LookingForSomething")) - ((string-equal cram-action-name "fetching") - (setf knowrob-action-name "PickingUpAnObject")) - ((string-equal cram-action-name "delivering") - (setf knowrob-action-name "PuttingDownAnObject")) - ((string-equal cram-action-name "Transporting") - (setf knowrob-action-name "FetchAndDeliver")) - ((string-equal cram-action-name "Turning-Towards") - (setf knowrob-action-name "LookingForSomething")) - ((string-equal cram-action-name "SEALING") - (setf knowrob-action-name "MovingToOperate")) - ((string-equal cram-action-name "PUSHING") - (setf knowrob-action-name "Pushing")) - ((string-equal cram-action-name "PULLING") - (setf knowrob-action-name "Pulling")) - ((string-equal cram-action-name "ACCESSING") - (setf knowrob-action-name "MovingToOperate"))) - (if (string-equal knowrob-action-name "OpeningAGripper") - (if (desig:desig-prop-value designator :gripper) - (setf knowrob-action-name "OpeningAGripper") - (setf knowrob-action-name "OpeningADrawer"))) - (if (string-equal knowrob-action-name "ClosingAGripper") - (if (desig:desig-prop-value designator :gripper) - (setf knowrob-action-name "ClosingAGripper") - (setf knowrob-action-name "ClosingADrawer"))) + (let* ((lower-cram-action-name (string-downcase cram-action-name)) + (knowrob-action-name (get-definition-from-mapper lower-cram-action-name *action-name-mapper*))) + (when (not knowrob-action-name) (setf knowrob-action-name "PhysicalTask")) knowrob-action-name)) diff --git a/cram_knowrob/cram_cloud_logger/src/logging-functions.lisp b/cram_knowrob/cram_cloud_logger/src/logging-functions.lisp index ad9f15b421..93e04219ed 100644 --- a/cram_knowrob/cram_cloud_logger/src/logging-functions.lisp +++ b/cram_knowrob/cram_cloud_logger/src/logging-functions.lisp @@ -3,16 +3,17 @@ (defparameter action-designator-parameter-logging-functions (make-hash-table)) (defun define-all-action-designator-parameter-logging-functions () - (add-logging-function-for-action-designator-parameter 'send-effort-action-parameter :effort) - (add-logging-function-for-action-designator-parameter 'send-position-action-parameter :position) + ;;(add-logging-function-for-action-designator-parameter 'send-effort-action-parameter :effort) + ;;(add-logging-function-for-action-designator-parameter 'send-position-action-parameter :position) (add-logging-function-for-action-designator-parameter 'send-object-action-parameter :object) - (add-logging-function-for-action-designator-parameter 'send-arm-action-parameter :arm) - (add-logging-function-for-action-designator-parameter 'send-gripper-action-parameter :gripper) + ;;(add-logging-function-for-action-designator-parameter 'send-arm-action-parameter :arm) + ;;(add-logging-function-for-action-designator-parameter 'send-gripper-action-parameter :gripper) (add-logging-function-for-action-designator-parameter 'send-grasp-action-parameter :grasp) - (add-logging-function-for-action-designator-parameter 'send-left-pose-stamped-list-action-parameter :left-poses) - (add-logging-function-for-action-designator-parameter 'send-right-pose-stamped-list-action-parameter :right-poses) - (add-logging-function-for-action-designator-parameter 'send-location-action-parameter :location) - (add-logging-function-for-action-designator-parameter 'send-target-action-parameter :target)) + ;;(add-logging-function-for-action-designator-parameter 'send-left-pose-stamped-list-action-parameter :left-poses) + ;;(add-logging-function-for-action-designator-parameter 'send-right-pose-stamped-list-action-parameter :right-poses) + ;;(add-logging-function-for-action-designator-parameter 'send-location-action-parameter :location) + ;;(add-logging-function-for-action-designator-parameter 'send-target-action-parameter :target)) + ) (defun add-logging-function-for-action-designator-parameter (logging-function action-designator-parameter) (setf diff --git a/cram_knowrob/cram_cloud_logger/src/mapper/cram-2-knowrob-mapper.lisp b/cram_knowrob/cram_cloud_logger/src/mapper/cram-2-knowrob-mapper.lisp new file mode 100644 index 0000000000..164ebb47ac --- /dev/null +++ b/cram_knowrob/cram_cloud_logger/src/mapper/cram-2-knowrob-mapper.lisp @@ -0,0 +1,14 @@ +(in-package :ccl) + +(defclass cram-2-knowrob-mapper () + ((map :initform (make-hash-table :test 'equal)))) + +(defmethod add-definition-to-mapper (definition (mapper cram-2-knowrob-mapper)) + (loop for x in definition + do (let ((cram-key (car x)) + (knowrob-value (cadr x)) + (map (slot-value mapper 'map))) + (setf (gethash cram-key map) knowrob-value)))) + +(defmethod get-definition-from-mapper (definition (mapper cram-2-knowrob-mapper)) + (gethash definition (slot-value mapper 'map))) diff --git a/cram_knowrob/cram_cloud_logger/src/neem-interface.pl b/cram_knowrob/cram_cloud_logger/src/neem-interface.pl new file mode 100644 index 0000000000..1c649d2e68 --- /dev/null +++ b/cram_knowrob/cram_cloud_logger/src/neem-interface.pl @@ -0,0 +1,47 @@ +:- rdf_meta(mem_event_create(r,r,r)). +:- use_module(library('db/mongo/client')). + +mem_episode_start(Action) :- + tripledb_load('package://knowrob/owl/knowrob.owl',[graph(tbox),namespace(knowrob)]), + tell([is_episode(Episode), is_action(Action), has_type(Task,soma:'PhysicalTask'), + executes_task(Action,Task),is_setting_for(Episode,Action)]),!. + +mem_episode_stop(NeemPath) :- get_time(CurrentTime), atom_concat(NeemPath,'/',X1), atom_concat(X1,CurrentTime,X2), memorize(X2),tripledb_drop(),forall(mng_collection(roslog,Coll),mng_drop(roslog,Coll)). + +mem_event_set_failed(Action) :- tell(action_failed(Action)). + +mem_event_set_succeeded(Action) :- tell(action_succeeded(Action)). + +mem_event_add_diagnosis(Situation, Diagnosis) :- tell(satisfies(Situation, Diagnosis)). + +add_subaction_with_task(Action,SubAction,TaskType) :- tell([is_action(SubAction), has_type(Task,TaskType), executes_task(SubAction,Task), has_subevent(Action,SubAction)]), !. + +mem_event_end(Event) :- get_time(CurrentTime),ask(triple(Event,dul:'hasTimeInterval',TimeInterval)),tripledb_forget(TimeInterval, soma:'hasIntervalEnd', _),tell(holds(TimeInterval, soma:'hasIntervalEnd', CurrentTime)),!. + +mem_event_begin(Event) :- get_time(CurrentTime),tell(occurs(Event) since CurrentTime),!. + +belief_perceived_at(ObjectType, Frame, Object) :- get_time(CurrentTime),tell([has_type(Object,ObjectType),is_at(Object,Frame) since CurrentTime]). + + + +add_participant_with_role(Action, ObjectId, RoleType) :- tell([has_participant(Action,ObjectId), has_type(Role, RoleType), has_role(ObjectId,Role) during [0.0,0.0]]). + + +add_parameter(Task,ParameterType,RegionType) :- tell([has_type(Parameter, ParameterType), has_type(Region,RegionType),has_assignment(Parameter,Region) during [0.0,0.1], has_parameter(Task, Parameter)]). + +add_grasping_parameter(Action,GraspingOrientationType) :- ask(executes_task(Action, Task)), tell([has_type(GraspingOrientation,GraspingOrientationType), has_type(GraspingOrientationConcept,'http://www.ease-crc.org/ont/SOMA.owl#GraspingOrientation'), has_parameter(Task,GraspingOrientationConcept),holds(GraspingOrientationConcept, dul:classifies, GraspingOrientation),has_region(Action,GraspingOrientation)]),!. + +add_comment(Entity,Comment) :- tell(triple(Entity, 'http://www.w3.org/2000/01/rdf-schema#comment', Comment)). + +ros_logger_start :- process_create(path('rosrun'),['mongodb_log', 'mongodb_log.py','__name:=topic_logger', '--mongodb-name', 'roslog', '/tf_projection', '/tf'],[process(PID)]),asserta(ros_logger_pid(PID)). + +ros_logger_stop :- ros_logger_pid(PID), + retractall(ros_logger_pid(PID)), + process_create(path(rosnode), ['kill', '/topic_logger'], + [process(KillPID)]),process_wait(KillPID, _), + process_wait(PID, _), + process_create(path(rosnode),['cleanup'], + [stdin(pipe(In)), detached(true), process(TLPID)]), + writeln(In,'y'),flush_output(In), process_wait(TLPID, _), + print_message(informational,'Topic Logger stopped'). + diff --git a/cram_knowrob/cram_cloud_logger/src/object-interface.lisp b/cram_knowrob/cram_cloud_logger/src/object-interface.lisp index 8df211c435..a220f32263 100644 --- a/cram_knowrob/cram_cloud_logger/src/object-interface.lisp +++ b/cram_knowrob/cram_cloud_logger/src/object-interface.lisp @@ -1,97 +1,157 @@ (in-package :ccl) +(defmethod cram-manipulation-interfaces:get-action-gripping-effort :around (object-type) + (if *is-logging-enabled* + (let ((reasoning-id (log-reasoning-task "GetActionGrippingEffort"))) + (ccl::start-situation reasoning-id) + (let ((query-result (call-next-method))) + (ccl::stop-situation reasoning-id) + (ccl::send-comment reasoning-id (concatenate 'string "INPUT -####- " (write-to-string object-type))) + (ccl::send-comment reasoning-id (concatenate 'string "OUTPUT -####- " (write-to-string query-result))) + query-result)) + (call-next-method))) -(defmethod man-int:calculate-object-faces :around (robot-to-object-transform) +(defmethod cram-manipulation-interfaces:get-action-gripper-opening :around (object-type) (if *is-logging-enabled* - (let ((pose-id (send-create-transform-pose-stamped robot-to-object-transform))) - (let ((query-id - (ccl::create-prolog-log-query-str - "calculate-object-faces" - (list pose-id))) - (query-result (call-next-method))) - (log-end-of-query query-id) - (log-result-of-query - query-id - (concatenate 'string (write-to-string (car query-result)) " " (write-to-string (cadr query-result)))) - query-result)) + (let ((reasoning-id (log-reasoning-task "GetActionGripperOpening"))) + (ccl::start-situation reasoning-id) + (let ((query-result (call-next-method))) + (ccl::stop-situation reasoning-id) + (ccl::send-comment reasoning-id (concatenate 'string "INPUT -####- " (write-to-string object-type))) + (ccl::send-comment reasoning-id (concatenate 'string "OUTPUT -####- " (write-to-string query-result))) + query-result)) (call-next-method))) -(defmethod man-int:get-action-gripping-effort :around (object-type) + +(defmethod cram-manipulation-interfaces:get-action-grasps :around (object-type arm object-transform-in-base) (if *is-logging-enabled* - (let ((query-id - (ccl::create-prolog-log-query-str - "get-object-type-gripping-effort" - (list (write-to-string object-type)))) - (query-result (call-next-method))) - (log-end-of-query query-id) - query-result) + (let ((reasoning-id (log-reasoning-task "GetActionGrasps"))) + (ccl::start-situation reasoning-id) + (let ((query-result (call-next-method))) + (ccl::stop-situation reasoning-id) + query-result)) (call-next-method))) +(defmethod cram-manipulation-interfaces:get-container-closing-distance :around (container-name) + (if *is-logging-enabled* + (let ((reasoning-id (log-reasoning-task "GetContainerClosingDistance"))) + (ccl::start-situation reasoning-id) + (let ((query-result (call-next-method))) + (ccl::stop-situation reasoning-id) + (ccl::send-comment reasoning-id (concatenate 'string "INPUT -####- " (write-to-string container-name))) + (ccl::send-comment reasoning-id (concatenate 'string "OUTPUT -####- " (write-to-string query-result))) + query-result)) + (call-next-method))) + +(defmethod cram-manipulation-interfaces:get-container-opening-distance :around (container-name) + (if *is-logging-enabled* + (let ((reasoning-id (log-reasoning-task "GetContainerOpeningDistance"))) + (ccl::start-situation reasoning-id) + (let ((query-result (call-next-method))) + (ccl::stop-situation reasoning-id) + (ccl::send-comment reasoning-id (concatenate 'string "INPUT -####- " (write-to-string container-name))) + (ccl::send-comment reasoning-id (concatenate 'string "OUTPUT -####- " (write-to-string query-result))) + query-result)) + (call-next-method))) + +;;(defmethod cram-manipulation-interfaces:get-action-grasps :around (object-type arm object-transform-in-base) +;; (if *is-logging-enabled* +;; (let* ((query-result (call-next-method)) +;; (query-id (log-reasoning-task "cram-manipulation-interfaces:get-action-grasps" (write-to-string object-type) (write-to-string query-result))) +;; (pose-id (send-create-transform-pose-stamped object-transform-in-base))) +;; (send-rdf-query query-id +;; "knowrob:parameter2" +;; (convert-to-prolog-str pose-id)) +;; query-result) +;; (call-next-method))) + +(defmethod cram-manipulation-interfaces:get-action-trajectory :around (action-type arm grasp location objects-acted-on &key &allow-other-keys) + (if *is-logging-enabled* + (let ((reasoning-id (log-reasoning-task "GetActionTrajectory"))) + (ccl::start-situation reasoning-id) + (let ((query-result (call-next-method))) + (ccl::stop-situation reasoning-id) + (ccl::send-comment reasoning-id (concatenate 'string "INPUT -####- " (write-to-string action-type) + " -####- " (write-to-string arm) + " -####- " (write-to-string grasp) + " -####- " (write-to-string objects-acted-on))) + (ccl::send-comment reasoning-id (concatenate 'string "OUTPUT -####- " (write-to-string query-result))) + query-result)) + (call-next-method))) -(defmethod man-int:get-action-grasps :around (object-type - arm - object-transform-in-base) +(defmethod cram-manipulation-interfaces:get-location-poses :around (location-designator) (if *is-logging-enabled* - (let ((query-id - (ccl::create-prolog-log-query-str - "get-object-type-grasps" - (list (write-to-string object-type) - (write-to-string nil) - (write-to-string nil) - (write-to-string nil) - (write-to-string arm)))) - (query-result (call-next-method))) - (log-end-of-query query-id) - query-result) + (let ((reasoning-id (log-reasoning-task "GetLocationPoses"))) + (ccl::start-situation reasoning-id) + (let ((query-result (call-next-method))) + (ccl::stop-situation reasoning-id) + (ccl::send-comment reasoning-id (concatenate 'string "INPUT -####- " (write-to-string location-designator))) + (ccl::send-comment reasoning-id (concatenate 'string "OUTPUT -####- " (write-to-string query-result))) + query-result)) (call-next-method))) -(defmethod man-int:get-action-gripper-opening :around (object-type) - ;;(format t "Asking for GRIPPER OPENING for the object: ~a~%" object-type) - (let ((query-result (call-next-method))) - ;;(format t "GRIPPER OPENING Result is ~a~% for the object: ~a~%" query-result object-type) - query-result)) - -(defmethod man-int:get-object-type-to-gripper-lift-transform :around (object-type - object-name - arm - grasp - grasp-transform) - ;;(format t "Asking for GRIPPER LIFT TRANSFORMATION for the object: ~a~%" object-type) - (let ((query-result (call-next-method))) - ;;(format t "GRIPPER LIFT TRANSFORMATION Result is ~a~% for the object: ~a~%" query-result object-type) - query-result)) - -(defmethod man-int:get-object-type-to-gripper-transform :around (object-type - object-name - arm - grasp) - ;;(format t "Asking for GRIPPER TRANSFORM for the object: ~a~%" object-type) - (let ((query-result (call-next-method))) - ;;(format t "GRIPPER TRANSFORM Result is ~a~% for the object: ~a~%" query-result object-type) - query-result)) - -(defmethod man-int:get-object-type-to-gripper-pregrasp-transform :around (object-type - object-name - arm - grasp - grasp-transform) - ;;(format t "Asking for GRIPPER PREGRASP TRANSFORMATION for the object: ~a~%" object-type) - (let ((query-result (call-next-method))) - ;;(format t "GRIPPER PREGRASP TRANSFORMATION Result is ~a~% for the object: ~a~%" query-result object-type) - query-result)) - -(defmethod man-int:get-object-type-to-gripper-2nd-pregrasp-transform :around (object-type - object-name - arm - grasp - grasp-transform) - ;;(format t "Asking for GRIPPER 2ND PREGRASP TRANSFORMATION for the object: ~a~%" object-type) - (let ((query-result (call-next-method))) - ;;(format t "GRIPPER 2ND PREGRASP TRANSFORMATION Result is ~a~% for the object: ~a~%" query-result object-type) - query-result)) - -(defmethod man-int:get-object-grasping-poses :around (object-name object-type arm grasp object-transform) - ;;(format t "Asking for GRASPING POSES for the object: ~a~%" object-type) - (let ((query-result (call-next-method))) - ;;(format t "Asking for GRASPING POSES Result is ~a~% for the object: ~a~%" query-result object-type) - query-result)) +(defun log-reasoning-task (predicate-name) + (let ((reasoning-url (create-reasoning-url predicate-name))) + (attach-event-to-situation reasoning-url (get-parent-uri)))) + + +(defun create-reasoning-url (predicate-name) + (concatenate 'string "'http://www.ease-crc.org/ont/EASE-ACT.owl#" predicate-name "'")) + +;;(defun log-reasoning-task (predicate-name parameter reasoning-result) +;; (let +;; ((query-id (convert-to-prolog-str (get-value-of-json-prolog-dict +;; (cdaar +;; (send-cram-start-action +;; (concatenate 'string "knowrob:" (convert-to-prolog-str "ReasoningTask")) +;; " \\'TableSetting\\'" +;; (convert-to-prolog-str (get-timestamp-for-logging)) +;; "PV" +;; "ActionInst")) +;; "ActionInst")))) +;; (print "REASONING LOGGING") +;; ;;(send-init-reasoning-query query-id) +;; (send-predicate-query query-id predicate-name) +;; (print "REASONING LOGGING 1") +;; (send-parameter-query query-id parameter) +;; (print "REASONING LOGGING 2") +;; (send-link-reasoing-to-action query-id) +;; (print "REASONING LOGGING 3") +;; (send-result-query query-id reasoning-result) +;; (print "REASONING LOGGING 4") +;; query-id)) + + +(defun send-init-reasoning-query (query-id) + (send-prolog-query-1 + (create-query + "cram_start_action" + (list (concatenate 'string "knowrob:" (convert-to-prolog-str "PrologQuery")) + "\\'TableSetting\\'" + (get-timestamp-for-logging) + "PV" + query-id)))) + +(defun send-predicate-query (query-id predicate-name) + (send-rdf-query query-id + "knowrob:predicate" + (convert-to-prolog-str predicate-name))) + +(defun send-result-query (query-id result-query) + (send-rdf-query query-id + "knowrob:result" + (convert-to-prolog-str result-query))) + +(defun send-parameter-query (query-id parameter) + (send-rdf-query query-id + "knowrob:parameter" + (convert-to-prolog-str parameter))) + +(defun send-link-reasoing-to-action (query-id) + (send-rdf-query (convert-to-prolog-str (car *action-parents*)) + "knowrob:reasoningTask" + query-id)) + +(defun create-reasoning-task-query-id () + (convert-to-prolog-str (concatenate 'string "http://knowrob.org/kb/knowrob.owl#" "PrologQuery_" (format nil "~x" (random (expt 16 8)))))) + ;;(concatenate (concatenate 'string "knowrob:" (convert-to-prolog-str (concatenate 'string "PrologQuery_" (format nil "~x" (random (expt 16 8)))))))) diff --git a/cram_knowrob/cram_cloud_logger/src/prolog-query-handler.lisp b/cram_knowrob/cram_cloud_logger/src/prolog-query-handler.lisp index e25100cc97..292cd412e3 100644 --- a/cram_knowrob/cram_cloud_logger/src/prolog-query-handler.lisp +++ b/cram_knowrob/cram_cloud_logger/src/prolog-query-handler.lisp @@ -6,7 +6,8 @@ (defmethod prolog::prove-one :around (query binds &optional rethrow-cut) - (if *is-logging-enabled* + ;;(if *is-logging-enabled* + (if nil (let ((query-id (create-prolog-log-query (car query) '("http://knowrob.org/kb/knowrob.owl#no-parameter"))) @@ -82,9 +83,10 @@ (print "--------")))))) (defun send-batch-query () - (print "Sending batch query ...") - (if (cpl:value *prolog-queries*) - (send-prolog-query-1 (create-batch-query))) + (print "Preparing batch query ...") + ;;(if (cpl:value *prolog-queries*) + ;; (progn (print "Sending batch query ...") + ;; (send-prolog-query-1 (create-batch-query)))) (print "Batch query is done")) (defun create-obj-true-false-log-query (predicate-name) diff --git a/cram_knowrob/cram_cloud_logger/src/utils-for-perform.lisp b/cram_knowrob/cram_cloud_logger/src/utils-for-perform.lisp index 2e44036024..b521d770cc 100644 --- a/cram_knowrob/cram_cloud_logger/src/utils-for-perform.lisp +++ b/cram_knowrob/cram_cloud_logger/src/utils-for-perform.lisp @@ -30,67 +30,120 @@ (in-package :ccl) +(defun get-ease-object-lookup-table() + (let ((lookup-table (make-hash-table :test 'equal))) + (setf (gethash "BOWL" lookup-table) "'http://www.ease-crc.org/ont/SOMA.owl#Bowl'") + (setf (gethash "CUP" lookup-table) "'http://www.ease-crc.org/ont/SOMA.owl#Cup'") + (setf (gethash "DRAWER" lookup-table) "'http://www.ease-crc.org/ont/SOMA.owl#Drawer'") + lookup-table)) + (cpl:define-task-variable *action-parents* '()) (defparameter *action-siblings* (make-hash-table)) +(defparameter *detected-objects* (make-hash-table :test 'equal)) +(defparameter *episode-name* nil) +(defparameter *is-logging-enabled* nil) +(defparameter *ease-object-lookup-table* (get-ease-object-lookup-table)) + + +(defun clear-detected-objects () + (setf *detected-objects* (make-hash-table :test 'equal))) + +(defun get-ease-object-id-of-detected-object-by-name (object-name) + (gethash object-name *detected-objects*)) +(defun get-parent-uri() + (if (is-action-parent) + *episode-name* + (car *action-parents*))) + +(defun get-transform-of-detected-object (detected-object) + (let* + ((detected-object-transform (man-int:get-object-transform-in-map detected-object)) + (translate (cl-transforms-stamped:translation detected-object-transform)) + (quaternion (cl-transforms-stamped:rotation detected-object-transform))) + (concatenate + 'string "['map'," + (send-create-3d-vector translate) "," + (send-create-quaternion quaternion)"]"))) + +(defun is-action-parent () + (if (not *action-parents*) t nil)) + +(defun convert-to-ease-object-type-url (object-type) + (if (gethash object-type *ease-object-lookup-table*) + (gethash object-type *ease-object-lookup-table*) + "'http://www.ontologydesignpatterns.org/ont/dul/DUL.owl#DesignedArtifact'")) + +(defun handle-detected-object (detected-object) + (let* ((object-name (get-designator-property-value-str detected-object :NAME)) + (detected-object-type (get-designator-property-value-str detected-object :TYPE)) + (object-type + (convert-to-ease-object-type-url detected-object-type))) + (if (gethash object-name *detected-objects*) + (print "Object exists") + (let ((object-id (send-belief-perceived-at object-type + (get-transform-of-detected-object detected-object) + (concatenate 'string + "'" "http://www.ease-crc.org/ont/SOMA.owl#" + (roslisp-utilities:rosify-underscores-lisp-name (make-symbol object-name)) "'")))) + (setf (gethash object-name *detected-objects*) object-id) + (when (string-equal object-type "'http://www.ontologydesignpatterns.org/ont/dul/DUL.owl#DesignedArtifact'") + (send-comment object-id (concatenate 'string "Unknown Object: "(write-to-string detected-object-type)))))))) + (defmethod exe:generic-perform :around ((designator desig:action-designator)) (if *is-logging-enabled* - ;;This hack was needed for the milestone 2018 - ;;(if (and *is-logging-enabled* (not (string-equal (get-designator-property-value-str designator :TYPE) "grasping"))) (let ((action-id (log-perform-call designator)) - (is-parent-action nil) (cram-action-name (get-designator-property-value-str designator :TYPE))) (cpl:with-failure-handling ((cpl:plan-failure (e) - (log-cram-finish-action action-id) - (send-task-success action-id "false") - (log-failure action-id e) - ;;(format t "failure string: ~a" (write-to-string e)) - (if is-parent-action - (send-batch-query)))) - ;;(print designator) - (if cram-projection:*projection-environment* - (send-performed-in-projection action-id "true") - (send-performed-in-projection action-id "false")) - (log-cram-sub-action - (car *action-parents*) - action-id - (get-knowrob-action-name cram-action-name designator)) - (log-cram-sibling-action - (car *action-parents*) action-id (get-knowrob-action-name cram-action-name designator)) - (if (not *action-parents*) - (setq is-parent-action t)) + ;;(log-cram-finish-action action-id) + (set-event-status-to-failed action-id) + (set-event-diagnosis action-id (ccl::get-failure-uri (subseq (write-to-string e) 2 (search " " (write-to-string e))))) + ;;(log-failure action-id e) + ;;(equate action-id (log-perform-call (second (desig:reference designator))))) + (print "plan failure"))) + + ;;;;;;;;;;;;;;;; CHECK IF ENVIRONMENT IS A SIMULATION + ;;(if cram-projection:*projection-environment* + ;; (send-performed-in-projection action-id "true") + ;; (send-performed-in-projection action-id "false")) + + ;;;;;;;;;;;;;;;; LOG SUBACTIONS + ;;(log-cram-sub-action + ;; (car *action-parents*) + ;; action-id + ;; (get-knowrob-action-name cram-action-name designator)) + + ;;(log-cram-sibling-action + ;; (car *action-parents*) action-id (get-knowrob-action-name cram-action-name designator)) (push action-id *action-parents*) - (let ((perform-result (call-next-method))) - (log-cram-finish-action action-id) - (when (and perform-result (typep perform-result 'desig:object-designator)) - (let ((name (desig:desig-prop-value perform-result :name))) - (when name - (send-object-action-parameter action-id perform-result)))) - (send-task-success action-id "true") - (if is-parent-action - (send-batch-query)) - perform-result))) + + (ccl::start-situation action-id) + (multiple-value-bind (perform-result action-desig) + (call-next-method) + ;;(let ((referenced-action-id (log-perform-call action-desig))) + (let ((referenced-action-id "") + (action-designator-parameters (desig:properties (or action-desig designator)))) + (log-action-designator-parameters-for-logged-action-designator action-designator-parameters action-id) + (when (string-equal cram-action-name "detecting") + (handle-detected-object perform-result)) + (set-event-status-to-succeeded action-id) + (ccl::stop-situation action-id) + perform-result)))) (call-next-method))) +(defun equate (designator-id referenced-designator-id) + (send-rdf-query (convert-to-prolog-str designator-id) + "knowrob:equate" + (convert-to-prolog-str referenced-designator-id))) + (defun log-perform-call (designator) - (connect-to-cloud-logger) - (if *is-client-connected* - (let ((result "") - (cram-action-name (get-designator-property-value-str designator :TYPE)) - (action-designator-parameters (desig:properties designator))) - (setf result (get-value-of-json-prolog-dict - (cdaar - (send-cram-start-action - (get-knowrob-action-name-uri cram-action-name designator) - " \\'TableSetting\\'" - (convert-to-prolog-str (get-timestamp-for-logging)) - "PV" - "ActionInst")) - "ActionInst")) - (log-action-designator-parameters-for-logged-action-designator - action-designator-parameters result) - result) + (if *is-logging-enabled* + (let* ((cram-action-name (get-knowrob-action-name-uri (get-designator-property-value-str designator :TYPE) designator)) + (event-name-url (attach-event-to-situation cram-action-name (get-parent-uri)))) + (when (string-equal cram-action-name "'http://www.ease-crc.org/ont/SOMA.owl#PhysicalTask'") + (send-comment event-name-url (concatenate 'string "Unknown Action: " (get-designator-property-value-str designator :TYPE)))) + event-name-url) "NOLOGGING")) (defun log-failure (action-id failure-type) diff --git a/cram_knowrob/cram_cloud_logger/src/utils.lisp b/cram_knowrob/cram_cloud_logger/src/utils.lisp index 607bd91d30..5c0842857a 100644 --- a/cram_knowrob/cram_cloud_logger/src/utils.lisp +++ b/cram_knowrob/cram_cloud_logger/src/utils.lisp @@ -1,5 +1,20 @@ (in-package :ccl) +(defun get-url-variable-result-as-str-from-json-prolog-result (variable-name json-prolog-result) + (let* ((variable-name-key + (transform-variable-name-to-variable-key variable-name)) + (json-prolog-first-result + (car json-prolog-result)) + (prolog-string-url + (string (cdr (assoc variable-name-key json-prolog-first-result))))) + prolog-string-url)) + +(defun transform-variable-name-to-variable-key (variable-name) + (read-from-string (concatenate 'string "|?" variable-name "|"))) + +(defun convert-to-lisp-str (prolog-str) + (subseq prolog-str 1 (- (length prolog-str) 1))) + (defun get-designator-property-value-str (designator property-keyname) (string (cadr (assoc property-keyname (desig:properties designator))))) diff --git a/cram_json_prolog/.gitignore b/cram_knowrob/cram_json_prolog/.gitignore similarity index 100% rename from cram_json_prolog/.gitignore rename to cram_knowrob/cram_json_prolog/.gitignore diff --git a/cram_json_prolog/CHANGELOG.md b/cram_knowrob/cram_json_prolog/CHANGELOG.md similarity index 100% rename from cram_json_prolog/CHANGELOG.md rename to cram_knowrob/cram_json_prolog/CHANGELOG.md diff --git a/cram_json_prolog/CMakeLists.txt b/cram_knowrob/cram_json_prolog/CMakeLists.txt similarity index 100% rename from cram_json_prolog/CMakeLists.txt rename to cram_knowrob/cram_json_prolog/CMakeLists.txt diff --git a/cram_json_prolog/README.md b/cram_knowrob/cram_json_prolog/README.md similarity index 100% rename from cram_json_prolog/README.md rename to cram_knowrob/cram_json_prolog/README.md diff --git a/cram_json_prolog/cram-json-prolog.asd b/cram_knowrob/cram_json_prolog/cram-json-prolog.asd similarity index 87% rename from cram_json_prolog/cram-json-prolog.asd rename to cram_knowrob/cram_json_prolog/cram-json-prolog.asd index e52b2edadc..d107c41e35 100644 --- a/cram_json_prolog/cram-json-prolog.asd +++ b/cram_knowrob/cram_json_prolog/cram-json-prolog.asd @@ -1,10 +1,10 @@ ;;; ;;; Copyright (c) 2009, Lorenz Moesenlechner ;;; All rights reserved. -;;; +;;; ;;; Redistribution and use in source and binary forms, with or without ;;; modification, are permitted provided that the following conditions are met: -;;; +;;; ;;; * Redistributions of source code must retain the above copyright ;;; notice, this list of conditions and the following disclaimer. ;;; * Redistributions in binary form must reproduce the above copyright @@ -13,7 +13,7 @@ ;;; * Neither the name of Willow Garage, Inc. nor the names of its ;;; contributors may be used to endorse or promote products derived from ;;; this software without specific prior written permission. -;;; +;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" ;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE ;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE @@ -27,8 +27,6 @@ ;;; POSSIBILITY OF SUCH DAMAGE. ;;; -;;;; -*- Mode: LISP -*- - (in-package :asdf) (defsystem "cram-json-prolog" @@ -41,7 +39,7 @@ :depends-on (:cram-utilities :cram-prolog :json_prolog_msgs-srv - :yason + :yason :roslisp :alexandria) @@ -49,7 +47,8 @@ ((:module "src" :components ((:file "package") - (:file "json-conversion" :depends-on ("package")) - (:file "prolog-interface" :depends-on ("package" "json-conversion")) - (:file "prolog-handlers" :depends-on ("package" "prolog-interface")) - (:file "server" :depends-on ("package")))))) + ;; (:file "server" :depends-on ("package")) + ;; (:file "json-conversion" :depends-on ("package")) + (:file "conversion" :depends-on ("package")) + (:file "prolog-interface" :depends-on ("package" "conversion")) + (:file "prolog-handlers" :depends-on ("package" "prolog-interface")))))) diff --git a/cram_json_prolog/package.xml b/cram_knowrob/cram_json_prolog/package.xml similarity index 100% rename from cram_json_prolog/package.xml rename to cram_knowrob/cram_json_prolog/package.xml diff --git a/cram_knowrob/cram_json_prolog/src/conversion.lisp b/cram_knowrob/cram_json_prolog/src/conversion.lisp new file mode 100644 index 0000000000..b8044c4977 --- /dev/null +++ b/cram_knowrob/cram_json_prolog/src/conversion.lisp @@ -0,0 +1,146 @@ +;;; +;;; Copyright (c) 2009, Lorenz Moesenlechner +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of Willow Garage, Inc. nor the names of its +;;; contributors may be used to endorse or promote products derived from +;;; this software without specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. +;;; + +(in-package :json-prolog) + +(defun prologify (s) + (flet ((contains-lower-case-char (symbol) + (and + (find-if (lambda (ch) + (let ((lch (char-downcase ch))) + (and (find lch "abcdefghijklmnopqrstuvwxyz") + (eq lch ch)))) + (symbol-name symbol)) + t))) + (if (contains-lower-case-char s) + (string s) + (string-downcase (substitute #\_ #\- (copy-seq (string s))))))) + +(defun lispify (s) + (string-upcase (string s))) + +(defun replace-all-2 (new old str) + (with-output-to-string (out) + (let ((pos (search old str))) + (cond (pos + (write-string (subseq str 0 pos) out) + (write-string new out) + (write-string + (replace-all-2 new old (subseq str (+ pos (length old)))) out)) + (t + (write-string str out))) + out))) + +(defun escape-quotes (str) + (replace-all-2 "\\'" "'" str)) + +(defun unescape-string (str) + (remove "\\" (copy-seq str))) + +(defun replace-complex-types (exp) + (mapcar (lambda (e) + (typecase e + (list (replace-complex-types e)) + (symbol (symbol-name e)) + ;; (string e) + (t e))) + exp)) + +(defun prolog->query-string (exp &key prologify) + "Recursively walks exp and converts every lisp-expression + into a simple prolog query representation." + (when exp + (typecase exp + (string (format nil "'~a'" exp)) + (number (write-to-string exp)) + (symbol + (cond ((is-var exp) + (when (find #\- (symbol-name exp)) + (error 'simple-error + :format-control "Variable name `~a' invalid. ~ + For prolog, it must not contain ~ + `-' characters." + :format-arguments (list exp))) + (subseq (symbol-name exp) 1)) + (t + (if prologify + (escape-quotes (prologify exp)) + (escape-quotes (symbol-name exp)))))) + (list + (cond ((eq (car exp) 'and) + (format nil "~{~A~^, ~}" + (mapcar 'prolog->query-string (cdr exp)))) + ((eq (car exp) 'or) + (format nil "~{~A~^; ~}" + (mapcar 'prolog->query-string (cdr exp)))) + ((eq (car exp) 'quote) + (format nil "[~{~A~^, ~}]" + (mapcar 'prolog->query-string (cadr exp)))) + ((eq (car exp) 'list) + (format nil "[~{~A~^, ~}]" + (mapcar 'prolog->query-string (cdr exp)))) + ((listp (car exp)) + (format nil "[~{~A~^, ~}]" + (mapcar 'prolog->query-string exp))) + (t + (format nil "~a(~{~A~^, ~})" + (car exp) (mapcar 'prolog->query-string (cdr exp)))))) + (t (prolog->query-string + (gensym (symbol-name (type-of exp))) + :prologify prologify))))) + +(defun json->prolog (exp &key (lispify nil) (package *package*)) + "Converts a json encoded string into its lisp prolog representation." + (flet ((map-operators (str) + (string-case str + (";" "OR") + ("," "AND") + (t str)))) + (when exp + (typecase exp + (string (let ((exp (map-operators (unescape-string exp)))) + (if lispify + (intern (lispify exp) package) + (intern (concatenate 'string "'" exp "'") + package)))) + (number exp) + (list (mapcar (alexandria:rcurry #'json->prolog :lispify lispify) exp)) + (hash-table + (let ((list (gethash "list" exp)) + (term (gethash "term" exp)) + (var (gethash "variable" exp))) + (cond (list (list 'quote (json->prolog list :lispify lispify))) + (term (json->prolog term :lispify lispify)) + (var (intern (concatenate 'string "?" var) package))))))))) + +(defun json-bdgs->prolog-bdgs (bdgs-str &key (lispify nil) (package *package*)) + (loop for var being the hash-keys in (yason:parse bdgs-str) + using (hash-value bdg) + collecting (cons (intern (concatenate 'string "?" var) package) + (json->prolog bdg :lispify lispify :package package)))) diff --git a/cram_json_prolog/src/json-conversion.lisp b/cram_knowrob/cram_json_prolog/src/json-conversion.lisp similarity index 99% rename from cram_json_prolog/src/json-conversion.lisp rename to cram_knowrob/cram_json_prolog/src/json-conversion.lisp index 9725ccb13c..c57f204537 100644 --- a/cram_json_prolog/src/json-conversion.lisp +++ b/cram_knowrob/cram_json_prolog/src/json-conversion.lisp @@ -63,7 +63,7 @@ (defun lispify (s) (string-upcase (string s))) -(defun replace-all (new old str) +(defun replace-all-2 (new old str) (with-output-to-string (out) (let ((pos (search old str))) (cond (pos @@ -74,7 +74,7 @@ out))) (defun escape-quotes (str) - (replace-all "\\'" "'" str)) + (replace-all-2 "\\'" "'" str)) (defun unescape-string (str) (remove "\\" (copy-seq str))) diff --git a/cram_json_prolog/src/package.lisp b/cram_knowrob/cram_json_prolog/src/package.lisp similarity index 89% rename from cram_json_prolog/src/package.lisp rename to cram_knowrob/cram_json_prolog/src/package.lisp index cf42d37566..ca59709ab9 100644 --- a/cram_json_prolog/src/package.lisp +++ b/cram_knowrob/cram_json_prolog/src/package.lisp @@ -1,10 +1,10 @@ ;;; ;;; Copyright (c) 2009, Lorenz Moesenlechner ;;; All rights reserved. -;;; +;;; ;;; Redistribution and use in source and binary forms, with or without ;;; modification, are permitted provided that the following conditions are met: -;;; +;;; ;;; * Redistributions of source code must retain the above copyright ;;; notice, this list of conditions and the following disclaimer. ;;; * Redistributions in binary form must reproduce the above copyright @@ -13,7 +13,7 @@ ;;; * Neither the name of Willow Garage, Inc. nor the names of its ;;; contributors may be used to endorse or promote products derived from ;;; this software without specific prior written permission. -;;; +;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" ;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE ;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE @@ -39,9 +39,10 @@ #:prolog-simple-1 #:finish-query #:json-prolog - #:wait-for-prolog-service - #:with-type-atoms - #:init-type-atoms - #:clear-type-atoms - #:replace-complex-types - #:start-prolog-server)) + ;; #:wait-for-prolog-service + ;; #:with-type-atoms + ;; #:init-type-atoms + ;; #:clear-type-atoms + ;; #:replace-complex-types + ;; #:start-prolog-server + )) diff --git a/cram_json_prolog/src/prolog-handlers.lisp b/cram_knowrob/cram_json_prolog/src/prolog-handlers.lisp similarity index 100% rename from cram_json_prolog/src/prolog-handlers.lisp rename to cram_knowrob/cram_json_prolog/src/prolog-handlers.lisp diff --git a/cram_json_prolog/src/prolog-interface.lisp b/cram_knowrob/cram_json_prolog/src/prolog-interface.lisp similarity index 97% rename from cram_json_prolog/src/prolog-interface.lisp rename to cram_knowrob/cram_json_prolog/src/prolog-interface.lisp index a88f659f3c..b395b359fb 100644 --- a/cram_json_prolog/src/prolog-interface.lisp +++ b/cram_knowrob/cram_json_prolog/src/prolog-interface.lisp @@ -1,10 +1,10 @@ ;;; ;;; Copyright (c) 2009, Lorenz Moesenlechner ;;; All rights reserved. -;;; +;;; ;;; Redistribution and use in source and binary forms, with or without ;;; modification, are permitted provided that the following conditions are met: -;;; +;;; ;;; * Redistributions of source code must retain the above copyright ;;; notice, this list of conditions and the following disclaimer. ;;; * Redistributions in binary form must reproduce the above copyright @@ -13,7 +13,7 @@ ;;; * Neither the name of Willow Garage, Inc. nor the names of its ;;; contributors may be used to endorse or promote products derived from ;;; this software without specific prior written permission. -;;; +;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" ;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE ;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE @@ -30,7 +30,7 @@ (in-package :json-prolog) (defvar *finish-marker* nil) -(defvar *service-namespace* "/json_prolog") +(defvar *service-namespace* "/rosprolog") (defvar *persistent-services* (make-hash-table :test 'equal)) @@ -116,7 +116,7 @@ 'json_prolog_msgs-srv:PrologQuery :id query-id :mode mode - :query (prolog->json exp :prologify prologify)) + :query (prolog->query-string exp :prologify prologify)) :lispify lispify :package package))) (defun prolog-1 (exp &key (mode 0) (prologify t) (lispify nil) (package *package*)) @@ -130,7 +130,7 @@ evaluates it." (let ((query-id (make-query-id))) (prolog-result->bdgs query-id - (call-prolog-service (concatenate 'string *service-namespace* "/simple_query") + (call-prolog-service (concatenate 'string *service-namespace* "/query") 'json_prolog_msgs-srv:PrologQuery :id query-id :mode mode @@ -141,7 +141,7 @@ evaluates it." "Like PROLOG-SIMPLE but closes the query after the first solution." (let ((bdgs (prolog-simple query-str :lispify lispify :mode mode :package package))) (finish-query bdgs))) - + (defun finish-query (result) (let ((*finish-marker* t)) (lazy-cdr (last result)) diff --git a/cram_json_prolog/src/server.lisp b/cram_knowrob/cram_json_prolog/src/server.lisp similarity index 100% rename from cram_json_prolog/src/server.lisp rename to cram_knowrob/cram_json_prolog/src/server.lisp diff --git a/cram_knowrob/cram_knowrob_cloud/src/cloud-interface.lisp b/cram_knowrob/cram_knowrob_cloud/src/cloud-interface.lisp index 45cb8b861f..67dfe3a40d 100644 --- a/cram_knowrob/cram_knowrob_cloud/src/cloud-interface.lisp +++ b/cram_knowrob/cram_knowrob_cloud/src/cloud-interface.lisp @@ -29,29 +29,13 @@ (in-package :kr-cloud) -(defun replace-all (string part replacement &key (test #'char=)) - "Returns a new string in which all the occurences of the part -is replaced with replacement. - Taken from Common Lisp Cookbook." - (with-output-to-string (out) - (loop with part-length = (length part) - for old-pos = 0 then (+ pos part-length) - for pos = (search part string - :start2 old-pos - :test test) - do (write-string string out - :start old-pos - :end (or pos (length string))) - when pos do (write-string replacement out) - while pos))) - (defun json-result->string (result-symbol) (when result-symbol (string-trim "'" (symbol-name result-symbol)))) (defun cloud-prolog-simple (query) (declare (type string query)) - (let* ((escaped-query (replace-all query "'" "\\'")) + (let* ((escaped-query (cut:replace-all query "'" "\\'")) (query-answer (json-prolog:prolog-simple-1 (format nil "send_prolog_query('~a', @(false), ID)." escaped-query) :mode 1 @@ -122,7 +106,7 @@ is replaced with replacement. episode-ids) stream) (get-output-stream-string stream))) - (episode-ids-string (replace-all episode-ids-yason-string "\"" "'"))) + (episode-ids-string (cut:replace-all episode-ids-yason-string "\"" "'"))) (cloud-prolog-simple "register_ros_package('knowrob_learning').") (cloud-prolog-simple diff --git a/cram_knowrob/cram_knowrob_manipulation_interfaces/src/cloud-interface.lisp b/cram_knowrob/cram_knowrob_manipulation_interfaces/src/cloud-interface.lisp index 504f54faa1..78e9d24e3e 100644 --- a/cram_knowrob/cram_knowrob_manipulation_interfaces/src/cloud-interface.lisp +++ b/cram_knowrob/cram_knowrob_manipulation_interfaces/src/cloud-interface.lisp @@ -29,29 +29,13 @@ (in-package :kr-assembly) -(defun replace-all (string part replacement &key (test #'char=)) - "Returns a new string in which all the occurences of the part -is replaced with replacement. - Taken from Common Lisp Cookbook." - (with-output-to-string (out) - (loop with part-length = (length part) - for old-pos = 0 then (+ pos part-length) - for pos = (search part string - :start2 old-pos - :test test) - do (write-string string out - :start old-pos - :end (or pos (length string))) - when pos do (write-string replacement out) - while pos))) - (defun json-result->string (result-symbol) (when result-symbol (string-trim "'" (symbol-name result-symbol)))) (defun cloud-prolog-simple (query) (declare (type string query)) - (let* ((escaped-query (replace-all query "'" "\\'")) + (let* ((escaped-query (cut:replace-all query "'" "\\'")) (query-answer (json-prolog:prolog-simple-1 (format nil "send_prolog_query('~a', @(false), ID)." escaped-query) :mode 1))) @@ -99,7 +83,7 @@ is replaced with replacement. episode-ids) stream) (get-output-stream-string stream))) - (episode-ids-string (replace-all episode-ids-yason-string "\"" "'"))) + (episode-ids-string (cut:replace-all episode-ids-yason-string "\"" "'"))) (cloud-prolog-simple "register_ros_package('knowrob_learning').") (cloud-prolog-simple diff --git a/cram_knowrob/cram_knowrob_vr/README.md b/cram_knowrob/cram_knowrob_vr/README.md index 7a4987033e..28250037a3 100644 --- a/cram_knowrob/cram_knowrob_vr/README.md +++ b/cram_knowrob/cram_knowrob_vr/README.md @@ -1,381 +1,6 @@ -(README.md for lisp_ease repository) # cram_knowrob_vr - -This package provides the functionality to import data which has been recorded in Virtual Reality and stored in a MongoDB Database (or OpenEase) into CRAM, so that it can be used within robot plans. -This currently means, that from a recorded episode, 'GraspingSomething' Events are extracted and for each event, the start and end time stamps are given, the positions of the object, the head of the user and the hand which has performed the grasping action at the start and end of the event are extracted. -The package also contains tools for adapting the poses from the Virtual Reality environment and map to the one used within CRAM and the CRAM bullet world simulation. - -## Initialisation of the Environment -In order to be able to use this package, several other programs need to be running. This paragraph will explain which files need to be launched in which order, for the system to be usable. - -There are two ways to use this. Either with just a local MongoDB or with OpenEase instead. The only Mongo way is more leightweight, while the OpenEase option allows for visualization of the data within OpenEase. From the CRAM perspective, nothing within the usability changes. - -### Only MongoDB (leightweight option) -Have a Mongo container set up with the Episode Data and run it in the backgroud. It can be set to autostart on boot so one does not have to worry abot it at all later on. - - -#### ROS -Once mongo is up and running, launch a roscore and the json_prolog ros node: - - roscore - - roslaunch json_prolog json_prolog.launch - -### OpenEase -Using OpenEase instead of just the MongoDB databse, would allow for visualization of the Data within OpenEase. - -In order to run this with local OpenEase instead of just the MongoDB database, one needs to make sure Mongo is not running beforehand, since otherwise OpenEase might not launch properly and this might lead to connection issues. - - mongo ;; starts the mongo console - use admin ;; gives you admin rights - db.shutdownServer() ;; shuts down the db server - -Once the dockerized version of OpenEase is installed, go to the *docker/scripts* folder and execute: - - ./start-webrob - -OpenEase should launch normally. The first time it is launched, a lot of files might need to be downloaded, so please be patient. It will also check some GitHub repositories for changes and updates, so don't be suprised if occasionally things are getting downloaded during startup. - -#### ROS -A rosbridge is needed in order to allow OpenEase to communicate with the local system, since otherwise it is contained within docker. -First, start a roscore in a separate terminal, so in case of needing to restart any of the components, they can be restarted separately. - - roscore - -After that, the launch file can be launched: - - roslaunch knowrob_roslog_launch knowrob_ease.launch - -The CRAM-bullet-world environment needs to be setup also, which can be done with the following: - - roslaunch cram_bullet_world_tutorial world.launch - -### Emacs -Startup emacs with whichever command you prefer, load the lisp_ease package and call the setup functions. It should be something among the lines of the following: - - emacs - M-x slime ;; starts the slime environment, aka. repl - - , r-s-l TAB ENTER ;; ros-load-system - lisp_ease ENTER ENTER ;; package name and confirm - - , in-package ENTER ;; in-package command - le ENTER ;; alias for the lisp_ease package and confirm - -Now one is in the package and can initialize what is needed there. - - -## Using the code -The following will describe how to access the VR data and use it within CRAM in order to make the robot perform plans within the bullet world environment. - -### Initialization (init.lisp) -In the init.lisp file, in the very first function (init-episde) a connection to the episode data and the MongoDB is established. For the episode data to be loaded correctly, the path of the episode data has to be adjusted accordingly to where the data lies on the disk. Aka the general Episode data and it's semantic map. - - -The connection to the MongoDB Database has to be established from CRAM. This can be done by calling: - - (init-full-simulation) - -Or, if preferred, step by step by calling the following: - - (init-episode) ;initializes the episode data and connects to the database - (init-bullet-world) ;launches the bullet world with kitchen and PR2 robot - (init-items) ;spawns the in VR used items in the bullet world and 3 axes objects for debugging - -The (init-full-simulation) function does the above 3 steps in one swoop. - -This can take a while to load, please be patient. - -### Preparing the experiment (demo-preparation.lisp) -In order for the robot to be able to perform a picking up action, the objects have to be first moved to the locations where the human within the VR interacted with them. To accomplish this, call: - - (demo-spawn-all-obj-in-place) - -Will move all the objects that have been used in the current VR episode, to the location at which they were in the beginning of the episode. - -### Running a pick-and-place-action (plan-execution.lisp) -In order to have the simulated robot pick an object up and bring it to the kitchen island, one can call: - - (execute-pick-and-place 'cup) - -The parameter of this function is the name of the object that should be manipulated. Currently six objects are supported, which are: muesli, cup, milk, bowl, fork and spoon. - -If anything goes wrong, try a different object or check the API for more debugging options. - - - -## Function descriptions -### init.lisp -#### (init-episode()) -Creates a ROS node and connects to the database (MongoDB), which contains the episode data. Note that the path to where the episode data and the semantic map are located, needs to be adjusted to your system. If other episode data is to be loaded, it has to be adjusted here accordingly. - -#### (init-bullet-world()) -Initializes the bullet-world, spawning the kitchen and the robot. It also adds the objects which were used in the recording process of the VR data and which are not part of the typical kitchen set, to the mesh list, so that they can later be spawned in the bullet world. Also contains costmap settings. (based on the bullet world tutorial) - -#### (init-items()) -Spawns all the kitchen items that were used in the VR data in the bullet world. Includes also three axes objects for debugging purposes. - -#### (init-full-simulation()) -Calls the three fucntions above in one swoop. - - -### items.lisp -Contains all the item spawning functions. - -#### (add-bowl (&optional (?name :edeka-red-bowl))) -Adds a new bowl object to the scene, at a hardcoded pose somewhere above the robot. (Since the bowl will be moved to where it was in the scenario, the initial pose does not matter.) -A new name can be given to the bowl, which is important if one needs more then one. If the ?name variable is not set, the default name will be: edeka-red-bowl. - -#### (add-cup (&optional (?name :cup-eco-orange))) -same as the above - -#### (add-muesli (&optional (?name :koelln-muesli-knusper-honig-nuss))) -same as the above - -#### (add-fork (&optional (?name :fork-blue-plastic))) -same as the above - -#### (add-spoon (&optional (?name :spoon-blue-plastic))) -same as the above - -#### (add-milk (&optional (?name :weide-milch-small))) -same as the above - -#### (add-axes (?optional (?name :axes))) -Adds an axes object which can be used for pose debugging at a random pose in the world. (Initial pose does not matter.) -A new name can be given to the axes object, which is important if one needs more then one. If the ?name variable is not set, the default name will be: axes. - - -### queries.lisp -Contains all the queries that can be used to access information stored in the MongoDB or OpenEase. These are used within the plans to determine where and object is, where the human was standing, etc. -Each query gets the name of an object as a parameter, and will output the pose or other information about this object, based on when a 'GraspingSomething' event occured. - -#### (base-query (object-type)) -Contains the query on which all the other queries are based, and which is used within the other queries. It asks for an Event based on the given type of the object. Also, the event has to contain an "objectActedOn", meaning it is a "GraspingSomething" event. It also asks for the Start and End time of the event. - -#### (get-event-by-object-type (object-type)) -Returns the event in which an "objectActedOn" event has been performed on the object of the given type. - -#### (get-object-location-at-start-by-object-type (object-type)) -Returns the location of an object of given type at the beginning of the event in the form of a cl-tf:transform. -Meaning, the pose which the object had before it was manipulated by the human. (pick up pose) - -#### (get-object-location-at-end-by-object-type (object-type)) -Returns the location of an object of given type at the end of the event in the form of a cl-tf:transform. -(placing pose) - -#### (get-hand (object-type)) -Returns which hand has been used to manipulate the given object. The result can be :left or :right. - -#### (get-hand-location-at-start-by-object-type (object-type)) -Returns a cl-tf:transform which describes the pose the humans hand had at the start of the "GraspingSomething" Event. The grasping pose the robot uses for his gripper is based on this pose. - -#### (get-hand-location-at-end-by-object-type (object-type)) -Returns a cl-tf:transform which describes the pose the humans hand had at the end of the "GraspingSomething" Event. - -#### (get-camera-location-at-start-by-object-type (object-type)) -Returns a cl-tf:transform which describes the pose of the humans head during the pick up action. The robots location during the pick up action within the environment is based on this pose. - -#### (get-camera-location-at-end-by-object-type (object-type)) -Returns a cl-tf:transform which describes the pose of the humans head at the placing action. The robots location during the placing action within the environment is based on this pose. - -#### (get-table-location ()) -Returns a cl-tf:transform of the pose of the kitchen-island-table within the environment, which is used for the calculation of the placing pose of the object. - -### openease-to-bullet.lisp -Contains all functions which manipulate the data that is obtained from the VR environment, so that it can be used in the plans. Some further manipulation is sometimes necessary depending on the use case of the data, some are more generic and therefore in a different file. - -#### (apply-bullet-transform (transform)) -Applies a transform to the given transform so that the position of the object within the bullet world is correct. Without this offset, the object would appear in a different spot within the bullet world as in the VR world, even if both environments are the same. There is an offset between the two worlds which is corrected by applying this function to the transform of an object or the robot. - -#### (apply-bullet-rotation (transform)) -Same as the above, just that it fixes the rotation only and not the 3d-vector offset between the two environments (VR and bullet world kitchen.) - -#### (quaternion-w-flip (pose)) -Flips the quaternion of the recived pose from wxyz (OpenEase standard) into xyzw (CRAM standard). Is not needed when using the data from the mongoBD directly, but when using OpenEase, it might need to be commented in again (in the make-pose function within the data-manipulation) file, depending on the used OpenEase version. - -#### (remove-z (pose)) -Removes the z component of a transform. Is used for deducing the position within the kitchen of the human/robot, since the only data one can deduce the positon from is the position of the camera/head of the human. - -#### (human-ro-tobot-hand-transform ()) -Defines the offset between the human hand from the virtual reality to the -robot standart gripper, which has been calculated manually. - - -### data-manipulation.lisp -Contains the remaining, more general data manipulating functions, which don't necessarily have anything to do with correcting the offset between the VR and bullet world. - -#### (make-pose (pose)) -Makes a proper cl-tf:transform out of the data received from the mongoDB or OpenEase, since in both cases the received result would have been a list of seven values. These are separated into the 3d vector and the quaternion here, which form the resulting transform. Also the correcting steps which fix the offsets between the two worlds and which were described in the previous file, are applied here. - -#### (apply-rotation (transform)) -Rotates the given transform around the z axis for pi/2. - -#### (add-pos-offset-to-transform (transform x y z)) -Adds a position offset to a given transform. Can be used to add an offset to the positon of an object, in order to test if the robot would still be able to interact with it, even if the position expected does not match. - -### designators.lisp -Contains the designator definitions for grasping the objects relevant for the current scenario, which are all the objects described and added in the items.lisp file. - -### movement.lisp -All the functions which move either the robot, parts of the robot or objects within the bullet world are collected here. - -#### (move-obj-with-offset (x-offset y-offset object)) -Moves the object to the given x and y offset. It does not change the z aspect of the object, since the usecase of this function is to just move an object on the surface of the table to test if the robot would still be able to interact with it, even after a change in position. - -#### (move-head (pose)) -Moves the head of the robot to the given pose. - -#### (move-object (transform object)) -Moves the given object to the given transform. - -#### (move-robot (transform)) -Moves the robot to the given transform. - -#### (move-torso-up (?angle)) -Moves the torso up by a given angle. - -### utils.lisp -Contains many of the utility functions. Some of them are just handy and make the usage a bit easier and basically don't have to be used and are therefore convenience functions. - -#### (object-type-filter-prolog (object-type)) -Maps the simple name of an object, e.g. 'cup to the proper one used within the mondoDB or OpenEase database, e.g. "CupEcoOrange". - -#### (object-type-filter-bullet (object-type)) -Maps the simple name of an object, e.g. 'cup to the proper one used within the bullet world, e.g. :cup-eco-orange - -#### (object-type-fixer (object-type)) -Since some names of the objects differ between the known names in bullet world and the names known to the database, this function makes sure that if they are mismatched, it will get fixed to the proper one so that the plans can still be executed. -This function can be removed once new data is recorded and the object names will be the same for the bullet world and the Virtual Reality. - -#### (move-object-to-starting-pose (object)) -Moves the object to it's starting position. Sarting position meaning where the object was located when the human started picking it up in the Virtual Reality. - -#### (place-offset-transform ()) -Contains the transform which describes the offset for placing an object. - -#### (parse-str (str)) -A string parser. Parses the output from knowrob into a proper string which can be used within prolog. - -#### (transform-to-pose-stamped (transform)) -Converts the given transform into a stamped one within the "map" frame and a time stamp of 0.0. - - -### robot-positions-calculations.lisp -Functions which calculate the positions the robot has to navigate to or to move his head or hand to, in order to interact with the objects. - -#### param: \*human-feet-offset* 0.05 -Sets the human-feet-offset, which corrects the robots positon. This is necessary in cases and episodes, where the human was standing too close to a table in the VR, and therefore if the robot would try to move to the same position, he would hit the base of the table, since the robots base (or foot) is a lot larger then the human one. -In some VR episodes this parameter is not needed at all and can be set to 0.0, but at the moment it is safer to keep it at 0.05. - -#### (set-grasp-base-pose (transform)) -Calculates the transform of where the robot should stand in order to interact -with an object. Based on data from Virtual Reality. This function removes the z -component of the Camera pose of the human and also fixes the quaternion so that -the robot won't tilt into the pane of the floor. - -#### (set-grasp-look-pose (transform)) -Transforms the given transform of the position of an object, into a pose -stamped, at which the robot will look for an object. - -#### (set-place-pose (transform)) -Takes the given transform of the placing the object pose, sets the -quaternion to an identity one and transforms the transform into a pose stamped. - -#### (place-pose-btr-island (type)) -Calculates the placing pose for an object, relative to the bullet world -kitchen island. This is needed, since the OpenEase kitchen island and the -bullet world kitchen island, are slightly offset to one another, and the offset -fixing the general semantic map offset, is not enough to fix it. - -### grasping.lisp -Implements several of the functions needed in order for the robot to perform a succesfull grasp, based on the one performed by the human in the Virtual Reality. Aka. Calculates the grasping pose, pre-pose and the lifting poses. - -#### (get-object-type-to-gripper-transform (object-type object-name arm grasp (eql :human-grasp))) -Calculates the object-type to gripper transform based on the transform the human has used in the Virtual Reality. - -#### (get-object-type-to-gripper-pregrasp-transform ((object-type object-name arm(grasp (eql :human-grasp)) grasp-transform)) -Calculates the object-type to gripper pre-transform based on the transform the human has used in the Virtual Reality. - -#### (get-object-type-to-gripper-2nd-pregrasp-transform (object-type object-name arm(grasp (eql :human-grasp)) grasp-transform)) -Calculates the object-type to gripper 2nd-pre-transform based on the transform the human has used in the Virtual Reality. - -#### (get-object-type-to-gripper-lift-transform ((object-type object-name arm(grasp (eql :human-grasp)) grasp-transform))) -Calculates the lift transform for the gripper. - - -#### (get-object-type-to-gripper-2nd-lift-transform ((object-type object-name arm(grasp (eql :human-grasp)) grasp-transform))) -Calculates the 2nd lift transform for the gripper. - -### plans.lisp -Contains all the plans for pick and place manipulation with designators. - -#### (move-to-object (?grasping-base-pose ?grasping-look-pose)) -Moves the robot into the position which the human had when interacting -with an object. The robot is placed at the spot where the human was standing and -is looking at the spot where the object was in Virtual Reality. - -#### (pick-up-obj (?type)) -Picks up an object of the given type. - -#### (pick-up-object (?grasping-base-pose ?grasping-look-pose ?type)) -A plan to pick up an object of the given time. This time the grasping base position and looking positon cam be passed to this function. - -#### (place-object (?placing-base-pose ?placing-look-pose ?place-pose ?obj-desig)) -A plan to place an object which is currently in one of the robots hands. - -#### (pick-and-place (?grasping-base-pose ?grasping-look-pose ?placing-base-pose ?placing-look-pose ?place-pose ?type)) -Picks up and object and places it down based on Virtual Reality data. - -### demo-preparation.lisp -Functions which prepare the environment for the pick and place execution. - -#### (demo-spawn-all-obj-in-place ()) -Spawns all the objects which are present in the current episode in the respective locations. - -### plan-execution.lisp -Executes some of the plans that are specified in the plan.lisp file. - -#### (execute-pick-and-place (type)) -Executes the pick and place plan on an object of the given type. -The positions of where the robot looks for the object and where he is placing -it down are the ones extracted from Virtual Reality. - -#### (execute-pick-up-object (type)) -Executes only the picking up action on an object given the type of the object. - -#### (execute-place-object (?obj-desig type)) -Executes the placing action given the object designator of the picked up and -held in hand object. The placing pose is the one used in VR for that kind of -object. -#### execute-move-to-object (type) -Moves the robot to the position where the human was standing in order to -grasp the object. - -### demo-plans.lisp -Contains some of the plan-executions used for demo puposes. - -#### (demo-all-pick-place ()) -Picks and places all objects of an episode one by one. Meaning the robot will always hold on to just one object and finish placing it before going back to picking up another one. - -#### (demo-all-obj ()) -For the entire episode, first place the object at the location where it was -for the robot to pick up, and then pick it up and place it. - -#### (execution-adjustment-test (type)) -Function to test if the newly done adjustments to the plans are still working. Calls one pick-up-object plan. - -### gaussian.lisp -(In progress) will contain an implementation auf gaussian functions for the base-pose of the robot and maybe more. - -### debugging-utils.lisp -Contains a lot of debuggin convenience functions, which the average user probably (hopefully) will not need. - -#### (reset-simulation ()) -Resets the simulation and respawns the objects. - -### utility-queries.lisp -Contains the lisp implementations of many of the prolog queries, so that they can be called easier, within lisp, with just a string as a parameter, instead of having to use the prolg-simple function. One can use them, but one can also just call prolog directly. Preference choice. +A tutorial explaining the usage of this package and it's capabilities can be found here +[http://cram-system.org/tutorials/advanced/unreal](http://cram-system.org/tutorials/advanced/unreal). diff --git a/cram_knowrob/cram_knowrob_vr/cram-knowrob-vr.asd b/cram_knowrob/cram_knowrob_vr/cram-knowrob-vr.asd index 63450e6324..403685b132 100644 --- a/cram_knowrob/cram_knowrob_vr/cram-knowrob-vr.asd +++ b/cram_knowrob/cram_knowrob_vr/cram-knowrob-vr.asd @@ -46,6 +46,7 @@ cram-executive cram-designators cram-prolog + cram-utilities cram-common-failures cram-urdf-projection ;; cram-pr2-description @@ -80,9 +81,12 @@ (:file "designator-integration" :depends-on ("package" "init" ; for *kvr-enabled* "query-based-calculations")) + ;; experiment log csv file generator stuff + (:file "experiment-log-generator" :depends-on ("package")) ;; plans that call fetch and deliver actions (:file "fetch-and-deliver-based-demo" :depends-on ("package" "init" ; for *kvr-enabled* + "experiment-log-generator" "query-based-calculations" "designator-integration")) ;; (:file "plan-execution" :depends-on ("package")) diff --git a/cram_knowrob/cram_knowrob_vr/experiments/HEUR_BOXY_new_urdf_kitchen.csv b/cram_knowrob/cram_knowrob_vr/experiments/HEUR_BOXY_new_urdf_kitchen.csv new file mode 100644 index 0000000000..8051471d95 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/HEUR_BOXY_new_urdf_kitchen.csv @@ -0,0 +1,603 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,38,7,4,34.344462871551514 +0,CUP,SUM,0,0,0,0,0,21,35,44.70782518386841 +0,SPOON,SUM,0,0,0,0,0,7,7,16.770144939422607 +0,,SUM,0,0,0,0,38,35,46,95.82243299484253 +0,, +1,, +1,BOWL,SUM,1,0,1,0,8,743,176,0.0 +1,CUP,SUM,0,0,0,0,8,2,22,26.220234870910645 +1,SPOON,SUM,0,0,0,0,0,1,5,14.759235858917236 +1,,SUM,1,0,1,0,16,746,203,40.97947072982788 +1,, +2,, +2,BOWL,SUM,0,0,0,0,0,1,0,9.126543998718262 +2,CUP,SUM,0,0,0,0,32,115,89,60.77761387825012 +2,SPOON,SUM,0,0,0,0,0,6,9,21.386530876159668 +2,,SUM,0,0,0,0,32,122,98,91.29068875312805 +2,, +3,, +3,BOWL,SUM,0,0,0,0,24,0,2,20.68395209312439 +3,CUP,SUM,0,0,0,0,0,5,22,15.09244680404663 +3,SPOON,SUM,1,0,1,0,8,1583,0,0.0 +3,,SUM,1,0,1,0,32,1588,24,35.77639889717102 +3,, +4,, +4,BOWL,SUM,0,0,0,0,0,0,7,15.25937294960022 +4,CUP,SUM,1,0,1,0,6,1138,420,0.0 +4,SPOON,SUM,0,0,0,0,0,1,0,10.695035934448242 +4,,SUM,1,0,1,0,6,1139,427,25.954408884048462 +4,, +5,, +5,BOWL,SUM,0,0,0,0,0,7,68,35.921189069747925 +5,CUP,SUM,0,0,0,0,0,8,22,15.513466119766235 +5,SPOON,SUM,0,0,0,0,0,0,3,13.895228862762451 +5,,SUM,0,0,0,0,0,15,93,65.32988405227661 +5,, +6,, +6,BOWL,SUM,0,0,0,0,0,3,12,13.963188886642456 +6,CUP,SUM,0,0,0,0,0,3,11,12.819225072860718 +6,SPOON,SUM,0,0,0,0,8,6,2,15.303355932235718 +6,,SUM,0,0,0,0,8,12,25,42.08576989173889 +6,, +7,, +7,BOWL,SUM,1,0,1,0,16,479,196,0.0 +7,CUP,SUM,0,0,0,0,0,4,21,17.67791485786438 +7,SPOON,SUM,0,0,0,0,0,2,3,16.514517068862915 +7,,SUM,1,0,1,0,16,485,220,34.192431926727295 +7,, +8,, +8,BOWL,SUM,0,0,0,0,0,1,14,23.27755093574524 +8,CUP,SUM,0,0,0,0,0,6,24,25.88141703605652 +8,SPOON,SUM,1,0,1,0,30,726,176,0.0 +8,,SUM,1,0,1,0,30,733,214,49.15896797180176 +8,, +9,, +9,BOWL,SUM,0,0,0,0,2,0,1,10.46094298362732 +9,CUP,SUM,0,0,0,0,0,6,27,18.41954517364502 +9,SPOON,SUM,0,0,0,0,0,2,8,15.358075857162476 +9,,SUM,0,0,0,0,2,8,36,44.238564014434814 +9,, +10,, +10,BOWL,SUM,0,0,0,0,8,3,7,20.237590074539185 +10,CUP,SUM,0,0,0,0,16,12,72,38.959457874298096 +10,SPOON,SUM,0,0,0,0,0,2,0,10.921795129776001 +10,,SUM,0,0,0,0,24,17,79,70.11884307861328 +10,, +11,, +11,BOWL,SUM,1,0,1,0,0,565,188,0.0 +11,CUP,SUM,0,0,0,0,0,1,62,27.097379207611084 +11,SPOON,SUM,0,0,0,0,0,4,4,14.64023494720459 +11,,SUM,1,0,1,0,0,570,254,41.737614154815674 +11,, +12,, +12,BOWL,SUM,0,0,0,0,0,0,0,8.242691993713379 +12,CUP,SUM,0,0,0,0,0,88,224,87.01893019676208 +12,SPOON,SUM,0,0,0,0,0,7,6,16.00449299812317 +12,,SUM,0,0,0,0,0,95,230,111.26611518859863 +12,, +13,, +13,BOWL,SUM,0,0,0,0,0,2,73,43.364293813705444 +13,CUP,SUM,0,0,0,0,0,3,44,23.699573040008545 +13,SPOON,SUM,1,0,1,0,56,1056,120,0.0 +13,,SUM,1,0,1,0,56,1061,237,67.06386685371399 +13,, +14,, +14,BOWL,SUM,0,0,0,0,0,1,21,17.691666841506958 +14,CUP,SUM,0,0,0,0,0,1,38,17.900398015975952 +14,SPOON,SUM,1,0,1,0,16,1082,124,0.0 +14,,SUM,1,0,1,0,16,1084,183,35.59206485748291 +14,, +15,, +15,BOWL,SUM,0,0,0,0,2,1,4,12.239400863647461 +15,CUP,SUM,0,0,0,0,40,230,154,103.97183513641357 +15,SPOON,SUM,0,0,0,0,0,0,6,13.619953155517578 +15,,SUM,0,0,0,0,42,231,164,129.8311891555786 +15,, +16,, +16,BOWL,SUM,0,0,0,0,8,5,8,17.266101837158203 +16,CUP,SUM,1,0,1,0,0,1474,160,0.0 +16,SPOON,SUM,0,0,0,0,0,3,4,14.171331882476807 +16,,SUM,1,0,1,0,8,1482,172,31.43743371963501 +16,, +17,, +17,BOWL,SUM,0,0,0,0,0,0,10,14.777184009552002 +17,CUP,SUM,0,0,0,0,2,0,52,24.348668098449707 +17,SPOON,SUM,1,0,1,0,0,1375,52,0.0 +17,,SUM,1,0,1,0,2,1375,114,39.12585210800171 +17,, +18,, +18,BOWL,SUM,0,0,0,0,0,1,2,8.309523820877075 +18,CUP,SUM,0,0,0,0,10,22,75,56.83479690551758 +18,SPOON,SUM,0,0,0,0,0,1,2,13.198771953582764 +18,,SUM,0,0,0,0,10,24,79,78.34309267997742 +18,, +19,, +19,BOWL,SUM,1,0,1,0,0,975,128,0.0 +19,CUP,SUM,0,0,0,0,0,5,19,12.762521982192993 +19,SPOON,SUM,0,0,0,0,0,2,4,13.590637922286987 +19,,SUM,1,0,1,0,0,982,151,26.35315990447998 +19,, +20,, +20,BOWL,SUM,0,0,0,0,16,703,67,85.11807012557983 +20,CUP,SUM,0,0,0,0,0,5,30,36.101662158966064 +20,SPOON,SUM,0,0,0,0,0,2,0,11.129091024398804 +20,,SUM,0,0,0,0,16,710,97,132.3488233089447 +20,, +21,, +21,BOWL,SUM,0,0,0,0,0,59,2,12.121548891067505 +21,CUP,SUM,0,0,0,0,0,4,63,31.01805090904236 +21,SPOON,SUM,0,0,0,0,0,2,8,15.118974924087524 +21,,SUM,0,0,0,0,0,65,73,58.25857472419739 +21,, +22,, +22,BOWL,SUM,0,0,0,0,0,1,5,12.159448862075806 +22,CUP,SUM,0,0,0,0,0,390,82,66.0432071685791 +22,SPOON,SUM,0,0,0,0,0,1,4,14.052274942398071 +22,,SUM,0,0,0,0,0,392,91,92.25493097305298 +22,, +23,, +23,BOWL,SUM,1,0,1,0,8,1082,120,0.0 +23,CUP,SUM,0,0,0,0,0,1,30,15.989773035049438 +23,SPOON,SUM,0,0,0,0,0,3,0,13.491703033447266 +23,,SUM,1,0,1,0,8,1086,150,29.481476068496704 +23,, +24,, +24,BOWL,SUM,0,0,0,0,0,3,0,8.287431001663208 +24,CUP,SUM,1,0,1,0,0,942,272,0.0 +24,SPOON,SUM,0,0,0,0,8,7,37,34.03307104110718 +24,,SUM,1,0,1,0,8,952,309,42.320502042770386 +24,, +25,, +25,BOWL,SUM,1,0,1,0,2,1583,0,0.0 +25,CUP,SUM,0,0,0,0,0,10,61,50.97846293449402 +25,SPOON,SUM,0,0,0,0,0,9,5,20.43876314163208 +25,,SUM,1,0,1,0,2,1602,66,71.4172260761261 +25,, +26,, +26,BOWL,SUM,1,0,1,0,32,1118,100,0.0 +26,CUP,SUM,0,0,0,0,0,6,26,20.18726420402527 +26,SPOON,SUM,0,0,0,0,0,2,3,15.757317066192627 +26,,SUM,1,0,1,0,32,1126,129,35.944581270217896 +26,, +27,, +27,BOWL,SUM,0,0,0,0,2,0,3,14.058407068252563 +27,CUP,SUM,0,0,0,0,0,16,62,57.66805815696716 +27,SPOON,SUM,1,0,1,0,0,962,140,0.0 +27,,SUM,1,0,1,0,2,978,205,71.72646522521973 +27,, +28,, +28,BOWL,SUM,0,0,0,0,0,2,3,11.726841926574707 +28,CUP,SUM,0,0,0,0,0,10,17,21.935189962387085 +28,SPOON,SUM,1,0,1,0,10,1332,64,0.0 +28,,SUM,1,0,1,0,10,1344,84,33.66203188896179 +28,, +29,, +29,BOWL,SUM,0,0,0,0,0,10,12,19.730308055877686 +29,CUP,SUM,0,0,0,0,0,8,25,21.289146900177002 +29,SPOON,SUM,0,0,0,0,0,3,10,18.781864881515503 +29,,SUM,0,0,0,0,0,21,47,59.80131983757019 +29,, +30,, +30,BOWL,SUM,0,0,0,0,0,1,3,12.33359694480896 +30,CUP,SUM,0,0,0,0,0,12,78,50.3775269985199 +30,SPOON,SUM,0,0,0,0,0,93,28,36.794755935668945 +30,,SUM,0,0,0,0,0,106,109,99.5058798789978 +30,, +31,, +31,BOWL,SUM,0,0,0,0,0,1,2,12.55295205116272 +31,CUP,SUM,0,0,0,0,0,80,101,51.301384925842285 +31,SPOON,SUM,0,0,0,0,8,2,2,17.739484071731567 +31,,SUM,0,0,0,0,8,83,105,81.59382104873657 +31,, +32,, +32,BOWL,SUM,0,0,0,0,0,2,2,8.642399072647095 +32,CUP,SUM,0,0,0,0,0,134,154,70.88061499595642 +32,SPOON,SUM,0,0,0,0,0,1,5,15.92270302772522 +32,,SUM,0,0,0,0,0,137,161,95.44571709632874 +32,, +33,, +33,BOWL,SUM,0,0,0,0,0,3,12,14.080327033996582 +33,CUP,SUM,0,0,0,0,0,6,32,21.670546054840088 +33,SPOON,SUM,1,0,1,0,24,1365,56,0.0 +33,,SUM,1,0,1,0,24,1374,100,35.75087308883667 +33,, +34,, +34,BOWL,SUM,0,0,0,0,0,2,8,13.322662115097046 +34,CUP,SUM,0,0,0,0,0,2,20,13.228490114212036 +34,SPOON,SUM,1,0,1,0,0,1407,44,0.0 +34,,SUM,1,0,1,0,0,1411,72,26.551152229309082 +34,, +35,, +35,BOWL,SUM,0,0,0,0,0,0,2,10.874907970428467 +35,CUP,SUM,0,0,0,0,8,1,8,12.268631935119629 +35,SPOON,SUM,0,0,0,0,0,343,119,88.9008560180664 +35,,SUM,0,0,0,0,8,344,129,112.0443959236145 +35,, +36,, +36,BOWL,SUM,0,0,0,0,0,0,0,8.235314846038818 +36,CUP,SUM,1,0,1,0,56,1190,19,0.0 +36,SPOON,SUM,0,0,0,0,0,8,10,20.193845987319946 +36,,SUM,1,0,1,0,56,1198,29,28.429160833358765 +36,, +37,, +37,BOWL,SUM,0,0,0,0,0,73,22,22.82380199432373 +37,CUP,SUM,0,0,0,0,0,4,11,12.840473890304565 +37,SPOON,SUM,0,0,0,0,8,2,4,16.78911304473877 +37,,SUM,0,0,0,0,8,79,37,52.453388929367065 +37,, +38,, +38,BOWL,SUM,0,0,0,0,0,0,4,10.530174016952515 +38,CUP,SUM,1,0,1,0,0,1443,140,0.0 +38,SPOON,SUM,0,0,0,0,0,0,7,15.383347034454346 +38,,SUM,1,0,1,0,0,1443,151,25.91352105140686 +38,, +39,, +39,BOWL,SUM,0,0,0,0,2,2,4,10.706947803497314 +39,CUP,SUM,0,0,0,0,0,1,17,18.701497077941895 +39,SPOON,SUM,1,0,1,0,24,528,180,0.0 +39,,SUM,1,0,1,0,26,531,201,29.40844488143921 +39,, +40,, +40,BOWL,SUM,0,0,0,0,16,27,37,33.59475612640381 +40,CUP,SUM,0,0,0,0,0,2,12,12.339104890823364 +40,SPOON,SUM,0,0,0,0,0,1,3,14.567800045013428 +40,,SUM,0,0,0,0,16,30,52,60.5016610622406 +40,, +41,, +41,BOWL,SUM,0,0,0,0,0,3,14,17.156768083572388 +41,CUP,SUM,0,0,0,0,0,1,59,24.2078697681427 +41,SPOON,SUM,0,0,0,0,0,23,20,22.904385805130005 +41,,SUM,0,0,0,0,0,27,93,64.26902365684509 +41,, +42,, +42,BOWL,SUM,0,0,0,0,0,2,2,8.719316005706787 +42,CUP,SUM,0,0,0,0,0,0,16,12.185566902160645 +42,SPOON,SUM,0,0,0,0,0,0,6,14.272743940353394 +42,,SUM,0,0,0,0,0,2,24,35.177626848220825 +42,, +43,, +43,BOWL,SUM,0,0,0,0,0,5,6,14.38601016998291 +43,CUP,SUM,0,0,0,0,0,5,34,24.549623012542725 +43,SPOON,SUM,1,0,1,0,8,1582,0,0.0 +43,,SUM,1,0,1,0,8,1592,40,38.935633182525635 +43,, +44,, +44,BOWL,SUM,0,0,0,0,0,2,0,8.6159508228302 +44,CUP,SUM,0,0,0,0,0,8,85,45.49362015724182 +44,SPOON,SUM,1,0,1,0,0,1110,104,0.0 +44,,SUM,1,0,1,0,0,1120,189,54.10957098007202 +44,, +45,, +45,BOWL,SUM,0,0,0,0,0,3,1,10.092656135559082 +45,CUP,SUM,0,0,0,0,2,2,13,16.90589714050293 +45,SPOON,SUM,1,0,1,0,2,1581,0,0.0 +45,,SUM,1,0,1,0,4,1586,14,26.99855327606201 +45,, +46,, +46,BOWL,SUM,0,0,0,0,0,1,14,17.396122217178345 +46,CUP,SUM,0,0,0,0,0,26,44,48.18840789794922 +46,SPOON,SUM,0,0,0,0,0,13,12,23.09922504425049 +46,,SUM,0,0,0,0,0,40,70,88.68375515937805 +46,, +47,, +47,BOWL,SUM,1,0,1,0,16,905,144,0.0 +47,CUP,SUM,0,0,0,0,0,1,28,15.005815982818604 +47,SPOON,SUM,0,0,0,0,0,2,1,13.684960126876831 +47,,SUM,1,0,1,0,16,908,173,28.690776109695435 +47,, +48,, +48,BOWL,SUM,0,0,0,0,2,82,107,64.65864896774292 +48,CUP,SUM,0,0,0,0,8,5,28,27.67088508605957 +48,SPOON,SUM,0,0,0,0,0,1,3,15.887479066848755 +48,,SUM,0,0,0,0,10,88,138,108.21701312065125 +48,, +49,, +49,BOWL,SUM,0,0,0,0,0,0,10,12.93373990058899 +49,CUP,SUM,0,0,0,0,0,5,11,13.951781034469604 +49,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +49,,SUM,1,0,1,0,0,1586,21,26.885520935058594 +49,, +50,, +50,BOWL,SUM,0,0,0,0,0,5,3,10.53671407699585 +50,CUP,SUM,0,0,0,0,0,0,12,11.12476897239685 +50,SPOON,SUM,0,0,0,0,10,9,8,21.043680906295776 +50,,SUM,0,0,0,0,10,14,23,42.70516395568848 +50,, +51,, +51,BOWL,SUM,1,0,1,0,0,281,200,0.0 +51,CUP,SUM,0,0,0,0,0,0,8,8.018105030059814 +51,SPOON,SUM,0,0,0,0,0,0,21,24.36358618736267 +51,,SUM,1,0,1,0,0,281,229,32.381691217422485 +51,, +52,, +52,BOWL,SUM,1,0,1,0,0,278,198,0.0 +52,CUP,SUM,0,0,0,0,0,5,14,15.537199020385742 +52,SPOON,SUM,0,0,0,0,0,3,9,17.701005935668945 +52,,SUM,1,0,1,0,0,286,221,33.23820495605469 +52,, +53,, +53,BOWL,SUM,1,0,1,0,0,1466,28,0.0 +53,CUP,SUM,0,0,0,0,0,3,52,30.662821054458618 +53,SPOON,SUM,0,0,0,0,0,0,0,11.976227045059204 +53,,SUM,1,0,1,0,0,1469,80,42.63904809951782 +53,, +54,, +54,BOWL,SUM,0,0,0,0,0,1,27,24.158150911331177 +54,CUP,SUM,0,0,0,0,16,190,501,207.6888267993927 +54,SPOON,SUM,0,0,0,0,0,0,3,13.429229021072388 +54,,SUM,0,0,0,0,16,191,531,245.27620673179626 +54,, +55,, +55,BOWL,SUM,1,0,1,0,0,755,180,0.0 +55,CUP,SUM,0,0,0,0,0,2,12,11.600555896759033 +55,SPOON,SUM,0,0,0,0,0,3,9,16.74602699279785 +55,,SUM,1,0,1,0,0,760,201,28.346582889556885 +55,, +56,, +56,BOWL,SUM,0,0,0,0,0,2,14,15.138602018356323 +56,CUP,SUM,0,0,0,0,0,391,276,136.73033714294434 +56,SPOON,SUM,0,0,0,0,0,1,0,12.039993047714233 +56,,SUM,0,0,0,0,0,394,290,163.9089322090149 +56,, +57,, +57,BOWL,SUM,0,0,0,0,0,0,17,16.297691106796265 +57,CUP,SUM,0,0,0,0,0,7,38,23.73480200767517 +57,SPOON,SUM,1,0,1,0,0,1008,136,0.0 +57,,SUM,1,0,1,0,0,1015,191,40.032493114471436 +57,, +58,, +58,BOWL,SUM,0,0,0,0,0,2,1,11.857285976409912 +58,CUP,SUM,1,0,0,1,0,39,59,0.0 +58,SPOON,SUM,1,0,1,0,16,1270,42,0.0 +58,,SUM,2,0,1,1,16,1311,102,11.857285976409912 +58,, +59,, +59,BOWL,SUM,1,0,1,0,0,1302,72,0.0 +59,CUP,SUM,0,0,0,0,0,4,25,20.84594702720642 +59,SPOON,SUM,0,0,0,0,0,5,3,16.58079981803894 +59,,SUM,1,0,1,0,0,1311,100,37.42674684524536 +59,, +60,, +60,BOWL,SUM,0,0,0,0,0,2,0,9.670446157455444 +60,CUP,SUM,1,0,1,0,10,1227,255,0.0 +60,SPOON,SUM,0,0,0,0,0,0,0,11.657161951065063 +60,,SUM,1,0,1,0,10,1229,255,21.327608108520508 +60,, +61,, +61,BOWL,SUM,0,0,0,0,0,2,23,22.12329602241516 +61,CUP,SUM,0,0,0,0,24,96,6,37.71416091918945 +61,SPOON,SUM,0,0,0,0,8,4,12,26.535336017608643 +61,,SUM,0,0,0,0,32,102,41,86.37279295921326 +61,, +62,, +62,BOWL,SUM,0,0,0,0,0,30,38,40.22603392601013 +62,CUP,SUM,0,0,0,0,0,4,50,24.5029878616333 +62,SPOON,SUM,0,0,0,0,0,0,0,11.168511867523193 +62,,SUM,0,0,0,0,0,34,88,75.89753365516663 +62,, +63,, +63,BOWL,SUM,0,0,0,0,2,29,9,17.262409925460815 +63,CUP,SUM,0,0,0,0,0,4,79,39.233587980270386 +63,SPOON,SUM,0,0,0,0,0,0,4,13.402683019638062 +63,,SUM,0,0,0,0,2,33,92,69.89868092536926 +63,, +64,, +64,BOWL,SUM,0,0,0,0,0,1,1,9.82887601852417 +64,CUP,SUM,0,0,0,0,0,14,44,33.311142921447754 +64,SPOON,SUM,0,0,0,0,0,3,16,18.370910167694092 +64,,SUM,0,0,0,0,0,18,61,61.510929107666016 +64,, +65,, +65,BOWL,SUM,0,0,0,0,0,1,15,15.730149984359741 +65,CUP,SUM,0,0,0,0,0,1,10,12.230621099472046 +65,SPOON,SUM,1,0,1,0,24,1583,0,0.0 +65,,SUM,1,0,1,0,24,1585,25,27.960771083831787 +65,, +66,, +66,BOWL,SUM,0,0,0,0,0,0,6,18.226905822753906 +66,CUP,SUM,0,0,0,0,0,3,63,31.559123992919922 +66,SPOON,SUM,0,0,0,0,0,12,3,14.181736946105957 +66,,SUM,0,0,0,0,0,15,72,63.967766761779785 +66,, +67,, +67,BOWL,SUM,0,0,0,0,0,6,16,19.811497926712036 +67,CUP,SUM,0,0,0,0,0,62,25,39.2946138381958 +67,SPOON,SUM,0,0,0,0,0,3,12,23.838361024856567 +67,,SUM,0,0,0,0,0,71,53,82.9444727897644 +67,, +68,, +68,BOWL,SUM,0,0,0,0,0,1,8,17.17681908607483 +68,CUP,SUM,1,0,1,0,0,647,688,0.0 +68,SPOON,SUM,0,0,0,0,0,2,5,14.693490028381348 +68,,SUM,1,0,1,0,0,650,701,31.870309114456177 +68,, +69,, +69,BOWL,SUM,0,0,0,0,0,0,1,9.067167043685913 +69,CUP,SUM,0,0,0,0,0,154,303,123.68788313865662 +69,SPOON,SUM,0,0,0,0,0,2,0,12.156394958496094 +69,,SUM,0,0,0,0,0,156,304,144.91144514083862 +69,, +70,, +70,BOWL,SUM,0,0,0,0,2,2,12,17.077754020690918 +70,CUP,SUM,0,0,0,0,0,4,66,31.220447063446045 +70,SPOON,SUM,0,0,0,0,0,45,48,38.64461398124695 +70,,SUM,0,0,0,0,2,51,126,86.94281506538391 +70,, +71,, +71,BOWL,SUM,0,0,0,0,0,3,5,12.425264120101929 +71,CUP,SUM,0,0,0,0,2,1,9,11.95126986503601 +71,SPOON,SUM,1,0,1,0,8,646,184,0.0 +71,,SUM,1,0,1,0,10,650,198,24.37653398513794 +71,, +72,, +72,BOWL,SUM,0,0,0,0,16,5,8,20.62417483329773 +72,CUP,SUM,0,0,0,0,0,6,4,10.181729793548584 +72,SPOON,SUM,0,0,0,0,4,5,8,20.08465886116028 +72,,SUM,0,0,0,0,20,16,20,50.89056348800659 +72,, +73,, +73,BOWL,SUM,0,0,0,0,0,3,10,14.456724882125854 +73,CUP,SUM,0,0,0,0,8,13,30,43.49733781814575 +73,SPOON,SUM,0,0,0,0,0,8,18,28.20351815223694 +73,,SUM,0,0,0,0,8,24,58,86.15758085250854 +73,, +74,, +74,BOWL,SUM,0,0,0,0,0,8,14,27.740752935409546 +74,CUP,SUM,0,0,0,0,0,2,29,16.05211305618286 +74,SPOON,SUM,1,0,1,0,0,1293,76,0.0 +74,,SUM,1,0,1,0,0,1303,119,43.79286599159241 +74,, +75,, +75,BOWL,SUM,1,0,1,0,8,1499,28,0.0 +75,CUP,SUM,0,0,0,0,0,4,9,10.47593092918396 +75,SPOON,SUM,0,0,0,0,0,0,1,13.77982497215271 +75,,SUM,1,0,1,0,8,1503,38,24.25575590133667 +75,, +76,, +76,BOWL,SUM,0,0,0,0,2,4,10,21.04207491874695 +76,CUP,SUM,0,0,0,0,0,2,14,15.740460872650146 +76,SPOON,SUM,0,0,0,0,0,7,21,30.189975023269653 +76,,SUM,0,0,0,0,2,13,45,66.97251081466675 +76,, +77,, +77,BOWL,SUM,0,0,0,0,2,5,6,12.497574090957642 +77,CUP,SUM,0,0,0,0,16,5,67,42.84397506713867 +77,SPOON,SUM,1,0,1,0,8,711,180,0.0 +77,,SUM,1,0,1,0,26,721,253,55.34154915809631 +77,, +78,, +78,BOWL,SUM,0,0,0,0,0,1,11,18.88516616821289 +78,CUP,SUM,0,0,0,0,38,113,123,102.10998582839966 +78,SPOON,SUM,0,0,0,0,0,6,5,19.156291007995605 +78,,SUM,0,0,0,0,38,120,139,140.15144300460815 +78,, +79,, +79,BOWL,SUM,0,0,0,0,0,9,2,10.628620147705078 +79,CUP,SUM,0,0,0,0,0,5,44,29.97930598258972 +79,SPOON,SUM,1,0,1,0,2,1412,36,0.0 +79,,SUM,1,0,1,0,2,1426,82,40.6079261302948 +79,, +80,, +80,BOWL,SUM,0,0,0,0,8,159,114,75.32941603660583 +80,CUP,SUM,0,0,0,0,0,4,19,20.471377849578857 +80,SPOON,SUM,0,0,0,0,0,1,0,11.741981983184814 +80,,SUM,0,0,0,0,8,164,133,107.5427758693695 +80,, +81,, +81,BOWL,SUM,1,0,1,0,0,650,184,0.0 +81,CUP,SUM,0,0,0,0,0,17,121,70.73364400863647 +81,SPOON,SUM,0,0,0,0,0,0,5,16.911969900131226 +81,,SUM,1,0,1,0,0,667,310,87.6456139087677 +81,, +82,, +82,BOWL,SUM,0,0,0,0,0,0,0,9.170495986938477 +82,CUP,SUM,0,0,0,0,0,11,33,47.06053185462952 +82,SPOON,SUM,0,0,0,0,0,3,3,13.979394912719727 +82,,SUM,0,0,0,0,0,14,36,70.21042275428772 +82,, +83,, +83,BOWL,SUM,0,0,0,0,0,0,2,10.796741962432861 +83,CUP,SUM,1,0,1,0,0,1022,217,0.0 +83,SPOON,SUM,0,0,0,0,0,10,13,21.39863395690918 +83,,SUM,1,0,1,0,0,1032,232,32.19537591934204 +83,, +84,, +84,BOWL,SUM,0,0,0,0,0,0,1,10.311408042907715 +84,CUP,SUM,1,0,1,0,8,1285,209,0.0 +84,SPOON,SUM,0,0,0,0,0,4,9,18.649210929870605 +84,,SUM,1,0,1,0,8,1289,219,28.96061897277832 +84,, +85,, +85,BOWL,SUM,0,0,0,0,0,4,1,11.065698146820068 +85,CUP,SUM,0,0,0,0,0,2,23,27.531572103500366 +85,SPOON,SUM,1,0,1,0,8,1581,0,0.0 +85,,SUM,1,0,1,0,8,1587,24,38.597270250320435 +85,, +86,, +86,BOWL,SUM,0,0,0,0,0,0,2,9.484333992004395 +86,CUP,SUM,0,0,0,0,0,3,25,19.872880935668945 +86,SPOON,SUM,1,0,1,0,24,1194,92,0.0 +86,,SUM,1,0,1,0,24,1197,119,29.35721492767334 +86,, +87,, +87,BOWL,SUM,0,0,0,0,0,1,1,10.460668802261353 +87,CUP,SUM,0,0,0,0,6,0,14,13.59163784980774 +87,SPOON,SUM,1,0,1,0,0,576,184,0.0 +87,,SUM,1,0,1,0,6,577,199,24.052306652069092 +87,, +88,, +88,BOWL,SUM,0,0,0,0,0,1,2,10.111532926559448 +88,CUP,SUM,0,0,0,0,2,1,10,13.031744003295898 +88,SPOON,SUM,0,0,0,0,0,30,22,25.889543056488037 +88,,SUM,0,0,0,0,2,32,34,49.032819986343384 +88,, +89,, +89,BOWL,SUM,0,0,0,0,0,7,6,17.402456998825073 +89,CUP,SUM,0,0,0,0,2,13,18,29.01715087890625 +89,SPOON,SUM,0,0,0,0,16,2,0,20.13014507293701 +89,,SUM,0,0,0,0,18,22,24,66.54975295066833 +89,, +90,, +90,BOWL,SUM,0,0,0,0,0,0,5,16.056543827056885 +90,CUP,SUM,1,0,1,0,8,848,350,0.0 +90,SPOON,SUM,0,0,0,0,0,1,1,13.293684005737305 +90,,SUM,1,0,1,0,8,849,356,29.35022783279419 +90,, +91,, +91,BOWL,SUM,0,0,0,0,8,3,52,38.92052102088928 +91,CUP,SUM,0,0,0,0,24,3,30,39.077194929122925 +91,SPOON,SUM,0,0,0,0,2,149,42,57.141937017440796 +91,,SUM,0,0,0,0,34,155,124,135.139652967453 +91,, +92,, +92,BOWL,SUM,0,0,0,0,0,0,9,14.264434814453125 +92,CUP,SUM,0,0,0,0,0,6,24,24.69369411468506 +92,SPOON,SUM,1,0,1,0,8,701,180,0.0 +92,,SUM,1,0,1,0,8,707,213,38.958128929138184 +92,, +93,, +93,BOWL,SUM,0,0,0,0,0,1,1,10.985059976577759 +93,CUP,SUM,0,0,0,0,0,3,10,14.604749202728271 +93,SPOON,SUM,1,0,1,0,16,1581,0,0.0 +93,,SUM,1,0,1,0,16,1585,11,25.58980917930603 +93,, +94,, +94,BOWL,SUM,1,0,1,0,0,1472,28,0.0 +94,CUP,SUM,0,0,0,0,0,0,8,9.93462586402893 +94,SPOON,SUM,0,0,0,0,2,3,7,21.783353090286255 +94,,SUM,1,0,1,0,2,1475,43,31.717978954315186 +94,, +95,, +95,BOWL,SUM,0,0,0,0,0,5,12,28.865066051483154 +95,CUP,SUM,0,0,0,0,2,64,118,75.00186204910278 +95,SPOON,SUM,0,0,0,0,0,3,4,16.49447202682495 +95,,SUM,0,0,0,0,2,72,134,120.36140012741089 +95,, +96,, +96,BOWL,SUM,0,0,0,0,16,38,6,23.540854930877686 +96,CUP,SUM,0,0,0,0,8,4,40,24.850946187973022 +96,SPOON,SUM,0,0,0,0,0,3,8,18.613851070404053 +96,,SUM,0,0,0,0,24,45,54,67.00565218925476 +96,, +97,, +97,BOWL,SUM,0,0,0,0,2,1,11,16.249590158462524 +97,CUP,SUM,0,0,0,0,0,6,29,28.12461805343628 +97,SPOON,SUM,0,0,0,0,0,2,4,15.9788179397583 +97,,SUM,0,0,0,0,2,9,44,60.353026151657104 +97,, +98,, +98,BOWL,SUM,0,0,0,0,0,3,14,18.310253143310547 +98,CUP,SUM,0,0,0,0,0,17,43,44.222975969314575 +98,SPOON,SUM,0,0,0,0,40,169,56,77.37796902656555 +98,,SUM,0,0,0,0,40,189,113,139.91119813919067 +98,, +99,, +99,BOWL,SUM,0,0,0,0,0,2,4,12.556239128112793 +99,CUP,SUM,0,0,0,0,0,5,22,17.979054927825928 +99,SPOON,SUM,0,0,0,0,8,4,3,18.51698088645935 +99,,SUM,0,0,0,0,8,11,29,49.05227494239807 +99,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/HEUR_BOXY_orig_kitchen.csv b/cram_knowrob/cram_knowrob_vr/experiments/HEUR_BOXY_orig_kitchen.csv new file mode 100644 index 0000000000..c20f0b1391 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/HEUR_BOXY_orig_kitchen.csv @@ -0,0 +1,1209 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,4,3,12.0770499706 +0,CUP,SUM,0,0,0,0,0,12,35,21.5131111145 +0,SPOON,SUM,0,0,0,0,0,2,0,10.6741280556 +0,,SUM,0,0,0,0,0,18,38,44.2642891407 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,8,1,13,16.4592130184 +1,CUP,SUM,0,0,0,0,0,6,79,32.2855000496 +1,SPOON,SUM,0,0,0,0,8,7,25,25.8515970707 +1,,SUM,0,0,0,0,16,14,117,74.5963101387 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,24,3,7,25.2449879646 +2,CUP,SUM,0,0,0,0,0,5,16,16.647578001 +2,SPOON,SUM,0,0,0,0,8,10,14,22.2254371643 +2,,SUM,0,0,0,0,32,18,37,64.11800313 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,0,12,18,16.5866129398 +3,CUP,SUM,1,0,0,1,0,45,61,0 +3,SPOON,SUM,0,0,0,0,8,3,4,19.6455690861 +3,,SUM,1,0,0,1,8,60,83,36.2321820259 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,8,65,40.1422801018 +4,CUP,SUM,0,0,0,0,14,4,29,25.7754869461 +4,SPOON,SUM,0,0,0,0,8,2,1,14.8742778301 +4,,SUM,0,0,0,0,22,14,95,80.792044878 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,0,4,9,18.9554190636 +5,CUP,SUM,0,0,0,0,0,4,2,7.2857279778 +5,SPOON,SUM,0,0,0,0,0,5,4,13.9568781853 +5,,SUM,0,0,0,0,0,13,15,40.1980252266 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,0,1,2,9.4788701534 +6,CUP,SUM,0,0,0,0,0,20,36,38.3783960342 +6,SPOON,SUM,0,0,0,0,0,1,17,21.0064430237 +6,,SUM,0,0,0,0,0,22,55,68.8637092113 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,2,3,9,18.1349329948 +7,CUP,SUM,0,0,0,0,0,3,39,18.9520041943 +7,SPOON,SUM,0,0,0,0,0,3,4,13.5247941017 +7,,SUM,0,0,0,0,2,9,52,50.6117312908 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,0,5,1,9.4055759907 +8,CUP,SUM,0,0,0,0,0,26,44,61.6272270679 +8,SPOON,SUM,0,0,0,0,0,1,6,12.524600029 +8,,SUM,0,0,0,0,0,32,51,83.5574030876 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,26,4,5,25.8357551098 +9,CUP,SUM,0,0,0,0,0,11,14,15.7592709064 +9,SPOON,SUM,0,0,0,0,0,4,10,17.956594944 +9,,SUM,0,0,0,0,26,19,29,59.5516209602 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,6,21,19.8333590031 +10,CUP,SUM,0,0,0,0,0,2,19,11.7307929993 +10,SPOON,SUM,0,0,0,0,42,6,25,40.6628680229 +10,,SUM,0,0,0,0,42,14,65,72.2270200253 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,0,12,0,8.8747339249 +11,CUP,SUM,0,0,0,0,10,0,9,13.4323480129 +11,SPOON,SUM,0,0,0,0,0,3,9,16.3990008831 +11,,SUM,0,0,0,0,10,15,18,38.7060828209 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,0,6,9,12.6035349369 +12,CUP,SUM,0,0,0,0,0,4,13,13.3185379505 +12,SPOON,SUM,0,0,0,0,0,1,0,10.675853014 +12,,SUM,0,0,0,0,0,11,22,36.5979259014 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,0,2,12,13.078592062 +13,CUP,SUM,0,0,0,0,2,5,60,29.4100151062 +13,SPOON,SUM,0,0,0,0,0,29,29,27.0527291298 +13,,SUM,0,0,0,0,2,36,101,69.541336298 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,2,6,2,11.0544989109 +14,CUP,SUM,0,0,0,0,0,13,9,14.832267046 +14,SPOON,SUM,0,0,0,0,16,20,8,29.2832632065 +14,,SUM,0,0,0,0,18,39,19,55.1700291634 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,6,2,6,17.9243249893 +15,CUP,SUM,0,0,0,0,0,1,13,14.1382060051 +15,SPOON,SUM,0,0,0,0,0,0,6,12.4566779137 +15,,SUM,0,0,0,0,6,3,25,44.5192089081 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,3,13,14.4290730953 +16,CUP,SUM,0,0,0,0,0,2,44,24.1614060402 +16,SPOON,SUM,0,0,0,0,0,0,6,13.8570261002 +16,,SUM,0,0,0,0,0,5,63,52.4475052357 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,8,8,10,24.2454550266 +17,CUP,SUM,0,0,0,0,2,9,8,9.9552350044 +17,SPOON,SUM,0,0,0,0,0,5,12,18.2358000278 +17,,SUM,0,0,0,0,10,22,30,52.4364900589 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,0,1,4,9.9994699955 +18,CUP,SUM,0,0,0,0,0,0,10,12.6149709225 +18,SPOON,SUM,0,0,0,0,0,1,6,14.8080019951 +18,,SUM,0,0,0,0,0,2,20,37.4224429131 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,3,9,12.109110117 +19,CUP,SUM,0,0,0,0,8,1,13,16.4277179241 +19,SPOON,SUM,0,0,0,0,2,2,20,21.8989338875 +19,,SUM,0,0,0,0,10,6,42,50.4357619286 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,0,1,8,12.2697238922 +20,CUP,SUM,0,0,0,0,0,4,9,10.1100721359 +20,SPOON,SUM,0,0,0,0,0,1,28,24.0044310093 +20,,SUM,0,0,0,0,0,6,45,46.3842270374 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,3,2,10.610532999 +21,CUP,SUM,1,0,0,1,0,36,121,0 +21,SPOON,SUM,0,0,0,0,0,4,2,12.2207608223 +21,,SUM,1,0,0,1,0,43,125,22.8312938213 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,8,2,10,15.596296072 +22,CUP,SUM,0,0,0,0,8,1,37,23.885215044 +22,SPOON,SUM,0,0,0,0,2,6,20,22.7432351112 +22,,SUM,0,0,0,0,18,9,67,62.2247462273 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,1,4,11.2698709965 +23,CUP,SUM,0,0,0,0,0,3,9,13.4256980419 +23,SPOON,SUM,0,0,0,0,2,9,8,14.5545458794 +23,,SUM,0,0,0,0,2,13,21,39.2501149178 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,18,1,1,16.1752681732 +24,CUP,SUM,0,0,0,0,0,24,66,43.9348459244 +24,SPOON,SUM,0,0,0,0,8,5,1,16.5965330601 +24,,SUM,0,0,0,0,26,30,68,76.7066471577 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,8,20,36,33.8320538998 +25,CUP,SUM,0,0,0,0,0,1,8,7.577837944 +25,SPOON,SUM,0,0,0,0,8,56,55,44.5961520672 +25,,SUM,0,0,0,0,16,77,99,86.006043911 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,0,2,0,8.8721039295 +26,CUP,SUM,0,0,0,0,0,1,46,21.7091929913 +26,SPOON,SUM,0,0,0,0,0,1,0,11.2764949799 +26,,SUM,0,0,0,0,0,4,46,41.8577919006 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,6,1,1,11.3495268822 +27,CUP,SUM,0,0,0,0,0,10,45,26.6689720154 +27,SPOON,SUM,0,0,0,0,4,0,11,19.8388800621 +27,,SUM,0,0,0,0,10,11,57,57.8573789597 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,0,4,20,19.2267580032 +28,CUP,SUM,0,0,0,0,8,18,65,33.8135020733 +28,SPOON,SUM,0,0,0,0,8,9,19,28.0125939846 +28,,SUM,0,0,0,0,16,31,104,81.0528540611 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,0,1,18,21.2568039894 +29,CUP,SUM,0,0,0,0,0,2,13,13.3974201679 +29,SPOON,SUM,0,0,0,0,0,1,20,20.3068358898 +29,,SUM,0,0,0,0,0,4,51,54.9610600471 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,8,6,1,13.3464961052 +30,CUP,SUM,0,0,0,0,0,9,153,62.9682660103 +30,SPOON,SUM,0,0,0,0,0,4,42,32.0627551079 +30,,SUM,0,0,0,0,8,19,196,108.3775172234 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,0,17,28,21.7850570679 +31,CUP,SUM,0,0,0,0,0,6,26,20.7700068951 +31,SPOON,SUM,0,0,0,0,0,0,6,13.8342058659 +31,,SUM,0,0,0,0,0,23,60,56.3892698288 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,0,5,12,14.6130449772 +32,CUP,SUM,0,0,0,0,0,2,9,9.6256320477 +32,SPOON,SUM,0,0,0,0,0,3,14,18.9390010834 +32,,SUM,0,0,0,0,0,10,35,43.1776781082 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,0,8,12.6596801281 +33,CUP,SUM,0,0,0,0,2,1,35,21.7693572044 +33,SPOON,SUM,0,0,0,0,0,2,4,17.3370859623 +33,,SUM,0,0,0,0,2,3,47,51.7661232948 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,0,2,7,14.7470958233 +34,CUP,SUM,0,0,0,0,0,41,74,61.2847468853 +34,SPOON,SUM,0,0,0,0,8,6,21,34.50147295 +34,,SUM,0,0,0,0,8,49,102,110.5333156586 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,0,4,28,20.1462049484 +35,CUP,SUM,0,0,0,0,24,14,28,28.7611598969 +35,SPOON,SUM,0,0,0,0,0,0,0,11.1654279232 +35,,SUM,0,0,0,0,24,18,56,60.0727927685 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,2,2,10,14.1225540638 +36,CUP,SUM,0,0,0,0,0,5,34,19.0679769516 +36,SPOON,SUM,0,0,0,0,40,5,6,42.3521690369 +36,,SUM,0,0,0,0,42,12,50,75.5427000523 +36,,,,,,,,,, +37,,,,,,,,,, +37,BOWL,SUM,0,0,0,0,0,2,8,12.1063091755 +37,CUP,SUM,0,0,0,0,0,10,41,23.8161900043 +37,SPOON,SUM,0,0,0,0,0,2,18,27.7428760529 +37,,SUM,0,0,0,0,0,14,67,63.6653752327 +37,,,,,,,,,, +38,,,,,,,,,, +38,BOWL,SUM,0,0,0,0,24,60,111,70.9372160435 +38,CUP,SUM,0,0,0,0,0,5,58,24.9346420765 +38,SPOON,SUM,0,0,0,0,0,3,16,18.1208519936 +38,,SUM,0,0,0,0,24,68,185,113.9927101135 +38,,,,,,,,,, +39,,,,,,,,,, +39,BOWL,SUM,0,0,0,0,0,1,5,12.6435592175 +39,CUP,SUM,0,0,0,0,0,4,37,19.9158611298 +39,SPOON,SUM,0,0,0,0,0,5,0,12.2953240871 +39,,SUM,0,0,0,0,0,10,42,44.8547444344 +39,,,,,,,,,, +40,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,0,1,6,13.1143610477 +40,CUP,SUM,0,0,0,0,8,5,30,30.2739360332 +40,SPOON,SUM,0,0,0,0,0,3,0,11.0517370701 +40,,SUM,0,0,0,0,8,9,36,54.4400341511 +40,,,,,,,,,, +41,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,8,0,2,12.2236318588 +41,CUP,SUM,0,0,0,0,0,6,20,15.7278051376 +41,SPOON,SUM,0,0,0,0,0,4,0,11.9923708439 +41,,SUM,0,0,0,0,8,10,22,39.9438078403 +41,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,0,1,0,8.2760689259 +42,CUP,SUM,0,0,0,0,0,16,90,42.3932721615 +42,SPOON,SUM,0,0,0,0,0,6,52,37.353908062 +42,,SUM,0,0,0,0,0,23,142,88.0232491493 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,0,1,6,13.2893970013 +43,CUP,SUM,0,0,0,0,0,4,9,9.6974420547 +43,SPOON,SUM,0,0,0,0,0,1,3,14.2883741856 +43,,SUM,0,0,0,0,0,6,18,37.2752132416 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,0,4,4,12.9398999214 +44,CUP,SUM,0,0,0,0,0,15,34,22.6941149235 +44,SPOON,SUM,0,0,0,0,0,7,33,26.6158480644 +44,,SUM,0,0,0,0,0,26,71,62.2498629093 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,38,3,6,28.3603248596 +45,CUP,SUM,0,0,0,0,0,6,35,24.9356381893 +45,SPOON,SUM,0,0,0,0,10,14,4,18.4223470688 +45,,SUM,0,0,0,0,48,23,45,71.7183101177 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,0,2,2,9.0883131027 +46,CUP,SUM,0,0,0,0,0,25,58,47.5299360752 +46,SPOON,SUM,0,0,0,0,0,0,1,12.6433839798 +46,,SUM,0,0,0,0,0,27,61,69.2616331577 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,0,0,0,0,0,9,77,44.9056859016 +47,CUP,SUM,1,0,0,1,0,29,67,0 +47,SPOON,SUM,0,0,0,0,0,4,3,13.7421839237 +47,,SUM,1,0,0,1,0,42,147,58.6478698254 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,0,8,58,36.7876229286 +48,CUP,SUM,0,0,0,0,0,0,9,10.1302611828 +48,SPOON,SUM,0,0,0,0,24,3,3,23.9981780052 +48,,SUM,0,0,0,0,24,11,70,70.9160621166 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,2,0,9,14.1768369675 +49,CUP,SUM,0,0,0,0,16,3,18,18.8937339783 +49,SPOON,SUM,0,0,0,0,16,2,0,19.0441339016 +49,,SUM,0,0,0,0,34,5,27,52.1147048473 +49,,,,,,,,,, +50,,,,,,,,,, +50,BOWL,SUM,0,0,0,0,0,60,77,48.2240679264 +50,CUP,SUM,0,0,0,0,0,0,23,15.5188031197 +50,SPOON,SUM,0,0,0,0,2,3,0,13.3251340389 +50,,SUM,0,0,0,0,2,63,100,77.068005085 +50,,,,,,,,,, +51,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,0,4,17,17.0555179119 +51,CUP,SUM,0,0,0,0,0,6,41,20.6041810513 +51,SPOON,SUM,0,0,0,0,0,0,0,11.5670788288 +51,,SUM,0,0,0,0,0,10,58,49.226777792 +51,,,,,,,,,, +52,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,0,2,1,9.9776711464 +52,CUP,SUM,0,0,0,0,2,32,204,82.8793389797 +52,SPOON,SUM,0,0,0,0,0,5,3,13.6310341358 +52,,SUM,0,0,0,0,2,39,208,106.4880442619 +52,,,,,,,,,, +53,,,,,,,,,, +53,BOWL,SUM,0,0,0,0,0,5,4,11.402338028 +53,CUP,SUM,0,0,0,0,8,4,32,21.6910271645 +53,SPOON,SUM,0,0,0,0,8,3,8,19.1797890663 +53,,SUM,0,0,0,0,16,12,44,52.2731542587 +53,,,,,,,,,, +54,,,,,,,,,, +54,BOWL,SUM,0,0,0,0,8,1,1,12.7617070675 +54,CUP,SUM,0,0,0,0,2,7,31,19.4559972286 +54,SPOON,SUM,0,0,0,0,0,0,6,15.4991118908 +54,,SUM,0,0,0,0,10,8,38,47.7168161869 +54,,,,,,,,,, +55,,,,,,,,,, +55,BOWL,SUM,0,0,0,0,0,2,8,11.6451871395 +55,CUP,SUM,1,0,0,1,8,35,141,0 +55,SPOON,SUM,0,0,0,0,0,3,9,16.8259308338 +55,,SUM,1,0,0,1,8,40,158,28.4711179733 +55,,,,,,,,,, +56,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,0,3,11,13.6318740845 +56,CUP,SUM,1,0,0,1,0,29,91,0 +56,SPOON,SUM,0,0,0,0,16,8,4,22.6801540852 +56,,SUM,1,0,0,1,16,40,106,36.3120281696 +56,,,,,,,,,, +57,,,,,,,,,, +57,BOWL,SUM,0,0,0,0,0,4,0,9.3105330467 +57,CUP,SUM,0,0,0,0,16,5,9,22.2582759857 +57,SPOON,SUM,0,0,0,0,16,3,5,21.0431239605 +57,,SUM,0,0,0,0,32,12,14,52.6119329929 +57,,,,,,,,,, +58,,,,,,,,,, +58,BOWL,SUM,0,0,0,0,24,7,1,19.3248310089 +58,CUP,SUM,0,0,0,0,16,13,9,36.0011079311 +58,SPOON,SUM,0,0,0,0,16,1,4,20.5024440289 +58,,SUM,0,0,0,0,56,21,14,75.8283829689 +58,,,,,,,,,, +59,,,,,,,,,, +59,BOWL,SUM,0,0,0,0,6,22,60,42.6724689007 +59,CUP,SUM,0,0,0,0,0,6,10,10.859359026 +59,SPOON,SUM,0,0,0,0,8,4,6,22.067305088 +59,,SUM,0,0,0,0,14,32,76,75.5991330147 +59,,,,,,,,,, +60,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,2,7,9,16.0697100163 +60,CUP,SUM,0,0,0,0,0,2,14,13.759581089 +60,SPOON,SUM,0,0,0,0,0,3,6,15.7325520515 +60,,SUM,0,0,0,0,2,12,29,45.5618431568 +60,,,,,,,,,, +61,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,0,0,9,12.8288969994 +61,CUP,SUM,0,0,0,0,2,2,112,46.6125991344 +61,SPOON,SUM,0,0,0,0,0,50,68,47.9524919987 +61,,SUM,0,0,0,0,2,52,189,107.3939881325 +61,,,,,,,,,, +62,,,,,,,,,, +62,BOWL,SUM,0,0,0,0,0,0,0,8.2080509663 +62,CUP,SUM,0,0,0,0,4,6,5,11.3617990017 +62,SPOON,SUM,0,0,0,0,2,1,9,18.0839390755 +62,,SUM,0,0,0,0,6,7,14,37.6537890434 +62,,,,,,,,,, +63,,,,,,,,,, +63,BOWL,SUM,0,0,0,0,8,3,12,18.0945360661 +63,CUP,SUM,0,0,0,0,0,3,23,15.9038710594 +63,SPOON,SUM,0,0,0,0,0,3,11,17.6008892059 +63,,SUM,0,0,0,0,8,9,46,51.5992963314 +63,,,,,,,,,, +64,,,,,,,,,, +64,BOWL,SUM,0,0,0,0,2,6,21,20.8261671066 +64,CUP,SUM,0,0,0,0,0,2,41,24.1043009758 +64,SPOON,SUM,0,0,0,0,0,4,11,22.2104871273 +64,,SUM,0,0,0,0,2,12,73,67.1409552097 +64,,,,,,,,,, +65,,,,,,,,,, +65,BOWL,SUM,0,0,0,0,0,2,4,11.0143258572 +65,CUP,SUM,1,0,0,1,0,32,234,0 +65,SPOON,SUM,0,0,0,0,0,4,6,17.4563670158 +65,,SUM,1,0,0,1,0,38,244,28.470692873 +65,,,,,,,,,, +66,,,,,,,,,, +66,BOWL,SUM,0,0,0,0,0,3,42,30.0879869461 +66,CUP,SUM,1,0,0,1,0,36,81,0 +66,SPOON,SUM,0,0,0,0,0,3,11,23.2088041306 +66,,SUM,1,0,0,1,0,42,134,53.2967910767 +66,,,,,,,,,, +67,,,,,,,,,, +67,BOWL,SUM,0,0,0,0,0,5,31,25.8886108398 +67,CUP,SUM,0,0,0,0,8,13,66,49.7677800655 +67,SPOON,SUM,0,0,0,0,0,2,9,16.8033120632 +67,,SUM,0,0,0,0,8,20,106,92.4597029686 +67,,,,,,,,,, +68,,,,,,,,,, +68,BOWL,SUM,0,0,0,0,0,2,2,11.0703210831 +68,CUP,SUM,0,0,0,0,2,17,134,64.6152908802 +68,SPOON,SUM,1,0,1,0,32,42,165,0 +68,,SUM,1,0,1,0,34,61,301,75.6856119633 +68,,,,,,,,,, +69,,,,,,,,,, +69,BOWL,SUM,0,0,0,0,0,6,0,8.8946270943 +69,CUP,SUM,0,0,0,0,8,8,38,34.2083539963 +69,SPOON,SUM,0,0,0,0,0,6,11,19.8471539021 +69,,SUM,0,0,0,0,8,20,49,62.9501349926 +69,,,,,,,,,, +70,,,,,,,,,, +70,BOWL,SUM,0,0,0,0,8,0,5,14.4376220703 +70,CUP,SUM,0,0,0,0,4,8,199,78.1846029758 +70,SPOON,SUM,0,0,0,0,24,5,14,37.9979012012 +70,,SUM,0,0,0,0,36,13,218,130.6201262474 +70,,,,,,,,,, +71,,,,,,,,,, +71,BOWL,SUM,0,0,0,0,0,6,5,12.5880680084 +71,CUP,SUM,0,0,0,0,4,14,62,57.1758389473 +71,SPOON,SUM,0,0,0,0,0,4,0,12.4180960655 +71,,SUM,0,0,0,0,4,24,67,82.1820030212 +71,,,,,,,,,, +72,,,,,,,,,, +72,BOWL,SUM,0,0,0,0,0,23,26,22.0999391079 +72,CUP,SUM,0,0,0,0,8,0,8,12.2291779518 +72,SPOON,SUM,0,0,0,0,0,0,7,17.0001871586 +72,,SUM,0,0,0,0,8,23,41,51.3293042183 +72,,,,,,,,,, +73,,,,,,,,,, +73,BOWL,SUM,0,0,0,0,0,2,4,10.9730389118 +73,CUP,SUM,0,0,0,0,0,5,17,19.1849589348 +73,SPOON,SUM,0,0,0,0,0,4,8,15.872590065 +73,,SUM,0,0,0,0,0,11,29,46.0305879116 +73,,,,,,,,,, +74,,,,,,,,,, +74,BOWL,SUM,0,0,0,0,0,2,3,9.9845600128 +74,CUP,SUM,1,0,0,1,0,29,65,0 +74,SPOON,SUM,0,0,0,0,2,0,2,11.919054985 +74,,SUM,1,0,0,1,2,31,70,21.9036149979 +74,,,,,,,,,, +75,,,,,,,,,, +75,BOWL,SUM,0,0,0,0,0,2,9,12.6102077961 +75,CUP,SUM,0,0,0,0,0,6,14,11.5181648731 +75,SPOON,SUM,0,0,0,0,0,6,12,24.6231241226 +75,,SUM,0,0,0,0,0,14,35,48.7514967918 +75,,,,,,,,,, +76,,,,,,,,,, +76,BOWL,SUM,0,0,0,0,0,0,8,17.937474966 +76,CUP,SUM,0,0,0,0,8,8,35,22.300896883 +76,SPOON,SUM,0,0,0,0,0,7,8,17.103276968 +76,,SUM,0,0,0,0,8,15,51,57.3416488171 +76,,,,,,,,,, +77,,,,,,,,,, +77,BOWL,SUM,0,0,0,0,8,4,11,25.861866951 +77,CUP,SUM,0,0,0,0,8,1,8,13.0013501644 +77,SPOON,SUM,0,0,0,0,2,23,29,27.7617990971 +77,,SUM,0,0,0,0,18,28,48,66.6250162125 +77,,,,,,,,,, +78,,,,,,,,,, +78,BOWL,SUM,0,0,0,0,0,9,0,9.6499249935 +78,CUP,SUM,0,0,0,0,0,0,46,21.9657900333 +78,SPOON,SUM,0,0,0,0,2,0,1,14.3538150787 +78,,SUM,0,0,0,0,2,9,47,45.9695301056 +78,,,,,,,,,, +79,,,,,,,,,, +79,BOWL,SUM,0,0,0,0,0,0,12,14.9729161263 +79,CUP,SUM,1,0,0,1,8,28,93,0 +79,SPOON,SUM,0,0,0,0,0,2,7,18.3992209435 +79,,SUM,1,0,0,1,8,30,112,33.3721370697 +79,,,,,,,,,, +80,,,,,,,,,, +80,BOWL,SUM,0,0,0,0,0,3,7,12.3295559883 +80,CUP,SUM,0,0,0,0,10,0,8,13.242634058 +80,SPOON,SUM,0,0,0,0,0,6,14,19.7955021858 +80,,SUM,0,0,0,0,10,9,29,45.3676922321 +80,,,,,,,,,, +81,,,,,,,,,, +81,BOWL,SUM,0,0,0,0,0,2,2,9.0526850224 +81,CUP,SUM,0,0,0,0,0,4,8,8.6552760601 +81,SPOON,SUM,0,0,0,0,16,32,148,91.5000259876 +81,,SUM,0,0,0,0,16,38,158,109.2079870701 +81,,,,,,,,,, +82,,,,,,,,,, +82,BOWL,SUM,0,0,0,0,8,1,4,13.4514360428 +82,CUP,SUM,0,0,0,0,0,2,16,15.0288498402 +82,SPOON,SUM,0,0,0,0,0,3,11,17.629128933 +82,,SUM,0,0,0,0,8,6,31,46.1094148159 +82,,,,,,,,,, +83,,,,,,,,,, +83,BOWL,SUM,0,0,0,0,16,5,5,17.787637949 +83,CUP,SUM,0,0,0,0,8,0,25,19.4262008667 +83,SPOON,SUM,0,0,0,0,0,34,48,36.2400012016 +83,,SUM,0,0,0,0,24,39,78,73.4538400173 +83,,,,,,,,,, +84,,,,,,,,,, +84,BOWL,SUM,0,0,0,0,0,3,11,23.1120290756 +84,CUP,SUM,0,0,0,0,0,1,32,17.3254489899 +84,SPOON,SUM,0,0,0,0,0,11,18,21.2291531563 +84,,SUM,0,0,0,0,0,15,61,61.6666312218 +84,,,,,,,,,, +85,,,,,,,,,, +85,BOWL,SUM,0,0,0,0,2,3,11,14.243265152 +85,CUP,SUM,1,0,0,1,0,36,107,0 +85,SPOON,SUM,0,0,0,0,0,2,17,22.5013217926 +85,,SUM,1,0,0,1,2,41,135,36.7445869446 +85,,,,,,,,,, +86,,,,,,,,,, +86,BOWL,SUM,0,0,0,0,0,1,12,18.4115679264 +86,CUP,SUM,0,0,0,0,8,8,83,40.9447159767 +86,SPOON,SUM,0,0,0,0,0,5,13,22.2598628998 +86,,SUM,0,0,0,0,8,14,108,81.6161468029 +86,,,,,,,,,, +87,,,,,,,,,, +87,BOWL,SUM,0,0,0,0,0,2,0,8.9825279713 +87,CUP,SUM,0,0,0,0,0,2,25,14.8542671204 +87,SPOON,SUM,0,0,0,0,0,10,6,16.1379449368 +87,,SUM,0,0,0,0,0,14,31,39.9747400284 +87,,,,,,,,,, +88,,,,,,,,,, +88,BOWL,SUM,0,0,0,0,0,5,14,20.3026919365 +88,CUP,SUM,0,0,0,0,2,5,25,16.7271699905 +88,SPOON,SUM,0,0,0,0,8,1,0,14.400028944 +88,,SUM,0,0,0,0,10,11,39,51.429890871 +88,,,,,,,,,, +89,,,,,,,,,, +89,BOWL,SUM,0,0,0,0,0,3,24,18.3462159634 +89,CUP,SUM,0,0,0,0,2,2,4,8.0055720806 +89,SPOON,SUM,0,0,0,0,0,0,0,11.0242190361 +89,,SUM,0,0,0,0,2,5,28,37.3760070801 +89,,,,,,,,,, +90,,,,,,,,,, +90,BOWL,SUM,0,0,0,0,0,5,15,19.4957530499 +90,CUP,SUM,1,0,0,1,0,48,55,0 +90,SPOON,SUM,0,0,0,0,2,3,2,16.4778628349 +90,,SUM,1,0,0,1,2,56,72,35.9736158848 +90,,,,,,,,,, +91,,,,,,,,,, +91,BOWL,SUM,0,0,0,0,0,0,16,16.6632900238 +91,CUP,SUM,0,0,0,0,2,5,147,59.8887281418 +91,SPOON,SUM,0,0,0,0,0,11,20,24.0351209641 +91,,SUM,0,0,0,0,2,16,183,100.5871391296 +91,,,,,,,,,, +92,,,,,,,,,, +92,BOWL,SUM,0,0,0,0,0,2,7,12.4545958042 +92,CUP,SUM,0,0,0,0,2,0,26,17.7279000282 +92,SPOON,SUM,0,0,0,0,0,42,42,33.510258913 +92,,SUM,0,0,0,0,2,44,75,63.6927547455 +92,,,,,,,,,, +93,,,,,,,,,, +93,BOWL,SUM,0,0,0,0,0,6,4,11.2177360058 +93,CUP,SUM,0,0,0,0,0,2,16,11.7129240036 +93,SPOON,SUM,0,0,0,0,0,4,12,17.8364171982 +93,,SUM,0,0,0,0,0,12,32,40.7670772076 +93,,,,,,,,,, +94,,,,,,,,,, +94,BOWL,SUM,0,0,0,0,0,5,26,21.0465779305 +94,CUP,SUM,0,0,0,0,0,2,8,8.8721880913 +94,SPOON,SUM,0,0,0,0,0,1,4,13.9941699505 +94,,SUM,0,0,0,0,0,8,38,43.9129359722 +94,,,,,,,,,, +95,,,,,,,,,, +95,BOWL,SUM,0,0,0,0,0,4,12,14.0828900337 +95,CUP,SUM,1,0,0,1,4,63,87,0 +95,SPOON,SUM,0,0,0,0,8,1,42,36.2504048347 +95,,SUM,1,0,0,1,12,68,141,50.3332948685 +95,,,,,,,,,, +96,,,,,,,,,, +96,BOWL,SUM,0,0,0,0,0,3,8,12.6698408127 +96,CUP,SUM,0,0,0,0,4,2,43,24.1099410057 +96,SPOON,SUM,0,0,0,0,0,1,0,12.8643960953 +96,,SUM,0,0,0,0,4,6,51,49.6441779137 +96,,,,,,,,,, +97,,,,,,,,,, +97,BOWL,SUM,0,0,0,0,0,3,4,13.9682872295 +97,CUP,SUM,0,0,0,0,0,6,62,27.7778551579 +97,SPOON,SUM,0,0,0,0,0,9,28,27.6302988529 +97,,SUM,0,0,0,0,0,18,94,69.3764412403 +97,,,,,,,,,, +98,,,,,,,,,, +98,BOWL,SUM,0,0,0,0,0,1,0,8.4316279888 +98,CUP,SUM,0,0,0,0,0,13,31,32.2144072056 +98,SPOON,SUM,0,0,0,0,0,4,12,17.8237938881 +98,,SUM,0,0,0,0,0,18,43,58.4698290825 +98,,,,,,,,,, +99,,,,,,,,,, +99,BOWL,SUM,0,0,0,0,8,4,16,18.8897659779 +99,CUP,SUM,1,0,0,1,24,35,61,0 +99,SPOON,SUM,0,0,0,0,4,9,28,29.6520869732 +99,,SUM,1,0,0,1,36,48,105,48.541852951 +99,,,,,,,,,, +100,,,,,,,,,, +100,BOWL,SUM,0,0,0,0,0,19,28,28.6015450954 +100,CUP,SUM,0,0,0,0,0,8,19,13.9253730774 +100,SPOON,SUM,0,0,0,0,2,0,0,11.6585171223 +100,,SUM,0,0,0,0,2,27,47,54.1854352951 +100,,,,,,,,,, +101,,,,,,,,,, +101,BOWL,SUM,0,0,0,0,0,11,65,40.3713548183 +101,CUP,SUM,0,0,0,0,8,6,10,15.1644179821 +101,SPOON,SUM,0,0,0,0,0,2,0,10.9562380314 +101,,SUM,0,0,0,0,8,19,75,66.4920108318 +101,,,,,,,,,, +102,,,,,,,,,, +102,BOWL,SUM,0,0,0,0,8,12,49,39.0906000137 +102,CUP,SUM,0,0,0,0,0,41,163,101.4877450466 +102,SPOON,SUM,0,0,0,0,8,14,2,16.173429966 +102,,SUM,0,0,0,0,16,67,214,156.7517750263 +102,,,,,,,,,, +103,,,,,,,,,, +103,BOWL,SUM,0,0,0,0,0,3,2,9.0838048458 +103,CUP,SUM,0,0,0,0,0,9,25,16.5667901039 +103,SPOON,SUM,0,0,0,0,16,4,9,29.1736590862 +103,,SUM,0,0,0,0,16,16,36,54.8242540359 +103,,,,,,,,,, +104,, +104,BOWL,SUM,0,0,0,0,0,19,28,27.929215908050537 +104,CUP,SUM,0,0,0,0,0,8,19,14.102808952331543 +104,SPOON,SUM,0,0,0,0,2,0,0,11.999412059783936 +104,,SUM,0,0,0,0,2,27,47,54.031436920166016 +104,, +105,, +105,BOWL,SUM,0,0,0,0,0,11,65,41.432589054107666 +105,CUP,SUM,0,0,0,0,8,6,10,16.057969093322754 +105,SPOON,SUM,0,0,0,0,0,2,0,10.756262063980103 +105,,SUM,0,0,0,0,8,19,75,68.24682021141052 +105,, +106,, +106,BOWL,SUM,0,0,0,0,8,12,49,41.38061308860779 +106,CUP,SUM,0,0,0,0,0,41,163,104.58359694480896 +106,SPOON,SUM,0,0,0,0,8,14,2,16.991039037704468 +106,,SUM,0,0,0,0,16,67,214,162.95524907112122 +106,, +107,, +107,BOWL,SUM,0,0,0,0,0,3,2,9.436041831970215 +107,CUP,SUM,0,0,0,0,0,9,25,16.921226024627686 +107,SPOON,SUM,0,0,0,0,16,4,9,30.885266065597534 +107,,SUM,0,0,0,0,16,16,36,57.242533922195435 +107,, +108,, +108,BOWL,SUM,0,0,0,0,2,0,0,10.161350965499878 +108,CUP,SUM,0,0,0,0,2,27,49,67.80019783973694 +108,SPOON,SUM,0,0,0,0,24,3,5,29.639067888259888 +108,,SUM,0,0,0,0,28,30,54,107.6006166934967 +108,, +109,, +109,BOWL,SUM,0,0,0,0,8,4,6,18.067124843597412 +109,CUP,SUM,0,0,0,0,0,6,44,22.904263973236084 +109,SPOON,SUM,0,0,0,0,0,6,11,17.08932113647461 +109,,SUM,0,0,0,0,8,16,61,58.060709953308105 +109,, +110,, +110,BOWL,SUM,0,0,0,0,0,0,1,9.784749031066895 +110,CUP,SUM,0,0,0,0,10,0,78,37.53702402114868 +110,SPOON,SUM,0,0,0,0,8,1,9,18.64061713218689 +110,,SUM,0,0,0,0,18,1,88,65.96239018440247 +110,, +111,, +111,BOWL,SUM,0,0,0,0,0,0,1,9.101906061172485 +111,CUP,SUM,0,0,0,0,0,8,32,19.844709873199463 +111,SPOON,SUM,0,0,0,0,0,7,27,26.810055017471313 +111,,SUM,0,0,0,0,0,15,60,55.75667095184326 +111,, +112,, +112,BOWL,SUM,0,0,0,0,8,2,4,12.956021070480347 +112,CUP,SUM,0,0,0,0,0,11,44,35.77800393104553 +112,SPOON,SUM,0,0,0,0,0,2,0,10.776010036468506 +112,,SUM,0,0,0,0,8,15,48,59.510035037994385 +112,, +113,, +113,BOWL,SUM,0,0,0,0,2,2,2,9.820525884628296 +113,CUP,SUM,0,0,0,0,32,9,26,41.10254406929016 +113,SPOON,SUM,0,0,0,0,0,1,8,15.124905109405518 +113,,SUM,0,0,0,0,34,12,36,66.04797506332397 +113,, +114,, +114,BOWL,SUM,0,0,0,0,0,2,0,8.00278902053833 +114,CUP,SUM,0,0,0,0,22,7,10,25.41716194152832 +114,SPOON,SUM,0,0,0,0,8,1,1,15.353732109069824 +114,,SUM,0,0,0,0,30,10,11,48.773683071136475 +114,, +115,, +115,BOWL,SUM,0,0,0,0,8,3,7,16.67108702659607 +115,CUP,SUM,0,0,0,0,16,3,74,36.650989055633545 +115,SPOON,SUM,0,0,0,0,0,2,5,14.360852003097534 +115,,SUM,0,0,0,0,24,8,86,67.68292808532715 +115,, +116,, +116,BOWL,SUM,0,0,0,0,2,12,1,11.956151008605957 +116,CUP,SUM,0,0,0,0,0,3,81,35.61701011657715 +116,SPOON,SUM,0,0,0,0,0,17,16,23.42335295677185 +116,,SUM,0,0,0,0,2,32,98,70.99651408195496 +116,, +117,, +117,BOWL,SUM,0,0,0,0,2,5,5,14.169718980789185 +117,CUP,SUM,0,0,0,0,16,12,51,37.65520906448364 +117,SPOON,SUM,0,0,0,0,0,3,17,19.999264001846313 +117,,SUM,0,0,0,0,18,20,73,71.82419204711914 +117,, +118,, +118,BOWL,SUM,0,0,0,0,8,2,8,14.994199991226196 +118,CUP,SUM,0,0,0,0,0,11,46,26.953962087631226 +118,SPOON,SUM,0,0,0,0,0,2,8,15.031354188919067 +118,,SUM,0,0,0,0,8,15,62,56.97951626777649 +118,, +119,, +119,BOWL,SUM,0,0,0,0,0,4,1,9.757030963897705 +119,CUP,SUM,0,0,0,0,0,3,29,16.761300086975098 +119,SPOON,SUM,0,0,0,0,2,2,4,12.051172971725464 +119,,SUM,0,0,0,0,2,9,34,38.56950402259827 +119,, +120,, +120,BOWL,SUM,0,0,0,0,0,18,30,29.423885107040405 +120,CUP,SUM,0,0,0,0,0,16,19,28.66416311264038 +120,SPOON,SUM,0,0,0,0,2,6,4,18.963908910751343 +120,,SUM,0,0,0,0,2,40,53,77.05195713043213 +120,, +121,, +121,BOWL,SUM,0,0,0,0,0,1,10,15.800713062286377 +121,CUP,SUM,0,0,0,0,24,39,214,97.63655710220337 +121,SPOON,SUM,0,0,0,0,0,2,9,17.69720482826233 +121,,SUM,0,0,0,0,24,42,233,131.13447499275208 +121,, +122,, +122,BOWL,SUM,0,0,0,0,8,5,2,22.27001190185547 +122,CUP,SUM,0,0,0,0,0,4,19,13.689356088638306 +122,SPOON,SUM,0,0,0,0,0,1,0,12.313279151916504 +122,,SUM,0,0,0,0,8,10,21,48.27264714241028 +122,, +123,, +123,BOWL,SUM,0,0,0,0,0,1,2,11.143609046936035 +123,CUP,SUM,0,0,0,0,0,5,9,10.286356925964355 +123,SPOON,SUM,0,0,0,0,0,7,2,13.308614015579224 +123,,SUM,0,0,0,0,0,13,13,34.738579988479614 +123,, +124,, +124,BOWL,SUM,0,0,0,0,6,8,16,19.036189079284668 +124,CUP,SUM,0,0,0,0,0,1,47,27.860198974609375 +124,SPOON,SUM,0,0,0,0,0,6,2,14.100965023040771 +124,,SUM,0,0,0,0,6,15,65,60.997353076934814 +124,, +125,, +125,BOWL,SUM,0,0,0,0,0,1,1,10.71995496749878 +125,CUP,SUM,0,0,0,0,8,6,5,18.823019981384277 +125,SPOON,SUM,0,0,0,0,0,1,0,11.048107147216797 +125,,SUM,0,0,0,0,8,8,6,40.59108209609985 +125,, +126,, +126,BOWL,SUM,0,0,0,0,8,2,0,12.770699977874756 +126,CUP,SUM,0,0,0,0,18,14,13,32.502676010131836 +126,SPOON,SUM,0,0,0,0,10,13,86,66.81303977966309 +126,,SUM,0,0,0,0,36,29,99,112.08641576766968 +126,, +127,, +127,BOWL,SUM,0,0,0,0,0,2,8,16.479416131973267 +127,CUP,SUM,0,0,0,0,2,3,40,26.296247005462646 +127,SPOON,SUM,0,0,0,0,0,3,5,15.617522954940796 +127,,SUM,0,0,0,0,2,8,53,58.39318609237671 +127,, +128,, +128,BOWL,SUM,1,0,1,0,0,71,192,0.0 +128,CUP,SUM,0,0,0,0,2,3,8,10.605578184127808 +128,SPOON,SUM,0,0,0,0,0,0,8,16.982015132904053 +128,,SUM,1,0,1,0,2,74,208,27.58759331703186 +128,, +129,, +129,BOWL,SUM,0,0,0,0,0,1,2,9.586380958557129 +129,CUP,SUM,0,0,0,0,16,3,9,20.561023950576782 +129,SPOON,SUM,0,0,0,0,0,6,7,18.635541915893555 +129,,SUM,0,0,0,0,16,10,18,48.782946825027466 +129,, +130,, +130,BOWL,SUM,0,0,0,0,0,2,1,10.659241914749146 +130,CUP,SUM,0,0,0,0,0,2,56,24.72844099998474 +130,SPOON,SUM,0,0,0,0,0,5,14,18.95421814918518 +130,,SUM,0,0,0,0,0,9,71,54.34190106391907 +130,, +131,, +131,BOWL,SUM,0,0,0,0,0,0,4,8.44313907623291 +131,CUP,SUM,0,0,0,0,8,4,18,20.98172903060913 +131,SPOON,SUM,0,0,0,0,2,0,10,17.10672903060913 +131,,SUM,0,0,0,0,10,4,32,46.53159713745117 +131,, +132,, +132,BOWL,SUM,0,0,0,0,0,3,0,8.382421970367432 +132,CUP,SUM,0,0,0,0,0,15,40,33.6412570476532 +132,SPOON,SUM,0,0,0,0,0,21,30,31.235488891601563 +132,,SUM,0,0,0,0,0,39,70,73.25916790962219 +132,, +133,, +133,BOWL,SUM,0,0,0,0,0,3,15,19.756561040878296 +133,CUP,SUM,0,0,0,0,8,4,14,18.51856803894043 +133,SPOON,SUM,0,0,0,0,0,1,1,12.245738983154297 +133,,SUM,0,0,0,0,8,8,30,50.52086806297302 +133,, +134,, +134,BOWL,SUM,0,0,0,0,8,7,3,17.92335820198059 +134,CUP,SUM,0,0,0,0,0,4,46,21.90714192390442 +134,SPOON,SUM,0,0,0,0,0,9,11,18.979650020599365 +134,,SUM,0,0,0,0,8,20,60,58.810150146484375 +134,, +135,, +135,BOWL,SUM,0,0,0,0,0,2,1,10.207993030548096 +135,CUP,SUM,0,0,0,0,2,3,26,15.94277286529541 +135,SPOON,SUM,0,0,0,0,0,17,21,24.676681995391846 +135,,SUM,0,0,0,0,2,22,48,50.82744789123535 +135,, +136,, +136,BOWL,SUM,0,0,0,0,16,1,8,18.17962384223938 +136,CUP,SUM,0,0,0,0,0,2,52,23.415377140045166 +136,SPOON,SUM,0,0,0,0,0,0,4,13.407725095748901 +136,,SUM,0,0,0,0,16,3,64,55.00272607803345 +136,, +137,, +137,BOWL,SUM,0,0,0,0,0,3,25,18.396801948547363 +137,CUP,SUM,0,0,0,0,0,2,8,10.990600109100342 +137,SPOON,SUM,0,0,0,0,0,0,0,11.270506858825684 +137,,SUM,0,0,0,0,0,5,33,40.65790891647339 +137,, +138,, +138,BOWL,SUM,0,0,0,0,0,0,4,9.299925088882446 +138,CUP,SUM,0,0,0,0,0,1,8,8.378817081451416 +138,SPOON,SUM,0,0,0,0,0,2,0,11.692605972290039 +138,,SUM,0,0,0,0,0,3,12,29.3713481426239 +138,, +139,, +139,BOWL,SUM,0,0,0,0,16,7,17,36.65086102485657 +139,CUP,SUM,0,0,0,0,0,2,8,8.48166298866272 +139,SPOON,SUM,0,0,0,0,0,1,7,14.81627106666565 +139,,SUM,0,0,0,0,16,10,32,59.94879508018494 +139,, +140,, +140,BOWL,SUM,0,0,0,0,0,6,42,30.121523141860962 +140,CUP,SUM,0,0,0,0,8,45,43,46.35043692588806 +140,SPOON,SUM,0,0,0,0,0,0,11,17.8267560005188 +140,,SUM,0,0,0,0,8,51,96,94.29871606826782 +140,, +141,, +141,BOWL,SUM,0,0,0,0,0,1,3,10.633234024047852 +141,CUP,SUM,0,0,0,0,0,1,59,26.379220008850098 +141,SPOON,SUM,0,0,0,0,0,3,12,18.004568099975586 +141,,SUM,0,0,0,0,0,5,74,55.017022132873535 +141,, +142,, +142,BOWL,SUM,0,0,0,0,8,2,12,18.266676902770996 +142,CUP,SUM,0,0,0,0,0,4,26,21.563902854919434 +142,SPOON,SUM,0,0,0,0,10,3,13,20.975256204605103 +142,,SUM,0,0,0,0,18,9,51,60.80583596229553 +142,, +143,, +143,BOWL,SUM,0,0,0,0,0,9,6,17.16957998275757 +143,CUP,SUM,1,0,0,1,0,37,75,0.0 +143,SPOON,SUM,0,0,0,0,2,12,17,25.981502056121826 +143,,SUM,1,0,0,1,2,58,98,43.151082038879395 +143,, +144,, +144,BOWL,SUM,0,0,0,0,16,8,34,39.52866506576538 +144,CUP,SUM,0,0,0,0,16,2,23,21.27524709701538 +144,SPOON,SUM,0,0,0,0,8,1,1,17.616525888442993 +144,,SUM,0,0,0,0,40,11,58,78.42043805122375 +144,, +145,, +145,BOWL,SUM,0,0,0,0,0,2,3,12.849640130996704 +145,CUP,SUM,1,0,0,1,8,24,87,0.0 +145,SPOON,SUM,0,0,0,0,0,1,2,11.244107007980347 +145,,SUM,1,0,0,1,8,27,92,24.09374713897705 +145,, +146,, +146,BOWL,SUM,0,0,0,0,0,3,0,10.234657049179077 +146,CUP,SUM,0,0,0,0,0,19,29,20.62289309501648 +146,SPOON,SUM,0,0,0,0,0,23,49,38.500319957733154 +146,,SUM,0,0,0,0,0,45,78,69.35787010192871 +146,, +147,, +147,BOWL,SUM,0,0,0,0,0,8,12,13.28510594367981 +147,CUP,SUM,1,0,0,1,2,40,74,0.0 +147,SPOON,SUM,0,0,0,0,0,2,25,25.192166090011597 +147,,SUM,1,0,0,1,2,50,111,38.477272033691406 +147,, +148,, +148,BOWL,SUM,0,0,0,0,0,1,6,11.094196081161499 +148,CUP,SUM,0,0,0,0,0,9,24,20.91757607460022 +148,SPOON,SUM,0,0,0,0,0,0,5,14.153205156326294 +148,,SUM,0,0,0,0,0,10,35,46.16497731208801 +148,, +149,, +149,BOWL,SUM,0,0,0,0,8,5,16,20.20341992378235 +149,CUP,SUM,0,0,0,0,8,6,18,24.386752128601074 +149,SPOON,SUM,0,0,0,0,0,2,1,11.889926195144653 +149,,SUM,0,0,0,0,16,13,35,56.480098247528076 +149,, +150,, +150,BOWL,SUM,0,0,0,0,0,6,17,16.98019313812256 +150,CUP,SUM,0,0,0,0,0,2,9,10.937092065811157 +150,SPOON,SUM,0,0,0,0,8,6,4,24.452383041381836 +150,,SUM,0,0,0,0,8,14,30,52.36966824531555 +150,, +151,, +151,BOWL,SUM,0,0,0,0,0,0,8,12.454985857009888 +151,CUP,SUM,0,0,0,0,0,0,17,12.730567932128906 +151,SPOON,SUM,0,0,0,0,0,1,4,13.306505918502808 +151,,SUM,0,0,0,0,0,1,29,38.4920597076416 +151,, +152,, +152,BOWL,SUM,0,0,0,0,2,4,16,18.231667041778564 +152,CUP,SUM,0,0,0,0,10,4,66,37.145318031311035 +152,SPOON,SUM,0,0,0,0,10,9,25,33.055875062942505 +152,,SUM,0,0,0,0,22,17,107,88.4328601360321 +152,, +153,, +153,BOWL,SUM,0,0,0,0,2,1,6,15.96946907043457 +153,CUP,SUM,0,0,0,0,0,32,33,27.417587995529175 +153,SPOON,SUM,0,0,0,0,4,2,5,17.205782890319824 +153,,SUM,0,0,0,0,6,35,44,60.59283995628357 +153,, +154,, +154,BOWL,SUM,0,0,0,0,2,3,0,10.080328941345215 +154,CUP,SUM,0,0,0,0,0,2,41,20.34007501602173 +154,SPOON,SUM,0,0,0,0,0,6,26,27.628055095672607 +154,,SUM,0,0,0,0,2,11,67,58.04845905303955 +154,, +155,, +155,BOWL,SUM,0,0,0,0,0,0,6,13.467150926589966 +155,CUP,SUM,0,0,0,0,0,1,18,13.613781929016113 +155,SPOON,SUM,0,0,0,0,0,6,19,32.18480396270752 +155,,SUM,0,0,0,0,0,7,43,59.2657368183136 +155,, +156,, +156,BOWL,SUM,0,0,0,0,0,5,17,21.04158902168274 +156,CUP,SUM,0,0,0,0,0,3,82,36.57166004180908 +156,SPOON,SUM,0,0,0,0,0,10,19,25.63810110092163 +156,,SUM,0,0,0,0,0,18,118,83.25135016441345 +156,, +157,, +157,BOWL,SUM,0,0,0,0,0,0,16,17.766587018966675 +157,CUP,SUM,0,0,0,0,8,3,30,24.87995195388794 +157,SPOON,SUM,0,0,0,0,0,10,46,37.01737713813782 +157,,SUM,0,0,0,0,8,13,92,79.66391611099243 +157,, +158,, +158,BOWL,SUM,0,0,0,0,0,6,15,21.191410064697266 +158,CUP,SUM,0,0,0,0,8,32,85,60.900630950927734 +158,SPOON,SUM,0,0,0,0,24,2,10,26.4148530960083 +158,,SUM,0,0,0,0,32,40,110,108.5068941116333 +158,, +159,, +159,BOWL,SUM,0,0,0,0,0,2,12,18.9167320728302 +159,CUP,SUM,0,0,0,0,16,3,10,22.835608959197998 +159,SPOON,SUM,0,0,0,0,0,7,2,16.162028074264526 +159,,SUM,0,0,0,0,16,12,24,57.914369106292725 +159,, +160,, +160,BOWL,SUM,0,0,0,0,0,6,3,11.267575979232788 +160,CUP,SUM,1,0,0,1,0,39,63,0.0 +160,SPOON,SUM,0,0,0,0,32,4,2,31.042449951171875 +160,,SUM,1,0,0,1,32,49,68,42.31002593040466 +160,, +161,, +161,BOWL,SUM,0,0,0,0,0,1,3,10.332636833190918 +161,CUP,SUM,0,0,0,0,0,1,11,11.9496750831604 +161,SPOON,SUM,0,0,0,0,0,0,0,11.635786056518555 +161,,SUM,0,0,0,0,0,2,14,33.91809797286987 +161,, +162,, +162,BOWL,SUM,0,0,0,0,26,12,10,33.07321906089783 +162,CUP,SUM,0,0,0,0,0,13,62,34.325103998184204 +162,SPOON,SUM,0,0,0,0,0,4,3,16.899513959884644 +162,,SUM,0,0,0,0,26,29,75,84.29783701896667 +162,, +163,, +163,BOWL,SUM,0,0,0,0,0,3,5,11.469825029373169 +163,CUP,SUM,0,0,0,0,16,6,9,22.739792108535767 +163,SPOON,SUM,0,0,0,0,0,0,0,13.11391806602478 +163,,SUM,0,0,0,0,16,9,14,47.323535203933716 +163,, +164,, +164,BOWL,SUM,0,0,0,0,0,0,1,11.422526121139526 +164,CUP,SUM,0,0,0,0,0,2,10,10.313378095626831 +164,SPOON,SUM,0,0,0,0,0,1,1,13.174352884292603 +164,,SUM,0,0,0,0,0,3,12,34.91025710105896 +164,, +165,, +165,BOWL,SUM,0,0,0,0,0,1,7,12.252137899398804 +165,CUP,SUM,0,0,0,0,2,2,36,19.385658979415894 +165,SPOON,SUM,0,0,0,0,0,3,21,25.033273935317993 +165,,SUM,0,0,0,0,2,6,64,56.67107081413269 +165,, +166,, +166,BOWL,SUM,0,0,0,0,0,2,12,15.911175966262817 +166,CUP,SUM,0,0,0,0,8,5,22,23.67223882675171 +166,SPOON,SUM,0,0,0,0,2,2,8,20.443201065063477 +166,,SUM,0,0,0,0,10,9,42,60.026615858078 +166,, +167,, +167,BOWL,SUM,0,0,0,0,0,1,1,9.926022052764893 +167,CUP,SUM,1,0,0,1,0,35,66,0.0 +167,SPOON,SUM,0,0,0,0,0,2,21,24.46167492866516 +167,,SUM,1,0,0,1,0,38,88,34.387696981430054 +167,, +168,, +168,BOWL,SUM,0,0,0,0,0,5,4,11.701008081436157 +168,CUP,SUM,0,0,0,0,2,6,14,16.712023973464966 +168,SPOON,SUM,0,0,0,0,8,3,2,22.794190168380737 +168,,SUM,0,0,0,0,10,14,20,51.20722222328186 +168,, +169,, +169,BOWL,SUM,0,0,0,0,8,2,3,15.930284023284912 +169,CUP,SUM,0,0,0,0,2,1,8,10.336577892303467 +169,SPOON,SUM,0,0,0,0,0,5,5,15.189657926559448 +169,,SUM,0,0,0,0,10,8,16,41.45651984214783 +169,, +170,, +170,BOWL,SUM,0,0,0,0,0,6,14,20.11457586288452 +170,CUP,SUM,0,0,0,0,8,4,15,19.631541967391968 +170,SPOON,SUM,0,0,0,0,14,22,66,58.038501024246216 +170,,SUM,0,0,0,0,22,32,95,97.7846188545227 +170,, +171,, +171,BOWL,SUM,0,0,0,0,0,0,0,8.289591073989868 +171,CUP,SUM,0,0,0,0,0,3,45,22.353986024856567 +171,SPOON,SUM,0,0,0,0,2,3,7,18.332741022109985 +171,,SUM,0,0,0,0,2,6,52,48.97631812095642 +171,, +172,, +172,BOWL,SUM,0,0,0,0,0,5,31,27.118900060653687 +172,CUP,SUM,0,0,0,0,2,2,8,9.765550136566162 +172,SPOON,SUM,0,0,0,0,0,9,3,14.959289789199829 +172,,SUM,0,0,0,0,2,16,42,51.84373998641968 +172,, +173,, +173,BOWL,SUM,0,0,0,0,0,8,14,16.997260808944702 +173,CUP,SUM,0,0,0,0,0,2,43,30.17957615852356 +173,SPOON,SUM,0,0,0,0,0,1,3,13.452217102050781 +173,,SUM,0,0,0,0,0,11,60,60.62905406951904 +173,, +174,, +174,BOWL,SUM,0,0,0,0,0,0,4,10.759026050567627 +174,CUP,SUM,1,0,0,1,0,30,79,0.0 +174,SPOON,SUM,0,0,0,0,24,1,3,30.765685081481934 +174,,SUM,1,0,0,1,24,31,86,41.52471113204956 +174,, +175,, +175,BOWL,SUM,0,0,0,0,0,1,8,18.186880826950073 +175,CUP,SUM,0,0,0,0,8,3,38,25.65276002883911 +175,SPOON,SUM,0,0,0,0,2,3,4,14.843183994293213 +175,,SUM,0,0,0,0,10,7,50,58.6828248500824 +175,, +176,, +176,BOWL,SUM,0,0,0,0,0,2,2,10.991513013839722 +176,CUP,SUM,1,0,0,1,0,47,112,0.0 +176,SPOON,SUM,0,0,0,0,0,2,3,14.966267108917236 +176,,SUM,1,0,0,1,0,51,117,25.957780122756958 +176,, +177,, +177,BOWL,SUM,0,0,0,0,2,0,0,11.351569890975952 +177,CUP,SUM,0,0,0,0,0,2,42,20.28758716583252 +177,SPOON,SUM,0,0,0,0,0,6,22,23.935675144195557 +177,,SUM,0,0,0,0,2,8,64,55.57483220100403 +177,, +178,, +178,BOWL,SUM,0,0,0,0,0,1,4,10.05449390411377 +178,CUP,SUM,0,0,0,0,0,1,49,23.28889298439026 +178,SPOON,SUM,0,0,0,0,0,0,5,14.420377969741821 +178,,SUM,0,0,0,0,0,2,58,47.76376485824585 +178,, +179,, +179,BOWL,SUM,0,0,0,0,0,1,1,10.182291984558105 +179,CUP,SUM,0,0,0,0,8,11,116,53.202078104019165 +179,SPOON,SUM,0,0,0,0,8,3,3,17.940169095993042 +179,,SUM,0,0,0,0,16,15,120,81.32453918457031 +179,, +180,, +180,BOWL,SUM,0,0,0,0,0,1,2,8.654798984527588 +180,CUP,SUM,1,0,0,1,8,32,51,0.0 +180,SPOON,SUM,0,0,0,0,2,6,4,16.32015085220337 +180,,SUM,1,0,0,1,10,39,57,24.974949836730957 +180,, +181,, +181,BOWL,SUM,0,0,0,0,8,6,13,23.683482885360718 +181,CUP,SUM,0,0,0,0,0,6,28,17.591875076293945 +181,SPOON,SUM,0,0,0,0,0,11,31,30.97537612915039 +181,,SUM,0,0,0,0,8,23,72,72.25073409080505 +181,, +182,, +182,BOWL,SUM,0,0,0,0,0,3,1,9.83558988571167 +182,CUP,SUM,0,0,0,0,16,17,142,80.43028593063354 +182,SPOON,SUM,0,0,0,0,18,13,0,22.801637172698975 +182,,SUM,0,0,0,0,34,33,143,113.06751298904419 +182,, +183,, +183,BOWL,SUM,0,0,0,0,0,3,5,13.317797899246216 +183,CUP,SUM,0,0,0,0,0,1,8,8.564082145690918 +183,SPOON,SUM,0,0,0,0,0,3,14,18.68388605117798 +183,,SUM,0,0,0,0,0,7,27,40.56576609611511 +183,, +184,, +184,BOWL,SUM,0,0,0,0,0,2,46,33.73436999320984 +184,CUP,SUM,0,0,0,0,0,6,129,58.1084189414978 +184,SPOON,SUM,0,0,0,0,2,4,0,13.630285024642944 +184,,SUM,0,0,0,0,2,12,175,105.47307395935059 +184,, +185,, +185,BOWL,SUM,0,0,0,0,8,21,10,27.841840028762817 +185,CUP,SUM,0,0,0,0,0,6,73,34.58004903793335 +185,SPOON,SUM,0,0,0,0,16,5,4,25.594264030456543 +185,,SUM,0,0,0,0,24,32,87,88.01615309715271 +185,, +186,, +186,BOWL,SUM,0,0,0,0,0,3,8,13.526717185974121 +186,CUP,SUM,0,0,0,0,8,12,14,24.229010105133057 +186,SPOON,SUM,0,0,0,0,0,83,93,63.071160078048706 +186,,SUM,0,0,0,0,8,98,115,100.82688736915588 +186,, +187,, +187,BOWL,SUM,0,0,0,0,0,5,8,14.419533014297485 +187,CUP,SUM,0,0,0,0,8,2,12,17.036720037460327 +187,SPOON,SUM,0,0,0,0,0,9,16,22.34933304786682 +187,,SUM,0,0,0,0,8,16,36,53.805586099624634 +187,, +188,, +188,BOWL,SUM,0,0,0,0,0,1,8,11.607836961746216 +188,CUP,SUM,1,0,0,1,0,28,71,0.0 +188,SPOON,SUM,0,0,0,0,0,7,0,13.609387159347534 +188,,SUM,1,0,0,1,0,36,79,25.21722412109375 +188,, +189,, +189,BOWL,SUM,0,0,0,0,0,4,1,10.050464868545532 +189,CUP,SUM,0,0,0,0,0,1,8,8.279722213745117 +189,SPOON,SUM,0,0,0,0,0,4,0,11.781866073608398 +189,,SUM,0,0,0,0,0,9,9,30.112053155899048 +189,, +190,, +190,BOWL,SUM,0,0,0,0,2,9,18,19.670212030410767 +190,CUP,SUM,0,0,0,0,8,5,9,14.422899961471558 +190,SPOON,SUM,0,0,0,0,16,1,7,21.740283966064453 +190,,SUM,0,0,0,0,26,15,34,55.83339595794678 +190,, +191,, +191,BOWL,SUM,0,0,0,0,0,1,6,11.301937103271484 +191,CUP,SUM,0,0,0,0,8,15,103,63.32354402542114 +191,SPOON,SUM,0,0,0,0,2,1,7,18.46735906600952 +191,,SUM,0,0,0,0,10,17,116,93.09284019470215 +191,, +192,, +192,BOWL,SUM,0,0,0,0,0,2,15,17.98362112045288 +192,CUP,SUM,0,0,0,0,2,9,23,24.000545024871826 +192,SPOON,SUM,0,0,0,0,2,5,5,16.494772911071777 +192,,SUM,0,0,0,0,4,16,43,58.478939056396484 +192,, +193,, +193,BOWL,SUM,0,0,0,0,4,2,4,16.546796083450317 +193,CUP,SUM,0,0,0,0,0,3,54,26.94080686569214 +193,SPOON,SUM,0,0,0,0,0,0,7,16.86823606491089 +193,,SUM,0,0,0,0,4,5,65,60.355839014053345 +193,, +194,, +194,BOWL,SUM,0,0,0,0,0,1,12,13.475688934326172 +194,CUP,SUM,1,0,0,1,0,34,59,0.0 +194,SPOON,SUM,0,0,0,0,0,3,14,24.018667936325073 +194,,SUM,1,0,0,1,0,38,85,37.494356870651245 +194,, +195,, +195,BOWL,SUM,0,0,0,0,0,10,11,19.34300208091736 +195,CUP,SUM,0,0,0,0,0,5,55,28.6088809967041 +195,SPOON,SUM,0,0,0,0,0,0,2,12.04930591583252 +195,,SUM,0,0,0,0,0,15,68,60.00118899345398 +195,, +196,, +196,BOWL,SUM,0,0,0,0,0,0,8,16.287348985671997 +196,CUP,SUM,0,0,0,0,16,5,17,22.203356981277466 +196,SPOON,SUM,0,0,0,0,0,1,3,12.946736097335815 +196,,SUM,0,0,0,0,16,6,28,51.43744206428528 +196,, +197,, +197,BOWL,SUM,0,0,0,0,0,2,12,12.630919933319092 +197,CUP,SUM,0,0,0,0,0,1,8,8.787729024887085 +197,SPOON,SUM,0,0,0,0,8,3,11,22.58549690246582 +197,,SUM,0,0,0,0,8,6,31,44.004145860672 +197,, +198,, +198,BOWL,SUM,0,0,0,0,0,1,22,22.224371194839478 +198,CUP,SUM,0,0,0,0,8,8,30,27.38603377342224 +198,SPOON,SUM,0,0,0,0,8,2,2,18.59175992012024 +198,,SUM,0,0,0,0,16,11,54,68.20216488838196 +198,, +199,, +199,BOWL,SUM,0,0,0,0,0,4,16,18.091618061065674 +199,CUP,SUM,0,0,0,0,4,8,36,29.826884031295776 +199,SPOON,SUM,0,0,0,0,16,2,18,29.273966789245605 +199,,SUM,0,0,0,0,20,14,70,77.19246888160706 +199,, +200,, +200,BOWL,SUM,0,0,0,0,0,7,1,9.784568071365356 +200,CUP,SUM,1,0,0,1,0,28,59,0.0 +200,SPOON,SUM,0,0,0,0,2,13,12,28.373988151550293 +200,,SUM,1,0,0,1,2,48,72,38.15855622291565 +200,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/HEUR_PR2_new_kitchen.csv b/cram_knowrob/cram_knowrob_vr/experiments/HEUR_PR2_new_kitchen.csv new file mode 100644 index 0000000000..1edf116fb8 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/HEUR_PR2_new_kitchen.csv @@ -0,0 +1,279 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,8,0,0,9.5823979378 +6,CUP,SUM,1,0,0,1,0,6,58,0 +6,SPOON,SUM,0,0,0,0,8,0,1,13.2539708614 +6,,SUM,1,0,0,1,16,6,59,22.8363687992 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,0,1,8,10.0951631069 +7,CUP,SUM,1,0,0,1,0,13,84,0 +7,SPOON,SUM,0,0,0,0,0,3,15,14.3470110893 +7,,SUM,1,0,0,1,0,17,107,24.4421741962 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,0,0,2,7.4805438519 +8,CUP,SUM,0,0,0,0,8,1,6,7.8354759216 +8,SPOON,SUM,0,0,0,0,0,1,2,10.8571770191 +8,,SUM,0,0,0,0,8,2,10,26.1731967926 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,1,16,9.8446819782 +9,CUP,SUM,0,0,0,0,0,0,18,7.3141942024 +9,SPOON,SUM,1,0,1,0,0,59,204,0 +9,,SUM,1,0,1,0,0,60,238,17.1588761806 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,5,18,10.6240510941 +10,CUP,SUM,1,0,0,1,0,7,55,0 +10,SPOON,SUM,0,0,0,0,0,1,3,11.390296936 +10,,SUM,1,0,0,1,0,13,76,22.0143480301 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,8,2,20,14.3920190334 +11,CUP,SUM,0,0,0,0,8,0,5,9.5418350697 +11,SPOON,SUM,0,0,0,0,8,5,21,17.7570359707 +11,,SUM,0,0,0,0,24,7,46,41.6908900738 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,0,1,11,10.1859638691 +12,CUP,SUM,0,0,0,0,0,0,7,4.7669119835 +12,SPOON,SUM,0,0,0,0,0,9,4,11.1963868141 +12,,SUM,0,0,0,0,0,10,22,26.1492626667 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,6,2,12,10.806483984 +13,CUP,SUM,0,0,0,0,0,3,47,23.3329639435 +13,SPOON,SUM,0,0,0,0,0,0,0,10.1093211174 +13,,SUM,0,0,0,0,6,5,59,44.2487690449 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,8,4,48,20.6121971607 +14,CUP,SUM,0,0,0,0,0,1,5,4.6157560349 +14,SPOON,SUM,0,0,0,0,0,1,13,12.9293370247 +14,,SUM,0,0,0,0,8,6,66,38.1572902203 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,0,1,8,8.207529068 +15,CUP,SUM,0,0,0,0,0,0,4,4.3784511089 +15,SPOON,SUM,0,0,0,0,0,5,21,15.1365959644 +15,,SUM,0,0,0,0,0,6,33,27.7225761414 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,9,32,14.228345871 +16,CUP,SUM,1,0,0,1,0,8,73,0 +16,SPOON,SUM,1,0,1,0,0,65,204,0 +16,,SUM,2,0,1,1,0,82,309,14.228345871 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,0,1,28,11.8024818897 +17,CUP,SUM,0,0,0,0,0,1,4,5.2994530201 +17,SPOON,SUM,0,0,0,0,0,0,2,10.8520441055 +17,,SUM,0,0,0,0,0,2,34,27.9539790154 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,8,0,0,9.8588671684 +18,CUP,SUM,0,0,0,0,0,0,11,8.2170598507 +18,SPOON,SUM,0,0,0,0,0,1,4,11.0862112045 +18,,SUM,0,0,0,0,8,1,15,29.1621382236 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,0,0,6.6271390915 +19,CUP,SUM,0,0,0,0,8,2,8,8.6294491291 +19,SPOON,SUM,0,0,0,0,0,11,64,24.5998871326 +19,,SUM,0,0,0,0,8,13,72,39.8564753532 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,0,1,6,7.3166189194 +20,CUP,SUM,0,0,0,0,0,0,11,4.7622139454 +20,SPOON,SUM,0,0,0,0,8,3,6,14.7724540234 +20,,SUM,0,0,0,0,8,4,23,26.8512868881 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,2,48,15.835791111 +21,CUP,SUM,0,0,0,0,0,0,21,7.1564748287 +21,SPOON,SUM,0,0,0,0,0,4,8,12.1405851841 +21,,SUM,0,0,0,0,0,6,77,35.1328511238 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,24,3,12,19.7494959831 +22,CUP,SUM,1,0,1,0,0,27,153,0 +22,SPOON,SUM,0,0,0,0,0,1,5,12.8357138634 +22,,SUM,1,0,1,0,24,31,170,32.5852098465 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,8,11,88,29.130259037 +23,CUP,SUM,0,0,0,0,0,0,4,4.2136259079 +23,SPOON,SUM,0,0,0,0,8,32,8,29.5245668888 +23,,SUM,0,0,0,0,16,43,100,62.8684518337 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,0,1,2,7.4266240597 +24,CUP,SUM,0,0,0,0,16,2,5,13.7178001404 +24,SPOON,SUM,0,0,0,0,0,1,4,11.5791800022 +24,,SUM,0,0,0,0,16,4,11,32.7236042023 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,0,2,13,10.7467770576 +25,CUP,SUM,0,0,0,0,0,1,8,5.8880751133 +25,SPOON,SUM,0,0,0,0,8,0,1,15.0659451485 +25,,SUM,0,0,0,0,8,3,22,31.7007973194 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,0,2,22,12.6748950481 +26,CUP,SUM,0,0,0,0,0,3,5,6.1071968079 +26,SPOON,SUM,0,0,0,0,0,4,20,16.9512310028 +26,,SUM,0,0,0,0,0,9,47,35.7333228588 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,0,2,28,13.2185308933 +27,CUP,SUM,0,0,0,0,0,0,4,5.2444179058 +27,SPOON,SUM,0,0,0,0,0,4,3,13.195928812 +27,,SUM,0,0,0,0,0,6,35,31.6588776112 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,8,0,0,11.9715659618 +28,CUP,SUM,1,0,0,1,0,5,56,0 +28,SPOON,SUM,0,0,0,0,0,1,6,13.1654560566 +28,,SUM,1,0,0,1,8,6,62,25.1370220184 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,1,0,1,0,0,28,204,0 +29,CUP,SUM,0,0,0,0,0,0,10,8.171957016 +29,SPOON,SUM,0,0,0,0,0,2,3,12.5921518803 +29,,SUM,1,0,1,0,0,30,217,20.7641088963 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,0,2,5,9.4371490479 +30,CUP,SUM,0,0,0,0,12,2,4,11.8267807961 +30,SPOON,SUM,0,0,0,0,8,0,8,18.641958952 +30,,SUM,0,0,0,0,20,4,17,39.9058887959 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,8,1,4,12.712086916 +31,CUP,SUM,0,0,0,0,0,1,9,8.254267931 +31,SPOON,SUM,0,0,0,0,0,1,1,11.2560989857 +31,,SUM,0,0,0,0,8,3,14,32.2224538326 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,0,1,5,9.9724159241 +32,CUP,SUM,0,0,0,0,0,0,6,7.7643449306 +32,SPOON,SUM,1,0,1,0,8,47,204,0 +32,,SUM,1,0,1,0,8,48,215,17.7367608547 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,1,8,10.1287560463 +33,CUP,SUM,0,0,0,0,0,1,9,7.3343479633 +33,SPOON,SUM,0,0,0,0,0,2,2,13.0352740288 +33,,SUM,0,0,0,0,0,4,19,30.4983780384 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,0,0,18,12.1588509083 +34,CUP,SUM,0,0,0,0,0,1,3,6.3981769085 +34,SPOON,SUM,0,0,0,0,0,2,9,13.5723619461 +34,,SUM,0,0,0,0,0,3,30,32.1293897629 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,0,1,14,14.7989759445 +35,CUP,SUM,0,0,0,0,0,2,20,15.1776599884 +35,SPOON,SUM,0,0,0,0,0,0,3,12.9814288616 +35,,SUM,0,0,0,0,0,3,37,42.9580647945 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,0,0,5,10.5192980766 +36,CUP,SUM,0,0,0,0,8,8,39,30.9816598892 +36,SPOON,SUM,0,0,0,0,0,1,4,13.8343992233 +36,,SUM,0,0,0,0,8,9,48,55.3353571892 +36,,,,,,,,,, +37,,,,,,,,,, +37,BOWL,SUM,0,0,0,0,0,2,12,11.50918293 +37,CUP,SUM,0,0,0,0,0,2,6,8.082597971 +37,SPOON,SUM,0,0,0,0,0,0,2,13.6201291084 +37,,SUM,0,0,0,0,0,4,20,33.2119100094 +37,,,,,,,,,, +38,,,,,,,,,, +38,BOWL,SUM,0,0,0,0,0,4,13,11.4918239117 +38,CUP,SUM,0,0,0,0,0,2,6,8.0135340691 +38,SPOON,SUM,0,0,0,0,0,1,1,12.1667330265 +38,,SUM,0,0,0,0,0,7,20,31.6720910072 +38,,,,,,,,,, +39,,,,,,,,,, +39,BOWL,SUM,0,0,0,0,0,4,10,11.3176591396 +39,CUP,SUM,0,0,0,0,0,1,6,6.8762130737 +39,SPOON,SUM,0,0,0,0,0,2,5,13.6390430927 +39,,SUM,0,0,0,0,0,7,21,31.8329153061 +39,,,,,,,,,, +40,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,16,1,0,19.7047579288 +40,CUP,SUM,1,0,0,1,0,2,54,0 +40,SPOON,SUM,0,0,0,0,0,2,4,13.0133318901 +40,,SUM,1,0,0,1,16,5,58,32.718089819 +40,,,,,,,,,, +41,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,8,10,25,19.3509571552 +41,CUP,SUM,0,0,0,0,0,0,4,5.9179217815 +41,SPOON,SUM,0,0,0,0,0,0,0,12.4402720928 +41,,SUM,0,0,0,0,8,10,29,37.7091510296 +41,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,8,0,4,15.1256668568 +42,CUP,SUM,0,0,0,0,0,1,7,5.7682189941 +42,SPOON,SUM,0,0,0,0,0,0,0,11.3719038963 +42,,SUM,0,0,0,0,8,1,11,32.2657897472 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,8,3,9,17.9245810509 +43,CUP,SUM,0,0,0,0,0,2,6,9.6863219738 +43,SPOON,SUM,0,0,0,0,8,2,14,20.4641160965 +43,,SUM,0,0,0,0,16,7,29,48.0750191212 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,0,7,13,12.3107540607 +44,CUP,SUM,1,0,1,0,0,10,153,0 +44,SPOON,SUM,0,0,0,0,0,5,25,18.0899500847 +44,,SUM,1,0,1,0,0,22,191,30.4007041454 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,8,0,4,16.2975170612 +45,CUP,SUM,0,0,0,0,0,2,9,7.8931410313 +45,SPOON,SUM,0,0,0,0,0,0,1,12.8005161285 +45,,SUM,0,0,0,0,8,2,14,36.991174221 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,16,4,13,22.1801760197 +46,CUP,SUM,1,0,0,1,0,13,66,0 +46,SPOON,SUM,0,0,0,0,0,1,0,12.4143979549 +46,,SUM,1,0,0,1,16,18,79,34.5945739746 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,0,0,0,0,16,1,8,22.0051560402 +47,CUP,SUM,0,0,0,0,0,1,7,6.6506478786 +47,SPOON,SUM,0,0,0,0,0,2,5,14.0658380985 +47,,SUM,0,0,0,0,16,4,20,42.7216420174 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,0,2,40,16.6058559418 +48,CUP,SUM,0,0,0,0,8,0,4,13.3970389366 +48,SPOON,SUM,0,0,0,0,0,2,8,14.4070467949 +48,,SUM,0,0,0,0,8,4,52,44.4099416733 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,0,5,5,9.4626951218 +49,CUP,SUM,0,0,0,0,8,1,20,16.3059859276 +49,SPOON,SUM,0,0,0,0,8,4,1,19.7865259647 +49,,SUM,0,0,0,0,16,10,26,45.5552070141 +49,,,,,,,,,, +50,,,,,,,,,, +50,BOWL,SUM,0,0,0,0,0,0,5,10.9654529095 +50,CUP,SUM,0,0,0,0,0,0,4,6.8033099174 +50,SPOON,SUM,0,0,0,0,0,1,20,16.4295210838 +50,,SUM,0,0,0,0,0,1,29,34.1982839108 +50,,,,,,,,,, +51,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,0,4,21,13.6529648304 +51,CUP,SUM,0,0,0,0,0,3,15,9.5032761097 +51,SPOON,SUM,0,0,0,0,0,4,12,14.3091821671 +51,,SUM,0,0,0,0,0,11,48,37.4654231071 +51,,,,,,,,,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/PR2_Hr_Sim.csv b/cram_knowrob/cram_knowrob_vr/experiments/PR2_Hr_Sim.csv new file mode 100644 index 0000000000..d99696fbb6 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/PR2_Hr_Sim.csv @@ -0,0 +1,1203 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,1,18,12.8868250847 +0,CUP,SUM,0,0,0,0,0,0,17,9.2035570145 +0,SPOON,SUM,0,0,0,0,20,0,0,17.2296690941 +0,,SUM,0,0,0,0,20,1,35,39.3200511932 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,0,1,4,6.8639597893 +1,CUP,SUM,0,0,0,0,20,2,6,13.6228618622 +1,SPOON,SUM,0,0,0,0,12,8,27,20.7887630463 +1,,SUM,0,0,0,0,32,11,37,41.2755846977 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,0,1,16,9.6965088844 +2,CUP,SUM,0,0,0,0,0,0,2,4.244836092 +2,SPOON,SUM,0,0,0,0,16,2,3,17.2406001091 +2,,SUM,0,0,0,0,16,3,21,31.1819450855 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,8,0,8,10.5855000019 +3,CUP,SUM,0,0,0,0,0,3,18,6.4490301609 +3,SPOON,SUM,0,0,0,0,0,0,4,9.9857809544 +3,,SUM,0,0,0,0,8,3,30,27.0203111172 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,8,2,32,15.4768509865 +4,CUP,SUM,0,0,0,0,0,0,22,9.6204090118 +4,SPOON,SUM,0,0,0,0,0,4,17,12.9086449146 +4,,SUM,0,0,0,0,8,6,71,38.0059049129 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,0,4,3,7.1034610271 +5,CUP,SUM,0,0,0,0,8,1,10,10.270373106 +5,SPOON,SUM,0,0,0,0,32,2,28,30.3356311321 +5,,SUM,0,0,0,0,40,7,41,47.7094652653 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,0,1,8,7.9186930656 +6,CUP,SUM,0,0,0,0,0,0,4,4.2926778793 +6,SPOON,SUM,0,0,0,0,16,0,0,15.946710825 +6,,SUM,0,0,0,0,16,1,12,28.1580817699 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,0,1,1,6.7906441689 +7,CUP,SUM,0,0,0,0,48,3,2,25.1059589386 +7,SPOON,SUM,0,0,0,0,8,0,2,13.7524030209 +7,,SUM,0,0,0,0,56,4,5,45.6490061283 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,0,1,18,12.3100121021 +8,CUP,SUM,0,0,0,0,0,0,17,9.0084381104 +8,SPOON,SUM,0,0,0,0,20,0,0,17.4890048504 +8,,SUM,0,0,0,0,20,1,35,38.8074550629 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,1,4,6.8408610821 +9,CUP,SUM,0,0,0,0,20,2,6,13.4904181957 +9,SPOON,SUM,0,0,0,0,12,8,27,20.478000164 +9,,SUM,0,0,0,0,32,11,37,40.8092794418 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,1,16,9.6217720509 +10,CUP,SUM,0,0,0,0,0,0,2,4.0521671772 +10,SPOON,SUM,0,0,0,0,16,2,3,17.4971330166 +10,,SUM,0,0,0,0,16,3,21,31.1710722446 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,8,0,8,10.9636209011 +11,CUP,SUM,0,0,0,0,0,3,18,6.2743570805 +11,SPOON,SUM,0,0,0,0,0,0,4,10.1082618237 +11,,SUM,0,0,0,0,8,3,30,27.3462398052 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,8,2,32,15.3894898891 +12,CUP,SUM,0,0,0,0,0,0,22,9.6602289677 +12,SPOON,SUM,0,0,0,0,0,4,17,13.0366840363 +12,,SUM,0,0,0,0,8,6,71,38.0864028931 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,0,4,3,6.8435721397 +13,CUP,SUM,0,0,0,0,8,1,10,9.9836978912 +13,SPOON,SUM,0,0,0,0,32,2,28,29.9146649837 +13,,SUM,0,0,0,0,40,7,41,46.7419350147 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,0,1,8,7.85947299 +14,CUP,SUM,0,0,0,0,0,0,4,4.1716580391 +14,SPOON,SUM,0,0,0,0,16,0,0,16.08466506 +14,,SUM,0,0,0,0,16,1,12,28.1157960892 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,0,1,1,6.5900440216 +15,CUP,SUM,0,0,0,0,48,3,2,25.1881930828 +15,SPOON,SUM,0,0,0,0,8,0,2,13.6236560345 +15,,SUM,0,0,0,0,56,4,5,45.4018931389 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,0,0,6.1940560341 +16,CUP,SUM,0,0,0,0,8,0,41,24.6789951324 +16,SPOON,SUM,0,0,0,0,0,2,16,12.6928331852 +16,,SUM,0,0,0,0,8,2,57,43.5658843517 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,0,2,2,6.2126150131 +17,CUP,SUM,0,0,0,0,0,3,44,22.9514181614 +17,SPOON,SUM,0,0,0,0,0,0,5,10.3252391815 +17,,SUM,0,0,0,0,0,5,51,39.489272356 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,0,0,0,6.0750510693 +18,CUP,SUM,0,0,0,0,0,2,2,4.0837421417 +18,SPOON,SUM,0,0,0,0,0,0,6,10.7504999638 +18,,SUM,0,0,0,0,0,2,8,20.9092931747 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,2,13,9.0930099487 +19,CUP,SUM,0,0,0,0,0,1,12,7.0760650635 +19,SPOON,SUM,0,0,0,0,0,0,2,10.2661738396 +19,,SUM,0,0,0,0,0,3,27,26.4352488518 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,0,12,21,10.9524009228 +20,CUP,SUM,1,0,0,1,24,1,67,0 +20,SPOON,SUM,0,0,0,0,0,2,4,10.2108559608 +20,,SUM,1,0,0,1,24,15,92,21.1632568836 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,0,4,6.7599239349 +21,CUP,SUM,0,0,0,0,12,3,11,11.4421658516 +21,SPOON,SUM,0,0,0,0,8,1,0,12.6718318462 +21,,SUM,0,0,0,0,20,4,15,30.8739216328 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,8,32,184,46.5364570618 +22,CUP,SUM,0,0,0,0,0,1,7,4.8348150253 +22,SPOON,SUM,0,0,0,0,0,2,0,9.5352180004 +22,,SUM,0,0,0,0,8,35,191,60.9064900875 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,3,48,16.2012979984 +23,CUP,SUM,0,0,0,0,0,0,2,4.2232899666 +23,SPOON,SUM,0,0,0,0,0,0,0,9.6906650066 +23,,SUM,0,0,0,0,0,3,50,30.1152529716 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,0,2,11,8.9214689732 +24,CUP,SUM,0,0,0,0,0,9,29,17.936727047 +24,SPOON,SUM,0,0,0,0,0,6,32,16.6180520058 +24,,SUM,0,0,0,0,0,17,72,43.4762480259 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,0,1,22,10.6977190971 +25,CUP,SUM,0,0,0,0,12,2,24,18.6047210693 +25,SPOON,SUM,0,0,0,0,8,0,5,14.220635891 +25,,SUM,0,0,0,0,20,3,51,43.5230760574 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,0,1,5,7.5495531559 +26,CUP,SUM,0,0,0,0,0,0,18,8.5182650089 +26,SPOON,SUM,0,0,0,0,0,0,9,11.5531489849 +26,,SUM,0,0,0,0,0,1,32,27.6209671497 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,0,17,60,18.723747015 +27,CUP,SUM,1,0,0,1,0,0,51,0 +27,SPOON,SUM,0,0,0,0,10,4,16,18.2132298946 +27,,SUM,1,0,0,1,10,21,127,36.9369769096 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,0,0,4,7.2506151199 +28,CUP,SUM,0,0,0,0,16,2,7,14.5965850353 +28,SPOON,SUM,0,0,0,0,0,2,18,13.1354808807 +28,,SUM,0,0,0,0,16,4,29,34.982681036 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,0,0,0,6.2490329742 +29,CUP,SUM,0,0,0,0,0,0,15,9.4839229584 +29,SPOON,SUM,0,0,0,0,0,1,4,10.6826291084 +29,,SUM,0,0,0,0,0,1,19,26.415585041 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,8,9,28,15.6901190281 +30,CUP,SUM,1,0,0,1,0,2,59,0 +30,SPOON,SUM,0,0,0,0,24,15,33,28.4713468552 +30,,SUM,1,0,0,1,32,26,120,44.1614658833 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,0,3,36,13.9809160233 +31,CUP,SUM,0,0,0,0,8,1,11,9.8417890072 +31,SPOON,SUM,0,0,0,0,0,2,9,12.6882638931 +31,,SUM,0,0,0,0,8,6,56,36.5109689236 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,0,6,8,9.2241950035 +32,CUP,SUM,0,0,0,0,0,1,2,4.9750339985 +32,SPOON,SUM,0,0,0,0,2,2,4,12.3001558781 +32,,SUM,0,0,0,0,2,9,14,26.4993848801 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,0,1,7.4829289913 +33,CUP,SUM,0,0,0,0,16,0,13,14.7805190086 +33,SPOON,SUM,0,0,0,0,8,0,13,17.9933419228 +33,,SUM,0,0,0,0,24,0,27,40.2567899227 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,0,1,0,7.2762839794 +34,CUP,SUM,1,0,0,1,0,0,66,0 +34,SPOON,SUM,0,0,0,0,0,0,5,12.9847791195 +34,,SUM,1,0,0,1,0,1,71,20.2610630989 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,8,2,10,13.1548578739 +35,CUP,SUM,0,0,0,0,6,0,5,8.30519104 +35,SPOON,SUM,0,0,0,0,8,0,0,15.1683578491 +35,,SUM,0,0,0,0,22,2,15,36.6284067631 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,0,1,20,11.2426829338 +36,CUP,SUM,0,0,0,0,0,2,18,9.8954041004 +36,SPOON,SUM,0,0,0,0,0,2,0,11.3789019585 +36,,SUM,0,0,0,0,0,5,38,32.5169889927 +36,,,,,,,,,, +37,,,,,,,,,, +37,BOWL,SUM,0,0,0,0,0,0,0,7.4002969265 +37,CUP,SUM,0,0,0,0,8,0,42,27.474957943 +37,SPOON,SUM,0,0,0,0,0,2,4,12.578772068 +37,,SUM,0,0,0,0,8,2,46,47.4540269375 +37,,,,,,,,,, +38,,,,,,,,,, +38,BOWL,SUM,0,0,0,0,0,18,176,43.6697130203 +38,CUP,SUM,0,0,0,0,12,1,6,12.0623941422 +38,SPOON,SUM,0,0,0,0,0,4,8,13.7960588932 +38,,SUM,0,0,0,0,12,23,190,69.5281660557 +38,,,,,,,,,, +39,,,,,,,,,, +39,BOWL,SUM,0,0,0,0,0,0,0,7.875357151 +39,CUP,SUM,0,0,0,0,0,0,43,23.2071499825 +39,SPOON,SUM,0,0,0,0,0,0,0,10.6997258663 +39,,SUM,0,0,0,0,0,0,43,41.7822329998 +39,,,,,,,,,, +40,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,0,1,0,7.9824428558 +40,CUP,SUM,0,0,0,0,0,0,7,6.7208909988 +40,SPOON,SUM,0,0,0,0,0,12,47,22.6448988914 +40,,SUM,0,0,0,0,0,13,54,37.3482327461 +40,,,,,,,,,, +41,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,0,0,3,8.5203299522 +41,CUP,SUM,0,0,0,0,14,1,6,13.8611290455 +41,SPOON,SUM,0,0,0,0,0,0,5,13.102104187 +41,,SUM,0,0,0,0,14,1,14,35.4835631847 +41,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,0,0,4,8.4169311523 +42,CUP,SUM,0,0,0,0,16,0,15,19.3218491077 +42,SPOON,SUM,0,0,0,0,0,4,11,14.0356647968 +42,,SUM,0,0,0,0,16,4,30,41.7744450569 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,12,0,0,14.6747610569 +43,CUP,SUM,0,0,0,0,8,2,21,16.2153348923 +43,SPOON,SUM,0,0,0,0,0,0,0,11.859197855 +43,,SUM,0,0,0,0,20,2,21,42.7492938042 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,0,6,84,25.3971431255 +44,CUP,SUM,0,0,0,0,0,2,17,13.0895380974 +44,SPOON,SUM,0,0,0,0,0,1,4,11.9813818932 +44,,SUM,0,0,0,0,0,9,105,50.4680631161 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,0,5,30,14.9458658695 +45,CUP,SUM,0,0,0,0,8,3,33,24.0518400669 +45,SPOON,SUM,0,0,0,0,8,5,4,18.1331820488 +45,,SUM,0,0,0,0,16,13,67,57.1308879852 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,0,0,1,9.0187418461 +46,CUP,SUM,0,0,0,0,0,0,7,7.3258450031 +46,SPOON,SUM,0,0,0,0,0,1,13,14.2071149349 +46,,SUM,0,0,0,0,0,1,21,30.5517017841 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,0,0,0,0,12,0,5,15.9248719215 +47,CUP,SUM,1,0,0,1,8,0,51,0 +47,SPOON,SUM,0,0,0,0,16,3,4,22.8173220158 +47,,SUM,1,0,0,1,36,3,60,38.7421939373 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,0,6,41,16.0754420757 +48,CUP,SUM,0,0,0,0,0,0,6,5.3779389858 +48,SPOON,SUM,0,0,0,0,0,2,0,12.1025829315 +48,,SUM,0,0,0,0,0,8,47,33.5559639931 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,0,4,18,11.9138839245 +49,CUP,SUM,0,0,0,0,8,5,54,37.5192821026 +49,SPOON,SUM,0,0,0,0,28,4,0,26.1263279915 +49,,SUM,0,0,0,0,36,13,72,75.5594940186 +49,,,,,,,,,, +50,,,,,,,,,, +50,BOWL,SUM,1,0,1,0,4,22,196,0 +50,CUP,SUM,1,0,0,1,24,2,51,0 +50,SPOON,SUM,0,0,0,0,24,7,1,28.0768549442 +50,,SUM,2,0,1,1,52,31,248,28.0768549442 +50,,,,,,,,,, +51,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,0,0,0,8.3131949902 +51,CUP,SUM,0,0,0,0,0,0,2,6.1342489719 +51,SPOON,SUM,0,0,0,0,0,0,2,12.7308900356 +51,,SUM,0,0,0,0,0,0,4,27.1783339977 +51,,,,,,,,,, +52,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,16,0,0,18.3324708939 +52,CUP,SUM,0,0,0,0,12,0,2,13.3191359043 +52,SPOON,SUM,0,0,0,0,0,1,0,11.3959951401 +52,,SUM,0,0,0,0,28,1,2,43.0476019382 +52,,,,,,,,,, +53,,,,,,,,,, +53,BOWL,SUM,0,0,0,0,8,3,21,17.7842929363 +53,CUP,SUM,0,0,0,0,0,3,21,12.0741188526 +53,SPOON,SUM,0,0,0,0,0,2,13,14.5062360764 +53,,SUM,0,0,0,0,8,8,55,44.3646478653 +53,,,,,,,,,, +54,,,,,,,,,, +54,BOWL,SUM,0,0,0,0,0,0,8,8.9383840561 +54,CUP,SUM,0,0,0,0,0,2,23,13.6544439793 +54,SPOON,SUM,0,0,0,0,0,1,0,12.0926930904 +54,,SUM,0,0,0,0,0,3,31,34.6855211258 +54,,,,,,,,,, +55,,,,,,,,,, +55,BOWL,SUM,0,0,0,0,0,4,10,10.1304860115 +55,CUP,SUM,0,0,0,0,0,2,7,6.3867139816 +55,SPOON,SUM,0,0,0,0,0,1,10,12.9298710823 +55,,SUM,0,0,0,0,0,7,27,29.4470710754 +55,,,,,,,,,, +56,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,0,2,5,9.7557339668 +56,CUP,SUM,0,0,0,0,0,1,2,5.9185678959 +56,SPOON,SUM,0,0,0,0,0,1,4,12.5263831615 +56,,SUM,0,0,0,0,0,4,11,28.2006850243 +56,,,,,,,,,, +57,,,,,,,,,, +57,BOWL,SUM,0,0,0,0,0,3,8,10.7106730938 +57,CUP,SUM,0,0,0,0,0,1,3,6.6652328968 +57,SPOON,SUM,0,0,0,0,0,10,36,20.0421209335 +57,,SUM,0,0,0,0,0,14,47,37.4180269241 +57,,,,,,,,,, +58,,,,,,,,,, +58,BOWL,SUM,0,0,0,0,0,2,16,9.6682059765 +58,CUP,SUM,0,0,0,0,0,2,6,4.4126329422 +58,SPOON,SUM,0,0,0,0,0,1,16,12.9875209332 +58,,SUM,0,0,0,0,0,5,38,27.0683598518 +58,,,,,,,,,, +59,,,,,,,,,, +59,BOWL,SUM,0,0,0,0,0,11,60,18.8260300159 +59,CUP,SUM,0,0,0,0,16,1,33,21.8232059479 +59,SPOON,SUM,0,0,0,0,0,1,0,9.1085929871 +59,,SUM,0,0,0,0,16,13,93,49.7578289509 +59,,,,,,,,,, +60,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,8,2,5,10.4012200832 +60,CUP,SUM,0,0,0,0,0,1,8,4.545427084 +60,SPOON,SUM,0,0,0,0,0,0,3,10.4259700775 +60,,SUM,0,0,0,0,8,3,16,25.3726172447 +60,,,,,,,,,, +61,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,0,0,5,7.3087821007 +61,CUP,SUM,0,0,0,0,8,10,65,38.4326338768 +61,SPOON,SUM,0,0,0,0,0,2,33,16.0271379948 +61,,SUM,0,0,0,0,8,12,103,61.7685539722 +61,,,,,,,,,, +62,,,,,,,,,, +62,BOWL,SUM,0,0,0,0,0,0,0,6.1273419857 +62,CUP,SUM,0,0,0,0,0,1,18,9.1771271229 +62,SPOON,SUM,0,0,0,0,0,2,5,10.6948068142 +62,,SUM,0,0,0,0,0,3,23,25.9992759228 +62,,,,,,,,,, +63,,,,,,,,,, +63,BOWL,SUM,0,0,0,0,0,0,12,8.4758760929 +63,CUP,SUM,0,0,0,0,0,0,26,14.4389801025 +63,SPOON,SUM,0,0,0,0,0,0,2,10.2660491467 +63,,SUM,0,0,0,0,0,0,40,33.1809053421 +63,,,,,,,,,, +64,,,,,,,,,, +64,BOWL,SUM,0,0,0,0,8,0,0,9.5460531712 +64,CUP,SUM,0,0,0,0,0,4,8,5.5689270496 +64,SPOON,SUM,0,0,0,0,0,0,0,9.5279388428 +64,,SUM,0,0,0,0,8,4,8,24.6429190636 +64,,,,,,,,,, +65,,,,,,,,,, +65,BOWL,SUM,0,0,0,0,32,1,0,20.4473941326 +65,CUP,SUM,0,0,0,0,16,0,2,10.4875361919 +65,SPOON,SUM,0,0,0,0,0,0,1,9.8783550262 +65,,SUM,0,0,0,0,48,1,3,40.8132853508 +65,,,,,,,,,, +66,,,,,,,,,, +66,BOWL,SUM,0,0,0,0,0,1,24,10.8991589546 +66,CUP,SUM,0,0,0,0,0,2,47,24.1746790409 +66,SPOON,SUM,0,0,0,0,0,4,10,12.3862469196 +66,,SUM,0,0,0,0,0,7,81,47.4600849152 +66,,,,,,,,,, +67,,,,,,,,,, +67,BOWL,SUM,0,0,0,0,8,0,8,11.515761137 +67,CUP,SUM,1,0,0,1,8,0,57,0 +67,SPOON,SUM,0,0,0,0,0,0,9,12.0420877934 +67,,SUM,1,0,0,1,16,0,74,23.5578489304 +67,,,,,,,,,, +68,,,,,,,,,, +68,BOWL,SUM,0,0,0,0,0,3,6,8.307336092 +68,CUP,SUM,0,0,0,0,0,1,5,4.94607687 +68,SPOON,SUM,0,0,0,0,8,0,5,14.2884299755 +68,,SUM,0,0,0,0,8,4,16,27.5418429375 +68,,,,,,,,,, +69,,,,,,,,,, +69,BOWL,SUM,0,0,0,0,8,10,66,22.4142298698 +69,CUP,SUM,0,0,0,0,0,1,44,19.1177401543 +69,SPOON,SUM,0,0,0,0,0,0,16,13.3245418072 +69,,SUM,0,0,0,0,8,11,126,54.8565118313 +69,,,,,,,,,, +70,,,,,,,,,, +70,BOWL,SUM,0,0,0,0,0,1,4,7.6118881702 +70,CUP,SUM,0,0,0,0,0,0,3,5.4900989532 +70,SPOON,SUM,0,0,0,0,8,9,44,24.5959160328 +70,,SUM,0,0,0,0,8,10,51,37.6979031563 +70,,,,,,,,,, +71,,,,,,,,,, +71,BOWL,SUM,0,0,0,0,0,0,24,11.3888509274 +71,CUP,SUM,0,0,0,0,8,6,72,36.8825199604 +71,SPOON,SUM,0,0,0,0,0,3,6,13.2844769955 +71,,SUM,0,0,0,0,8,9,102,61.5558478832 +71,,,,,,,,,, +72,,,,,,,,,, +72,BOWL,SUM,0,0,0,0,0,1,14,10.4121859074 +72,CUP,SUM,1,0,0,1,56,4,61,0 +72,SPOON,SUM,0,0,0,0,8,0,0,15.0754439831 +72,,SUM,1,0,0,1,64,5,75,25.4876298904 +72,,,,,,,,,, +73,,,,,,,,,, +73,BOWL,SUM,0,0,0,0,0,5,29,14.3728370667 +73,CUP,SUM,0,0,0,0,0,0,6,6.3985991478 +73,SPOON,SUM,0,0,0,0,8,0,4,15.9090890884 +73,,SUM,0,0,0,0,8,5,39,36.6805253029 +73,,,,,,,,,, +74,,,,,,,,,, +74,BOWL,SUM,0,0,0,0,12,1,8,14.9388189316 +74,CUP,SUM,0,0,0,0,0,0,12,9.2944719791 +74,SPOON,SUM,0,0,0,0,36,0,5,32.0581109524 +74,,SUM,0,0,0,0,48,1,25,56.2914018631 +74,,,,,,,,,, +75,,,,,,,,,, +75,BOWL,SUM,0,0,0,0,8,0,0,12.1203420162 +75,CUP,SUM,0,0,0,0,0,0,20,11.7941319942 +75,SPOON,SUM,0,0,0,0,0,1,0,11.0267679691 +75,,SUM,0,0,0,0,8,1,20,34.9412419796 +75,,,,,,,,,, +76,,,,,,,,,, +76,BOWL,SUM,0,0,0,0,0,0,1,8.1389110088 +76,CUP,SUM,0,0,0,0,0,0,4,6.4923481941 +76,SPOON,SUM,0,0,0,0,28,3,9,30.3912341595 +76,,SUM,0,0,0,0,28,3,14,45.0224933624 +76,,,,,,,,,, +77,,,,,,,,,, +77,BOWL,SUM,0,0,0,0,0,6,4,8.3913090229 +77,CUP,SUM,0,0,0,0,8,1,2,11.5134909153 +77,SPOON,SUM,0,0,0,0,0,2,4,12.4963438511 +77,,SUM,0,0,0,0,8,9,10,32.4011437893 +77,,,,,,,,,, +78,,,,,,,,,, +78,BOWL,SUM,0,0,0,0,8,1,4,13.8900771141 +78,CUP,SUM,0,0,0,0,0,0,10,6.7872481346 +78,SPOON,SUM,0,0,0,0,0,2,9,14.3729419708 +78,,SUM,0,0,0,0,8,3,23,35.0502672195 +78,,,,,,,,,, +79,,,,,,,,,, +79,BOWL,SUM,0,0,0,0,0,0,8,10.1590471268 +79,CUP,SUM,0,0,0,0,0,1,8,7.7371120453 +79,SPOON,SUM,0,0,0,0,0,0,4,13.0731239319 +79,,SUM,0,0,0,0,0,1,20,30.9692831039 +79,,,,,,,,,, +80,,,,,,,,,, +80,BOWL,SUM,0,0,0,0,0,0,0,9.0746631622 +80,CUP,SUM,0,0,0,0,0,1,14,9.6896378994 +80,SPOON,SUM,0,0,0,0,0,0,5,13.2256140709 +80,,SUM,0,0,0,0,0,1,19,31.9899151325 +80,,,,,,,,,, +81,,,,,,,,,, +81,BOWL,SUM,0,0,0,0,16,0,0,17.2518389225 +81,CUP,SUM,1,0,0,1,0,0,51,0 +81,SPOON,SUM,0,0,0,0,4,7,36,19.7306330204 +81,,SUM,1,0,0,1,20,7,87,36.9824719429 +81,,,,,,,,,, +82,,,,,,,,,, +82,BOWL,SUM,0,0,0,0,0,3,4,9.1886980534 +82,CUP,SUM,0,0,0,0,0,2,4,6.7278599739 +82,SPOON,SUM,0,0,0,0,0,0,0,11.8397378922 +82,,SUM,0,0,0,0,0,5,8,27.7562959194 +82,,,,,,,,,, +83,,,,,,,,,, +83,BOWL,SUM,0,0,0,0,0,2,8,10.1684780121 +83,CUP,SUM,0,0,0,0,8,2,39,25.5376429558 +83,SPOON,SUM,0,0,0,0,0,1,8,13.0391850471 +83,,SUM,0,0,0,0,8,5,55,48.745306015 +83,,,,,,,,,, +84,,,,,,,,,, +84,BOWL,SUM,0,0,0,0,0,1,0,8.1100280285 +84,CUP,SUM,0,0,0,0,0,0,23,15.5192451477 +84,SPOON,SUM,0,0,0,0,10,5,28,22.8591759205 +84,,SUM,0,0,0,0,10,6,51,46.4884490967 +84,,,,,,,,,, +85,,,,,,,,,, +85,BOWL,SUM,0,0,0,0,8,8,20,18.5176510811 +85,CUP,SUM,0,0,0,0,0,0,2,5.8213839531 +85,SPOON,SUM,0,0,0,0,0,2,9,12.9672119617 +85,,SUM,0,0,0,0,8,10,31,37.3062469959 +85,,,,,,,,,, +86,,,,,,,,,, +86,BOWL,SUM,0,0,0,0,0,1,43,17.2407739162 +86,CUP,SUM,0,0,0,0,0,2,25,10.7536950111 +86,SPOON,SUM,0,0,0,0,2,8,4,14.8476498127 +86,,SUM,0,0,0,0,2,11,72,42.8421187401 +86,,,,,,,,,, +87,,,,,,,,,, +87,BOWL,SUM,0,0,0,0,8,1,20,17.003360033 +87,CUP,SUM,0,0,0,0,0,1,11,9.058161974 +87,SPOON,SUM,0,0,0,0,0,2,4,12.9930310249 +87,,SUM,0,0,0,0,8,4,35,39.0545530319 +87,,,,,,,,,, +88,,,,,,,,,, +88,BOWL,SUM,0,0,0,0,0,0,4,8.7637939453 +88,CUP,SUM,0,0,0,0,0,0,10,8.2956438065 +88,SPOON,SUM,0,0,0,0,8,4,21,22.1916399002 +88,,SUM,0,0,0,0,8,4,35,39.251077652 +88,,,,,,,,,, +89,,,,,,,,,, +89,BOWL,SUM,0,0,0,0,0,1,5,10.2421908379 +89,CUP,SUM,0,0,0,0,0,0,35,21.5128278732 +89,SPOON,SUM,0,0,0,0,0,1,9,13.2498879433 +89,,SUM,0,0,0,0,0,2,49,45.0049066544 +89,,,,,,,,,, +90,,,,,,,,,, +90,BOWL,SUM,0,0,0,0,0,3,0,7.7414979935 +90,CUP,SUM,0,0,0,0,0,0,2,6.3719689846 +90,SPOON,SUM,0,0,0,0,0,8,40,19.277338028 +90,,SUM,0,0,0,0,0,11,42,33.390805006 +90,,,,,,,,,, +91,,,,,,,,,, +91,BOWL,SUM,0,0,0,0,0,0,0,8.55316782 +91,CUP,SUM,0,0,0,0,8,4,6,13.5152390003 +91,SPOON,SUM,0,0,0,0,0,2,4,11.0995769501 +91,,SUM,0,0,0,0,8,6,10,33.1679837704 +91,,,,,,,,,, +92,,,,,,,,,, +92,BOWL,SUM,0,0,0,0,0,3,8,10.5328698158 +92,CUP,SUM,1,0,0,1,0,1,51,0 +92,SPOON,SUM,0,0,0,0,0,1,2,12.5029761791 +92,,SUM,1,0,0,1,0,5,61,23.0358459949 +92,,,,,,,,,, +93,,,,,,,,,, +93,BOWL,SUM,0,0,0,0,8,3,0,15.2488288879 +93,CUP,SUM,0,0,0,0,0,0,8,8.2403371334 +93,SPOON,SUM,0,0,0,0,8,2,4,19.1321129799 +93,,SUM,0,0,0,0,16,5,12,42.6212790012 +93,,,,,,,,,, +94,,,,,,,,,, +94,BOWL,SUM,0,0,0,0,8,1,4,12.220995903 +94,CUP,SUM,0,0,0,0,8,0,24,17.9365642071 +94,SPOON,SUM,0,0,0,0,8,0,0,16.4863669872 +94,,SUM,0,0,0,0,24,1,28,46.6439270973 +94,,,,,,,,,, +95,,,,,,,,,, +95,BOWL,SUM,1,0,1,0,2,33,200,0 +95,CUP,SUM,1,0,0,1,0,1,51,0 +95,SPOON,SUM,0,0,0,0,0,0,5,13.3435490131 +95,,SUM,2,0,1,1,2,34,256,13.3435490131 +95,,,,,,,,,, +96,,,,,,,,,, +96,BOWL,SUM,0,0,0,0,8,3,4,15.5968999863 +96,CUP,SUM,1,0,0,1,0,0,51,0 +96,SPOON,SUM,0,0,0,0,8,2,4,17.4821028709 +96,,SUM,1,0,0,1,16,5,59,33.0790028572 +96,,,,,,,,,, +97,,,,,,,,,, +97,BOWL,SUM,0,0,0,0,0,9,20,13.0357921124 +97,CUP,SUM,0,0,0,0,0,0,6,7.1944391727 +97,SPOON,SUM,0,0,0,0,0,1,0,11.7848310471 +97,,SUM,0,0,0,0,0,10,26,32.0150623322 +97,,,,,,,,,, +98,,,,,,,,,, +98,BOWL,SUM,0,0,0,0,0,4,16,11.0560541153 +98,CUP,SUM,0,0,0,0,8,1,14,14.4293959141 +98,SPOON,SUM,0,0,0,0,12,0,4,17.3383479118 +98,,SUM,0,0,0,0,20,5,34,42.8237979412 +98,,,,,,,,,, +99,,,,,,,,,, +99,BOWL,SUM,0,0,0,0,24,12,60,36.6914620399 +99,CUP,SUM,0,0,0,0,0,1,2,6.1274399757 +99,SPOON,SUM,0,0,0,0,0,1,0,11.5757060051 +99,,SUM,0,0,0,0,24,14,62,54.3946080208 +99,,,,,,,,,, +100,,,,,,,,,, +100,BOWL,SUM,0,0,0,0,0,1,22,12.0083909035 +100,CUP,SUM,0,0,0,0,0,0,23,14.5507588387 +100,SPOON,SUM,0,0,0,0,0,3,12,14.1430220604 +100,,SUM,0,0,0,0,0,4,57,40.7021718025 +100,,,,,,,,,, +101,,,,,,,,,, +101,BOWL,SUM,0,0,0,0,8,9,64,24.7273309231 +101,CUP,SUM,0,0,0,0,0,0,7,8.2402009964 +101,SPOON,SUM,0,0,0,0,0,1,12,14.5651919842 +101,,SUM,0,0,0,0,8,10,83,47.5327239037 +101,,,,,,,,,, +102,,,,,,,,,, +102,BOWL,SUM,0,0,0,0,0,2,16,11.9253380299 +102,CUP,SUM,0,0,0,0,8,2,10,13.8237080574 +102,SPOON,SUM,0,0,0,0,0,2,13,14.07980299 +102,,SUM,0,0,0,0,8,6,39,39.8288490772 +102,,,,,,,,,, +103,,,,,,,,,, +103,BOWL,SUM,0,0,0,0,8,0,8,14.3617329597 +103,CUP,SUM,0,0,0,0,0,0,6,6.8497700691 +103,SPOON,SUM,0,0,0,0,0,3,6,13.0906131268 +103,,SUM,0,0,0,0,8,3,20,34.3021161556 +103,,,,,,,,,, +104,,,,,,,,,, +104,BOWL,SUM,0,0,0,0,0,2,18,11.7847719193 +104,CUP,SUM,0,0,0,0,8,0,12,13.5458579063 +104,SPOON,SUM,0,0,0,0,8,0,7,18.5574350357 +104,,SUM,0,0,0,0,16,2,37,43.8880648613 +104,,,,,,,,,, +105,,,,,,,,,, +105,BOWL,SUM,0,0,0,0,0,0,4,8.9500148296 +105,CUP,SUM,0,0,0,0,0,0,14,9.5944209099 +105,SPOON,SUM,0,0,0,0,0,1,4,12.2550759315 +105,,SUM,0,0,0,0,0,1,22,30.7995116711 +105,,,,,,,,,, +106,,,,,,,,,, +106,BOWL,SUM,0,0,0,0,0,1,8,10.411711216 +106,CUP,SUM,1,0,0,1,0,2,51,0 +106,SPOON,SUM,0,0,0,0,0,0,3,13.0440971851 +106,,SUM,1,0,0,1,0,3,62,23.4558084011 +106,,,,,,,,,, +107,,,,,,,,,, +107,BOWL,SUM,0,0,0,0,0,1,0,8.0925650597 +107,CUP,SUM,0,0,0,0,16,1,9,18.0357670784 +107,SPOON,SUM,0,0,0,0,0,1,4,10.9184751511 +107,,SUM,0,0,0,0,16,3,13,37.0468072891 +107,,,,,,,,,, +108,,,,,,,,,, +108,BOWL,SUM,0,0,0,0,0,7,17,12.3746919632 +108,CUP,SUM,0,0,0,0,0,0,2,5.2872600555 +108,SPOON,SUM,0,0,0,0,16,1,2,23.4880230427 +108,,SUM,0,0,0,0,16,8,21,41.1499750614 +108,,,,,,,,,, +109,,,,,,,,,, +109,BOWL,SUM,0,0,0,0,16,6,0,20.8347079754 +109,CUP,SUM,0,0,0,0,12,0,20,19.8371601105 +109,SPOON,SUM,0,0,0,0,0,3,0,12.4667270184 +109,,SUM,0,0,0,0,28,9,20,53.1385951042 +109,,,,,,,,,, +110,,,,,,,,,, +110,BOWL,SUM,0,0,0,0,8,2,4,14.1782639027 +110,CUP,SUM,0,0,0,0,12,0,33,25.2274668217 +110,SPOON,SUM,0,0,0,0,0,2,4,14.3193778992 +110,,SUM,0,0,0,0,20,4,41,53.7251086235 +110,,,,,,,,,, +111,,,,,,,,,, +111,BOWL,SUM,0,0,0,0,0,0,12,11.3112809658 +111,CUP,SUM,0,0,0,0,0,1,23,13.6705889702 +111,SPOON,SUM,0,0,0,0,4,2,12,15.8655180931 +111,,SUM,0,0,0,0,4,3,47,40.8473880291 +111,,,,,,,,,, +112,,,,,,,,,, +112,BOWL,SUM,0,0,0,0,0,1,8,10.693434 +112,CUP,SUM,0,0,0,0,0,0,8,5.8392679691 +112,SPOON,SUM,0,0,0,0,8,0,4,16.6769771576 +112,,SUM,0,0,0,0,8,1,20,33.2096791267 +112,,,,,,,,,, +113,,,,,,,,,, +113,BOWL,SUM,0,0,0,0,0,0,4,9.2254889011 +113,CUP,SUM,0,0,0,0,0,0,2,6.421859026 +113,SPOON,SUM,0,0,0,0,0,0,3,12.5002179146 +113,,SUM,0,0,0,0,0,0,9,28.1475658417 +113,,,,,,,,,, +114,,,,,,,,,, +114,BOWL,SUM,0,0,0,0,0,3,5,10.2243359089 +114,CUP,SUM,0,0,0,0,0,0,24,13.9054808617 +114,SPOON,SUM,0,0,0,0,0,0,4,13.4303679466 +114,,SUM,0,0,0,0,0,3,33,37.5601847172 +114,,,,,,,,,, +115,,,,,,,,,, +115,BOWL,SUM,0,0,0,0,8,3,4,15.6738481522 +115,CUP,SUM,0,0,0,0,0,2,8,7.4693028927 +115,SPOON,SUM,0,0,0,0,0,4,10,14.2961120605 +115,,SUM,0,0,0,0,8,9,22,37.4392631054 +115,,,,,,,,,, +116,,,,,,,,,, +116,BOWL,SUM,0,0,0,0,8,1,0,12.5245850086 +116,CUP,SUM,0,0,0,0,0,0,2,6.3411231041 +116,SPOON,SUM,0,0,0,0,0,2,5,14.8331520557 +116,,SUM,0,0,0,0,8,3,7,33.6988601685 +116,,,,,,,,,, +117,,,,,,,,,, +117,BOWL,SUM,0,0,0,0,0,0,6,9.7563149929 +117,CUP,SUM,0,0,0,0,0,0,13,9.3697500229 +117,SPOON,SUM,0,0,0,0,12,1,8,19.0869660378 +117,,SUM,0,0,0,0,12,1,27,38.2130310535 +117,,,,,,,,,, +118,,,,,,,,,, +118,BOWL,SUM,0,0,0,0,8,2,0,13.8831861019 +118,CUP,SUM,0,0,0,0,0,1,58,29.1042790413 +118,SPOON,SUM,0,0,0,0,0,4,8,13.3753929138 +118,,SUM,0,0,0,0,8,7,66,56.362858057 +118,,,,,,,,,, +119,,,,,,,,,, +119,BOWL,SUM,0,0,0,0,8,0,8,14.5605208874 +119,CUP,SUM,0,0,0,0,0,0,56,27.8634700775 +119,SPOON,SUM,0,0,0,0,0,3,12,14.3195030689 +119,,SUM,0,0,0,0,8,3,76,56.7434940338 +119,,,,,,,,,, +120,,,,,,,,,, +120,BOWL,SUM,0,0,0,0,8,4,24,18.0126640797 +120,CUP,SUM,0,0,0,0,8,2,10,11.1947000027 +120,SPOON,SUM,0,0,0,0,0,3,8,14.6660399437 +120,,SUM,0,0,0,0,16,9,42,43.873404026 +120,,,,,,,,,, +121,,,,,,,,,, +121,BOWL,SUM,0,0,0,0,8,9,38,21.6842601299 +121,CUP,SUM,0,0,0,0,8,0,48,33.0541598797 +121,SPOON,SUM,0,0,0,0,0,1,1,12.4957809448 +121,,SUM,0,0,0,0,16,10,87,67.2342009544 +121,,,,,,,,,, +122,,,,,,,,,, +122,BOWL,SUM,0,0,0,0,0,1,0,7.9808371067 +122,CUP,SUM,0,0,0,0,0,7,12,10.9543647766 +122,SPOON,SUM,0,0,0,0,0,9,20,16.0787661076 +122,,SUM,0,0,0,0,0,17,32,35.0139679909 +122,,,,,,,,,, +123,,,,,,,,,, +123,BOWL,SUM,0,0,0,0,0,0,4,9.2796809673 +123,CUP,SUM,0,0,0,0,0,0,3,6.6788079739 +123,SPOON,SUM,0,0,0,0,0,0,0,11.9989769459 +123,,SUM,0,0,0,0,0,0,7,27.9574658871 +123,,,,,,,,,, +124,,,,,,,,,, +124,BOWL,SUM,0,0,0,0,0,1,3,9.0994338989 +124,CUP,SUM,0,0,0,0,0,2,13,8.0218889713 +124,SPOON,SUM,0,0,0,0,14,1,0,18.1245131493 +124,,SUM,0,0,0,0,14,4,16,35.2458360195 +124,,,,,,,,,, +125,,,,,,,,,, +125,BOWL,SUM,0,0,0,0,8,4,10,15.1260309219 +125,CUP,SUM,1,0,0,1,0,0,51,0 +125,SPOON,SUM,0,0,0,0,0,2,1,12.4692161083 +125,,SUM,1,0,0,1,8,6,62,27.5952470303 +125,,,,,,,,,, +126,,,,,,,,,, +126,BOWL,SUM,0,0,0,0,0,0,4,8.9022769928 +126,CUP,SUM,0,0,0,0,8,1,7,12.0384180546 +126,SPOON,SUM,0,0,0,0,0,1,17,15.4897298813 +126,,SUM,0,0,0,0,8,2,28,36.4304249287 +126,,,,,,,,,, +127,,,,,,,,,, +127,BOWL,SUM,0,0,0,0,16,5,25,25.5456049442 +127,CUP,SUM,0,0,0,0,0,0,2,6.3506169319 +127,SPOON,SUM,0,0,0,0,0,2,8,14.0825178623 +127,,SUM,0,0,0,0,16,7,35,45.9787397385 +127,,,,,,,,,, +128,,,,,,,,,, +128,BOWL,SUM,0,0,0,0,8,0,0,13.6055428982 +128,CUP,SUM,0,0,0,0,0,0,11,7.2218708992 +128,SPOON,SUM,0,0,0,0,12,2,13,21.9605169296 +128,,SUM,0,0,0,0,20,2,24,42.787930727 +128,,,,,,,,,, +129,,,,,,,,,, +129,BOWL,SUM,0,0,0,0,0,4,8,10.4597380161 +129,CUP,SUM,0,0,0,0,0,1,6,7.4040448666 +129,SPOON,SUM,0,0,0,0,0,0,4,12.7344679832 +129,,SUM,0,0,0,0,0,5,18,30.5982508659 +129,,,,,,,,,, +130,,,,,,,,,, +130,BOWL,SUM,0,0,0,0,8,39,28,25.3400630951 +130,CUP,SUM,0,0,0,0,0,1,25,11.8041489124 +130,SPOON,SUM,0,0,0,0,0,2,38,19.5672988892 +130,,SUM,0,0,0,0,8,42,91,56.7115108967 +130,,,,,,,,,, +131,,,,,,,,,, +131,BOWL,SUM,0,0,0,0,0,3,28,15.1785299778 +131,CUP,SUM,0,0,0,0,0,1,2,6.1923620701 +131,SPOON,SUM,0,0,0,0,12,1,16,20.9050199986 +131,,SUM,0,0,0,0,12,5,46,42.2759120464 +131,,,,,,,,,, +132,,,,,,,,,, +132,BOWL,SUM,0,0,0,0,16,9,84,35.9350368977 +132,CUP,SUM,0,0,0,0,0,0,2,6.9105029106 +132,SPOON,SUM,0,0,0,0,6,1,4,15.5001299381 +132,,SUM,0,0,0,0,22,10,90,58.3456697464 +132,,,,,,,,,, +133,,,,,,,,,, +133,BOWL,SUM,0,0,0,0,0,4,0,8.9088990688 +133,CUP,SUM,0,0,0,0,8,0,10,12.6752429008 +133,SPOON,SUM,0,0,0,0,0,1,4,14.2103469372 +133,,SUM,0,0,0,0,8,5,14,35.7944889069 +133,,,,,,,,,, +134,,,,,,,,,, +134,BOWL,SUM,0,0,0,0,0,0,4,8.4709811211 +134,CUP,SUM,0,0,0,0,8,0,7,11.6575818062 +134,SPOON,SUM,0,0,0,0,0,2,6,13.2543981075 +134,,SUM,0,0,0,0,8,2,17,33.3829610348 +134,,,,,,,,,, +135,,,,,,,,,, +135,BOWL,SUM,0,0,0,0,20,0,2,18.3413441181 +135,CUP,SUM,1,0,0,1,0,1,51,0 +135,SPOON,SUM,0,0,0,0,16,0,0,21.3253350258 +135,,SUM,1,0,0,1,36,1,53,39.6666791439 +135,,,,,,,,,, +136,,,,,,,,,, +136,BOWL,SUM,0,0,0,0,0,1,0,7.4753768444 +136,CUP,SUM,0,0,0,0,24,2,4,20.9931070805 +136,SPOON,SUM,0,0,0,0,8,6,2,21.8333170414 +136,,SUM,0,0,0,0,32,9,6,50.3018009663 +136,,,,,,,,,, +137,,,,,,,,,, +137,BOWL,SUM,0,0,0,0,0,0,0,7.3021202087 +137,CUP,SUM,0,0,0,0,0,2,34,20.8928618431 +137,SPOON,SUM,0,0,0,0,16,0,4,20.5497660637 +137,,SUM,0,0,0,0,16,2,38,48.7447481155 +137,,,,,,,,,, +138,,,,,,,,,, +138,BOWL,SUM,0,0,0,0,12,3,20,18.7516279221 +138,CUP,SUM,0,0,0,0,0,0,2,6.5947680473 +138,SPOON,SUM,0,0,0,0,0,0,0,12.3777370453 +138,,SUM,0,0,0,0,12,3,22,37.7241330147 +138,,,,,,,,,, +139,,,,,,,,,, +139,BOWL,SUM,0,0,0,0,6,0,1,11.0141379833 +139,CUP,SUM,0,0,0,0,0,0,8,7.5752339363 +139,SPOON,SUM,0,0,0,0,0,0,8,13.225288868 +139,,SUM,0,0,0,0,6,0,17,31.8146607876 +139,,,,,,,,,, +140,, +140,BOWL,SUM,0,0,0,0,0,1,18,13.254175901412964 +140,CUP,SUM,0,0,0,0,0,0,17,9.571273803710938 +140,SPOON,SUM,0,0,0,0,20,0,0,18.191028833389282 +140,,SUM,0,0,0,0,20,1,35,41.016478538513184 +140,, +141,, +141,BOWL,SUM,0,0,0,0,0,1,4,7.161181926727295 +141,CUP,SUM,0,0,0,0,20,2,6,12.787253856658936 +141,SPOON,SUM,0,0,0,0,12,8,27,19.700588941574097 +141,,SUM,0,0,0,0,32,11,37,39.64902472496033 +141,, +142,, +142,BOWL,SUM,0,0,0,0,0,1,16,9.4899001121521 +142,CUP,SUM,0,0,0,0,0,0,2,4.077615022659302 +142,SPOON,SUM,0,0,0,0,16,2,3,16.176270961761475 +142,,SUM,0,0,0,0,16,3,21,29.743786096572876 +142,, +143,, +143,BOWL,SUM,0,0,0,0,8,0,8,10.062410116195679 +143,CUP,SUM,0,0,0,0,0,3,18,6.179131031036377 +143,SPOON,SUM,0,0,0,0,0,0,4,9.82832407951355 +143,,SUM,0,0,0,0,8,3,30,26.069865226745605 +143,, +144,, +144,BOWL,SUM,0,0,0,0,8,2,32,14.71783185005188 +144,CUP,SUM,0,0,0,0,0,0,22,9.784318923950195 +144,SPOON,SUM,0,0,0,0,0,4,17,12.861054182052612 +144,,SUM,0,0,0,0,8,6,71,37.36320495605469 +144,, +145,, +145,BOWL,SUM,0,0,0,0,0,4,3,6.748347997665405 +145,CUP,SUM,0,0,0,0,8,1,10,9.300237894058228 +145,SPOON,SUM,0,0,0,0,32,2,28,28.285474061965942 +145,,SUM,0,0,0,0,40,7,41,44.334059953689575 +145,, +146,, +146,BOWL,SUM,0,0,0,0,0,1,8,7.715286016464233 +146,CUP,SUM,0,0,0,0,0,0,4,4.1249189376831055 +146,SPOON,SUM,0,0,0,0,16,0,0,15.206550121307373 +146,,SUM,0,0,0,0,16,1,12,27.046755075454712 +146,, +147,, +147,BOWL,SUM,0,0,0,0,0,1,1,6.765604019165039 +147,CUP,SUM,0,0,0,0,48,3,2,22.053157806396484 +147,SPOON,SUM,0,0,0,0,8,0,2,13.193656921386719 +147,,SUM,0,0,0,0,56,4,5,42.01241874694824 +147,, +148,, +148,BOWL,SUM,0,0,0,0,0,0,0,6.157914876937866 +148,CUP,SUM,0,0,0,0,8,0,41,24.0885488986969 +148,SPOON,SUM,0,0,0,0,0,2,16,12.415299892425537 +148,,SUM,0,0,0,0,8,2,57,42.6617636680603 +148,, +149,, +149,BOWL,SUM,0,0,0,0,0,2,2,6.2880730628967285 +149,CUP,SUM,0,0,0,0,0,3,44,22.827225923538208 +149,SPOON,SUM,0,0,0,0,0,0,5,10.388996124267578 +149,,SUM,0,0,0,0,0,5,51,39.504295110702515 +149,, +150,, +150,BOWL,SUM,0,0,0,0,0,0,0,6.215072154998779 +150,CUP,SUM,0,0,0,0,0,2,2,4.0801169872283936 +150,SPOON,SUM,0,0,0,0,0,0,6,10.893266916275024 +150,,SUM,0,0,0,0,0,2,8,21.188456058502197 +150,, +151,, +151,BOWL,SUM,0,0,0,0,0,2,13,8.835331916809082 +151,CUP,SUM,0,0,0,0,0,1,12,7.128451824188232 +151,SPOON,SUM,0,0,0,0,0,0,2,10.250869989395142 +151,,SUM,0,0,0,0,0,3,27,26.214653730392456 +151,, +152,, +152,BOWL,SUM,0,0,0,0,0,12,21,10.780499935150146 +152,CUP,SUM,1,0,0,1,24,1,67,0.0 +152,SPOON,SUM,0,0,0,0,0,2,4,10.329346895217896 +152,,SUM,1,0,0,1,24,15,92,21.109846830368042 +152,, +153,, +153,BOWL,SUM,0,0,0,0,0,0,4,6.767704963684082 +153,CUP,SUM,0,0,0,0,12,3,11,10.795370101928711 +153,SPOON,SUM,0,0,0,0,8,1,0,12.345530033111572 +153,,SUM,0,0,0,0,20,4,15,29.908605098724365 +153,, +154,, +154,BOWL,SUM,0,0,0,0,8,32,184,45.51298785209656 +154,CUP,SUM,0,0,0,0,0,1,7,4.8926310539245605 +154,SPOON,SUM,0,0,0,0,0,2,0,9.563616037368774 +154,,SUM,0,0,0,0,8,35,191,59.96923494338989 +154,, +155,, +155,BOWL,SUM,0,0,0,0,0,3,48,15.947817087173462 +155,CUP,SUM,0,0,0,0,0,0,2,4.223170042037964 +155,SPOON,SUM,0,0,0,0,0,0,0,9.873634099960327 +155,,SUM,0,0,0,0,0,3,50,30.044621229171753 +155,, +156,, +156,BOWL,SUM,0,0,0,0,0,2,11,8.886243104934692 +156,CUP,SUM,0,0,0,0,0,9,29,17.986714124679565 +156,SPOON,SUM,0,0,0,0,0,6,32,16.05168104171753 +156,,SUM,0,0,0,0,0,17,72,42.92463827133179 +156,, +157,, +157,BOWL,SUM,0,0,0,0,0,1,22,10.633052110671997 +157,CUP,SUM,0,0,0,0,12,2,24,18.14969515800476 +157,SPOON,SUM,0,0,0,0,8,0,5,14.100103855133057 +157,,SUM,0,0,0,0,20,3,51,42.882851123809814 +157,, +158,, +158,BOWL,SUM,0,0,0,0,0,1,5,7.6548779010772705 +158,CUP,SUM,0,0,0,0,0,0,18,8.47749400138855 +158,SPOON,SUM,0,0,0,0,0,0,9,11.35426378250122 +158,,SUM,0,0,0,0,0,1,32,27.48663568496704 +158,, +159,, +159,BOWL,SUM,0,0,0,0,0,17,60,18.388856887817383 +159,CUP,SUM,1,0,0,1,0,0,51,0.0 +159,SPOON,SUM,0,0,0,0,10,4,16,17.673365831375122 +159,,SUM,1,0,0,1,10,21,127,36.062222719192505 +159,, +160,, +160,BOWL,SUM,0,0,0,0,0,0,4,7.114962816238403 +160,CUP,SUM,0,0,0,0,16,2,7,14.026718854904175 +160,SPOON,SUM,0,0,0,0,0,2,18,13.236496925354004 +160,,SUM,0,0,0,0,16,4,29,34.37817859649658 +160,, +161,, +161,BOWL,SUM,0,0,0,0,0,0,0,6.460599899291992 +161,CUP,SUM,0,0,0,0,0,0,15,9.470106840133667 +161,SPOON,SUM,0,0,0,0,0,1,4,11.27053713798523 +161,,SUM,0,0,0,0,0,1,19,27.20124387741089 +161,, +162,, +162,BOWL,SUM,0,0,0,0,8,9,28,15.769519090652466 +162,CUP,SUM,1,0,0,1,0,2,59,0.0 +162,SPOON,SUM,0,0,0,0,24,15,33,26.915421962738037 +162,,SUM,1,0,0,1,32,26,120,42.6849410533905 +162,, +163,, +163,BOWL,SUM,0,0,0,0,0,3,36,13.530049800872803 +163,CUP,SUM,0,0,0,0,8,1,11,9.812688112258911 +163,SPOON,SUM,0,0,0,0,0,2,9,12.086623907089233 +163,,SUM,0,0,0,0,8,6,56,35.42936182022095 +163,, +164,, +164,BOWL,SUM,0,0,0,0,0,6,8,8.719542980194092 +164,CUP,SUM,0,0,0,0,0,1,2,5.003866910934448 +164,SPOON,SUM,0,0,0,0,2,2,4,12.01035189628601 +164,,SUM,0,0,0,0,2,9,14,25.73376178741455 +164,, +165,, +165,BOWL,SUM,0,0,0,0,0,0,1,7.27709698677063 +165,CUP,SUM,0,0,0,0,16,0,13,16.034082889556885 +165,SPOON,SUM,0,0,0,0,8,0,13,17.058897018432617 +165,,SUM,0,0,0,0,24,0,27,40.37007689476013 +165,, +166,, +166,BOWL,SUM,0,0,0,0,0,1,0,7.129940032958984 +166,CUP,SUM,1,0,0,1,0,0,66,0.0 +166,SPOON,SUM,0,0,0,0,0,0,5,12.420130968093872 +166,,SUM,1,0,0,1,0,1,71,19.550071001052856 +166,, +167,, +167,BOWL,SUM,0,0,0,0,8,2,10,14.8211510181427 +167,CUP,SUM,0,0,0,0,6,0,5,7.1777119636535645 +167,SPOON,SUM,0,0,0,0,8,0,0,15.208556890487671 +167,,SUM,0,0,0,0,22,2,15,37.207419872283936 +167,, +168,, +168,BOWL,SUM,0,0,0,0,0,1,20,11.378844022750854 +168,CUP,SUM,0,0,0,0,0,2,18,10.42188286781311 +168,SPOON,SUM,0,0,0,0,0,2,0,12.403717994689941 +168,,SUM,0,0,0,0,0,5,38,34.204444885253906 +168,, +169,, +169,BOWL,SUM,0,0,0,0,0,0,0,6.724272966384888 +169,CUP,SUM,0,0,0,0,8,0,42,27.550779819488525 +169,SPOON,SUM,0,0,0,0,0,2,4,12.48380184173584 +169,,SUM,0,0,0,0,8,2,46,46.75885462760925 +169,, +170,, +170,BOWL,SUM,0,0,0,0,0,18,176,43.08479404449463 +170,CUP,SUM,0,0,0,0,12,1,6,11.928001165390015 +170,SPOON,SUM,0,0,0,0,0,4,8,14.04230523109436 +170,,SUM,0,0,0,0,12,23,190,69.055100440979 +170,, +171,, +171,BOWL,SUM,0,0,0,0,0,0,0,7.103800058364868 +171,CUP,SUM,0,0,0,0,0,0,43,24.20199489593506 +171,SPOON,SUM,0,0,0,0,0,0,0,11.257971048355103 +171,,SUM,0,0,0,0,0,0,43,42.56376600265503 +171,, +172,, +172,BOWL,SUM,0,0,0,0,0,1,0,8.247311115264893 +172,CUP,SUM,0,0,0,0,0,0,7,6.958992004394531 +172,SPOON,SUM,0,0,0,0,0,12,47,22.10333514213562 +172,,SUM,0,0,0,0,0,13,54,37.309638261795044 +172,, +173,, +173,BOWL,SUM,0,0,0,0,0,0,3,8.831927061080933 +173,CUP,SUM,0,0,0,0,14,1,6,13.002228021621704 +173,SPOON,SUM,0,0,0,0,0,0,5,13.53925609588623 +173,,SUM,0,0,0,0,14,1,14,35.37341117858887 +173,, +174,, +174,BOWL,SUM,0,0,0,0,0,0,4,7.7121570110321045 +174,CUP,SUM,0,0,0,0,16,0,15,17.86798095703125 +174,SPOON,SUM,0,0,0,0,0,4,11,13.699587106704712 +174,,SUM,0,0,0,0,16,4,30,39.279725074768066 +174,, +175,, +175,BOWL,SUM,0,0,0,0,12,0,0,13.171783924102783 +175,CUP,SUM,0,0,0,0,8,2,21,15.858865022659302 +175,SPOON,SUM,0,0,0,0,0,0,0,11.365931034088135 +175,,SUM,0,0,0,0,20,2,21,40.39657998085022 +175,, +176,, +176,BOWL,SUM,0,0,0,0,0,6,84,25.74063801765442 +176,CUP,SUM,0,0,0,0,0,2,17,12.168338060379028 +176,SPOON,SUM,0,0,0,0,0,1,4,12.808663129806519 +176,,SUM,0,0,0,0,0,9,105,50.717639207839966 +176,, +177,, +177,BOWL,SUM,0,0,0,0,0,5,30,15.066643953323364 +177,CUP,SUM,0,0,0,0,8,3,33,21.876862049102783 +177,SPOON,SUM,0,0,0,0,8,5,4,17.279477834701538 +177,,SUM,0,0,0,0,16,13,67,54.222983837127686 +177,, +178,, +178,BOWL,SUM,0,0,0,0,0,0,1,8.524921894073486 +178,CUP,SUM,0,0,0,0,0,0,7,7.47367000579834 +178,SPOON,SUM,0,0,0,0,0,1,13,14.935644149780273 +178,,SUM,0,0,0,0,0,1,21,30.9342360496521 +178,, +179,, +179,BOWL,SUM,0,0,0,0,12,0,5,15.010004043579102 +179,CUP,SUM,1,0,0,1,8,0,51,0.0 +179,SPOON,SUM,0,0,0,0,16,3,4,21.171390056610107 +179,,SUM,1,0,0,1,36,3,60,36.18139410018921 +179,, +180,, +180,BOWL,SUM,0,0,0,0,0,6,41,15.293370008468628 +180,CUP,SUM,0,0,0,0,0,0,6,5.187832832336426 +180,SPOON,SUM,0,0,0,0,0,2,0,12.558840990066528 +180,,SUM,0,0,0,0,0,8,47,33.04004383087158 +180,, +181,, +181,BOWL,SUM,0,0,0,0,0,4,18,10.43586277961731 +181,CUP,SUM,0,0,0,0,8,5,54,37.44101595878601 +181,SPOON,SUM,0,0,0,0,28,4,0,28.4790620803833 +181,,SUM,0,0,0,0,36,13,72,76.35594081878662 +181,, +182,, +182,BOWL,SUM,1,0,1,0,4,22,196,0.0 +182,CUP,SUM,1,0,0,1,24,2,51,0.0 +182,SPOON,SUM,0,0,0,0,24,7,1,28.580919981002808 +182,,SUM,2,0,1,1,52,31,248,28.580919981002808 +182,, +183,, +183,BOWL,SUM,0,0,0,0,0,0,0,8.964266061782837 +183,CUP,SUM,0,0,0,0,0,0,2,4.822875022888184 +183,SPOON,SUM,0,0,0,0,0,0,2,12.995568990707397 +183,,SUM,0,0,0,0,0,0,4,26.782710075378418 +183,, +184,, +184,BOWL,SUM,0,0,0,0,16,0,0,15.91485595703125 +184,CUP,SUM,0,0,0,0,12,0,2,12.426185131072998 +184,SPOON,SUM,0,0,0,0,0,1,0,11.551842212677002 +184,,SUM,0,0,0,0,28,1,2,39.89288330078125 +184,, +185,, +185,BOWL,SUM,0,0,0,0,8,3,21,18.634868144989014 +185,CUP,SUM,0,0,0,0,0,3,21,11.912768125534058 +185,SPOON,SUM,0,0,0,0,0,2,13,15.096560001373291 +185,,SUM,0,0,0,0,8,8,55,45.64419627189636 +185,, +186,, +186,BOWL,SUM,0,0,0,0,0,0,8,9.63208293914795 +186,CUP,SUM,0,0,0,0,0,2,23,14.247983932495117 +186,SPOON,SUM,0,0,0,0,0,1,0,11.220720052719116 +186,,SUM,0,0,0,0,0,3,31,35.10078692436218 +186,, +187,, +187,BOWL,SUM,0,0,0,0,0,4,10,10.845638990402222 +187,CUP,SUM,0,0,0,0,0,2,7,7.414214134216309 +187,SPOON,SUM,0,0,0,0,0,1,10,13.811771154403687 +187,,SUM,0,0,0,0,0,7,27,32.07162427902222 +187,, +188,, +188,BOWL,SUM,0,0,0,0,0,2,5,10.074436902999878 +188,CUP,SUM,0,0,0,0,0,1,2,5.182523012161255 +188,SPOON,SUM,0,0,0,0,0,1,4,10.69654393196106 +188,,SUM,0,0,0,0,0,4,11,25.953503847122192 +188,, +189,, +189,BOWL,SUM,0,0,0,0,0,3,8,9.701226949691772 +189,CUP,SUM,0,0,0,0,0,1,3,5.82650089263916 +189,SPOON,SUM,0,0,0,0,0,10,36,19.431666135787964 +189,,SUM,0,0,0,0,0,14,47,34.9593939781189 +189,, +190,, +190,BOWL,SUM,0,0,0,0,0,2,16,11.778557062149048 +190,CUP,SUM,0,0,0,0,0,2,6,6.005945920944214 +190,SPOON,SUM,0,0,0,0,0,1,16,14.504930019378662 +190,,SUM,0,0,0,0,0,5,38,32.289433002471924 +190,, +191,, +191,BOWL,SUM,0,0,0,0,0,11,60,20.568645000457764 +191,CUP,SUM,0,0,0,0,16,1,33,28.54251194000244 +191,SPOON,SUM,0,0,0,0,0,1,0,10.579431056976318 +191,,SUM,0,0,0,0,16,13,93,59.69058799743652 +191,, +192,, +192,BOWL,SUM,0,0,0,0,8,2,5,13.32099199295044 +192,CUP,SUM,0,0,0,0,0,1,8,5.457234859466553 +192,SPOON,SUM,0,0,0,0,0,0,3,12.46645212173462 +192,,SUM,0,0,0,0,8,3,16,31.24467897415161 +192,, +193,, +193,BOWL,SUM,0,0,0,0,0,0,5,9.680346012115479 +193,CUP,SUM,0,0,0,0,8,10,65,43.389946937561035 +193,SPOON,SUM,0,0,0,0,0,2,33,18.018511056900024 +193,,SUM,0,0,0,0,8,12,103,71.08880400657654 +193,, +194,, +194,BOWL,SUM,0,0,0,0,0,0,0,8.606698036193848 +194,CUP,SUM,0,0,0,0,0,1,18,11.422364950180054 +194,SPOON,SUM,0,0,0,0,0,2,5,13.22788119316101 +194,,SUM,0,0,0,0,0,3,23,33.25694417953491 +194,, +195,, +195,BOWL,SUM,0,0,0,0,0,0,12,10.619855880737305 +195,CUP,SUM,0,0,0,0,0,0,26,16.53536105155945 +195,SPOON,SUM,0,0,0,0,0,0,2,13.03675389289856 +195,,SUM,0,0,0,0,0,0,40,40.19197082519531 +195,, +196,, +196,BOWL,SUM,0,0,0,0,8,0,0,12.839002847671509 +196,CUP,SUM,0,0,0,0,0,4,8,8.348278045654297 +196,SPOON,SUM,0,0,0,0,0,0,0,12.004043817520142 +196,,SUM,0,0,0,0,8,4,8,33.19132471084595 +196,, +197,, +197,BOWL,SUM,0,0,0,0,32,1,0,29.206094980239868 +197,CUP,SUM,0,0,0,0,16,0,2,16.527390956878662 +197,SPOON,SUM,0,0,0,0,0,0,1,12.641416072845459 +197,,SUM,0,0,0,0,48,1,3,58.37490200996399 +197,, +198,, +198,BOWL,SUM,0,0,0,0,0,1,24,12.990669965744019 +198,CUP,SUM,0,0,0,0,0,2,47,27.09940791130066 +198,SPOON,SUM,0,0,0,0,0,4,10,15.077844858169556 +198,,SUM,0,0,0,0,0,7,81,55.16792273521423 +198,, +199,, +199,BOWL,SUM,0,0,0,0,8,0,8,14.773518085479736 +199,CUP,SUM,1,0,0,1,8,0,57,0.0 +199,SPOON,SUM,0,0,0,0,0,0,9,14.410346031188965 +199,,SUM,1,0,0,1,16,0,74,29.1838641166687 +199,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/Pr2VrSimLikeReal.csv b/cram_knowrob/cram_knowrob_vr/experiments/Pr2VrSimLikeReal.csv new file mode 100644 index 0000000000..26fd0fd211 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/Pr2VrSimLikeReal.csv @@ -0,0 +1,1203 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,6,270,23,39.7187120914 +0,CUP,SUM,0,0,0,0,0,44,18,25.3507940769 +0,SPOON,SUM,0,0,0,0,0,87,0,17.0062270164 +0,,SUM,0,0,0,0,6,401,41,82.0757331848 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,0,25,3,11.8642001152 +1,CUP,SUM,0,0,0,0,0,19,0,8.7102711201 +1,SPOON,SUM,0,0,0,0,0,0,4,15.6640019417 +1,,SUM,0,0,0,0,0,44,7,36.238473177 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,0,6,0,10.1101679802 +2,CUP,SUM,0,0,0,0,0,9,8,8.8709850311 +2,SPOON,SUM,0,0,0,0,0,12,0,13.1580340862 +2,,SUM,0,0,0,0,0,27,8,32.1391870975 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,0,9,2,10.0962979794 +3,CUP,SUM,0,0,0,0,0,14,5,9.8040990829 +3,SPOON,SUM,0,0,0,0,42,2,0,30.3018069267 +3,,SUM,0,0,0,0,42,25,7,50.202203989 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,21,8,14.2675487995 +4,CUP,SUM,0,0,0,0,6,90,28,41.0848448277 +4,SPOON,SUM,0,0,0,0,0,42,0,14.1250760555 +4,,SUM,0,0,0,0,6,153,36,69.4774696827 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,0,11,4,11.5904409885 +5,CUP,SUM,1,0,0,1,0,146,53,0 +5,SPOON,SUM,0,0,0,0,0,1,0,12.9767570496 +5,,SUM,1,0,0,1,0,158,57,24.5671980381 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,0,150,0,17.2870790958 +6,CUP,SUM,0,0,0,0,0,34,7,15.3222391605 +6,SPOON,SUM,1,0,1,0,0,1456,20,0 +6,,SUM,1,0,1,0,0,1640,27,32.6093182564 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,0,21,2,10.6668150425 +7,CUP,SUM,0,0,0,0,8,24,6,12.4839279652 +7,SPOON,SUM,0,0,0,0,0,4,3,14.5292541981 +7,,SUM,0,0,0,0,8,49,11,37.6799972057 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,114,49,2,58.3046619892 +8,CUP,SUM,1,0,0,1,0,161,56,0 +8,SPOON,SUM,0,0,0,0,2,10,0,13.6633889675 +8,,SUM,1,0,0,1,116,220,58,71.9680509567 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,41,6,13.783523798 +9,CUP,SUM,1,0,0,1,0,173,53,0 +9,SPOON,SUM,0,0,0,0,0,111,0,18.677200079 +9,,SUM,1,0,0,1,0,325,59,32.460723877 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,9,4,11.599613905 +10,CUP,SUM,0,0,0,0,0,62,13,24.1038591862 +10,SPOON,SUM,0,0,0,0,0,38,3,18.9507040977 +10,,SUM,0,0,0,0,0,109,20,54.6541771889 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,0,221,56,53.4270758629 +11,CUP,SUM,0,0,0,0,0,6,2,8.7267329693 +11,SPOON,SUM,0,0,0,0,0,91,3,18.9055891037 +11,,SUM,0,0,0,0,0,318,61,81.0593979359 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,0,8,0,10.1702849865 +12,CUP,SUM,0,0,0,0,0,28,8,9.1087629795 +12,SPOON,SUM,1,0,1,0,6,1721,0,0 +12,,SUM,1,0,1,0,6,1757,8,19.279047966 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,0,32,6,13.8396570683 +13,CUP,SUM,1,0,0,1,0,229,61,0 +13,SPOON,SUM,0,0,0,0,2,36,2,14.7184569836 +13,,SUM,1,0,0,1,2,297,69,28.5581140518 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,0,8,2,9.8854520321 +14,CUP,SUM,0,0,0,0,0,23,3,9.1376729012 +14,SPOON,SUM,0,0,0,0,0,58,0,15.8269422054 +14,,SUM,0,0,0,0,0,89,5,34.8500671387 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,2,7,0,11.1343529224 +15,CUP,SUM,0,0,0,0,16,16,6,17.4016039371 +15,SPOON,SUM,0,0,0,0,0,25,0,14.2622029781 +15,,SUM,0,0,0,0,18,48,6,42.7981598377 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,2,11,0,11.3111450672 +16,CUP,SUM,0,0,0,0,0,18,7,9.9933331013 +16,SPOON,SUM,0,0,0,0,2,96,3,21.5043718815 +16,,SUM,0,0,0,0,4,125,10,42.80885005 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,26,28,3,27.3157188892 +17,CUP,SUM,0,0,0,0,4,19,10,11.1238210201 +17,SPOON,SUM,0,0,0,0,0,14,0,14.0387690067 +17,,SUM,0,0,0,0,30,61,13,52.4783089161 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,0,28,0,11.2212970257 +18,CUP,SUM,0,0,0,0,0,6,4,8.9980978966 +18,SPOON,SUM,0,0,0,0,0,1,3,15.1006278992 +18,,SUM,0,0,0,0,0,35,7,35.3200228214 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,6,2,10.3720090389 +19,CUP,SUM,0,0,0,0,0,19,0,8.718059063 +19,SPOON,SUM,0,0,0,0,0,72,2,19.4057948589 +19,,SUM,0,0,0,0,0,97,4,38.4958629608 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,8,48,0,15.4422450066 +20,CUP,SUM,1,0,0,1,0,147,55,0 +20,SPOON,SUM,0,0,0,0,0,74,2,17.3854460716 +20,,SUM,1,0,0,1,8,269,57,32.8276910782 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,1,0,1,0,8,993,72,0 +21,CUP,SUM,0,0,0,0,0,221,52,78.6192920208 +21,SPOON,SUM,0,0,0,0,0,39,10,20.9298989773 +21,,SUM,1,0,1,0,8,1253,134,99.5491909981 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,0,142,6,19.2882018089 +22,CUP,SUM,1,0,1,0,14,424,91,0 +22,SPOON,SUM,0,0,0,0,0,12,2,13.5504579544 +22,,SUM,1,0,1,0,14,578,99,32.8386597633 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,91,12,21.6206328869 +23,CUP,SUM,1,0,0,1,0,199,55,0 +23,SPOON,SUM,0,0,0,0,0,16,1,14.7639648914 +23,,SUM,1,0,0,1,0,306,68,36.3845977783 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,4,36,1,14.6743810177 +24,CUP,SUM,0,0,0,0,0,61,19,29.8849070072 +24,SPOON,SUM,0,0,0,0,0,19,6,16.65710783 +24,,SUM,0,0,0,0,4,116,26,61.216395855 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,0,12,0,10.4177410603 +25,CUP,SUM,0,0,0,0,0,17,18,17.7146401405 +25,SPOON,SUM,1,0,1,0,0,1298,34,0 +25,,SUM,1,0,1,0,0,1327,52,28.1323812008 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,2,13,2,11.5581049919 +26,CUP,SUM,0,0,0,0,0,3,0,8.4301071167 +26,SPOON,SUM,0,0,0,0,0,3,0,13.1747920513 +26,,SUM,0,0,0,0,2,19,2,33.1630041599 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,0,67,4,14.7131090164 +27,CUP,SUM,0,0,0,0,0,27,9,13.18709898 +27,SPOON,SUM,0,0,0,0,0,0,1,14.3193840981 +27,,SUM,0,0,0,0,0,94,14,42.2195920944 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,0,0,0,9.9893951416 +28,CUP,SUM,0,0,0,0,2,44,16,16.0330960751 +28,SPOON,SUM,0,0,0,0,0,16,1,14.8567039967 +28,,SUM,0,0,0,0,2,60,17,40.8791952133 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,2,85,0,14.5591828823 +29,CUP,SUM,0,0,0,0,0,13,4,8.5089969635 +29,SPOON,SUM,0,0,0,0,0,6,6,18.4244110584 +29,,SUM,0,0,0,0,2,104,10,41.4925909042 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,0,43,0,12.6349978447 +30,CUP,SUM,0,0,0,0,14,25,12,16.6415250301 +30,SPOON,SUM,0,0,0,0,0,220,1,25.964482069 +30,,SUM,0,0,0,0,14,288,13,55.2410049438 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,56,72,1,36.929131031 +31,CUP,SUM,0,0,0,0,0,8,0,8.3995471001 +31,SPOON,SUM,0,0,0,0,0,49,2,15.8507888317 +31,,SUM,0,0,0,0,56,129,3,61.1794669628 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,0,220,24,32.9066829681 +32,CUP,SUM,1,0,0,1,0,194,59,0 +32,SPOON,SUM,0,0,0,0,0,77,2,17.3954820633 +32,,SUM,1,0,0,1,0,491,85,50.3021650314 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,12,0,10.2308030128 +33,CUP,SUM,0,0,0,0,0,18,2,8.9499261379 +33,SPOON,SUM,0,0,0,0,0,458,2,37.0567858219 +33,,SUM,0,0,0,0,0,488,4,56.2375149727 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,6,173,16,28.0616660118 +34,CUP,SUM,1,0,0,1,0,172,58,0 +34,SPOON,SUM,0,0,0,0,0,174,8,26.3589930534 +34,,SUM,1,0,0,1,6,519,82,54.4206590652 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,1,0,1,0,0,1229,49,0 +35,CUP,SUM,1,0,0,1,0,161,53,0 +35,SPOON,SUM,0,0,0,0,0,1,6,16.7337830067 +35,,SUM,2,0,1,1,0,1391,108,16.7337830067 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,2,180,4,21.4738481045 +36,CUP,SUM,0,0,0,0,0,26,4,9.4826960564 +36,SPOON,SUM,0,0,0,0,0,26,0,14.147605896 +36,,SUM,0,0,0,0,2,232,8,45.1041500568 +36,,,,,,,,,, +37,,,,,,,,,, +37,BOWL,SUM,0,0,0,0,6,34,2,14.0982410908 +37,CUP,SUM,0,0,0,0,4,13,10,12.7680740356 +37,SPOON,SUM,0,0,0,0,0,23,0,13.8755960464 +37,,SUM,0,0,0,0,10,70,12,40.7419111729 +37,,,,,,,,,, +38,,,,,,,,,, +38,BOWL,SUM,0,0,0,0,6,46,0,13.851238966 +38,CUP,SUM,0,0,0,0,0,15,2,8.4777991772 +38,SPOON,SUM,0,0,0,0,0,26,4,15.3136661053 +38,,SUM,0,0,0,0,6,87,6,37.6427042484 +38,,,,,,,,,, +39,,,,,,,,,, +39,BOWL,SUM,0,0,0,0,0,10,0,10.3229420185 +39,CUP,SUM,0,0,0,0,2,58,24,32.3285260201 +39,SPOON,SUM,0,0,0,0,2,30,2,14.7942531109 +39,,SUM,0,0,0,0,4,98,26,57.4457211494 +39,,,,,,,,,, +40,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,0,20,0,10.363353014 +40,CUP,SUM,0,0,0,0,2,8,1,10.5322568417 +40,SPOON,SUM,1,0,1,0,0,1074,60,0 +40,,SUM,1,0,1,0,2,1102,61,20.8956098557 +40,,,,,,,,,, +41,,,,,,,,,, +41,BOWL,SUM,1,0,1,0,0,976,72,0 +41,CUP,SUM,0,0,0,0,10,21,4,15.8176009655 +41,SPOON,SUM,0,0,0,0,2,157,11,26.9232559204 +41,,SUM,1,0,1,0,12,1154,87,42.7408568859 +41,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,0,10,0,10.3365678787 +42,CUP,SUM,0,0,0,0,0,9,4,8.7146501541 +42,SPOON,SUM,0,0,0,0,2,138,3,25.219990015 +42,,SUM,0,0,0,0,2,157,7,44.2712080479 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,0,13,0,10.292350769 +43,CUP,SUM,1,0,0,1,0,211,59,0 +43,SPOON,SUM,0,0,0,0,8,205,12,31.5711269379 +43,,SUM,1,0,0,1,8,429,71,41.8634777069 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,0,48,1,12.2994508743 +44,CUP,SUM,1,0,0,1,0,202,51,0 +44,SPOON,SUM,0,0,0,0,0,5,2,13.3526959419 +44,,SUM,1,0,0,1,0,255,54,25.6521468163 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,4,42,4,13.8747580051 +45,CUP,SUM,0,0,0,0,6,67,25,39.9600160122 +45,SPOON,SUM,0,0,0,0,0,178,0,23.1258919239 +45,,SUM,0,0,0,0,10,287,29,76.9606659412 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,56,26,0,34.3496901989 +46,CUP,SUM,0,0,0,0,2,8,8,9.4621729851 +46,SPOON,SUM,0,0,0,0,0,21,0,14.0868759155 +46,,SUM,0,0,0,0,58,55,8,57.8987390995 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,0,0,0,0,0,6,0,10.0863070488 +47,CUP,SUM,0,0,0,0,0,34,2,10.3195421696 +47,SPOON,SUM,0,0,0,0,0,40,0,15.6515388489 +47,,SUM,0,0,0,0,0,80,2,36.0573880672 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,0,15,0,10.4465889931 +48,CUP,SUM,0,0,0,0,0,10,0,8.3492040634 +48,SPOON,SUM,0,0,0,0,0,71,2,17.4699831009 +48,,SUM,0,0,0,0,0,96,2,36.2657761574 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,0,25,4,12.6468629837 +49,CUP,SUM,0,0,0,0,0,39,22,29.8515431881 +49,SPOON,SUM,0,0,0,0,0,66,1,15.7145271301 +49,,SUM,0,0,0,0,0,130,27,58.2129333019 +49,,,,,,,,,, +50,,,,,,,,,, +50,BOWL,SUM,0,0,0,0,2,12,4,13.9909319878 +50,CUP,SUM,1,0,0,1,0,196,66,0 +50,SPOON,SUM,0,0,0,0,0,46,3,16.597536087 +50,,SUM,1,0,0,1,2,254,73,30.5884680748 +50,,,,,,,,,, +51,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,2,22,0,11.3410999775 +51,CUP,SUM,0,0,0,0,0,81,37,50.3340320587 +51,SPOON,SUM,0,0,0,0,0,55,2,15.8011720181 +51,,SUM,0,0,0,0,2,158,39,77.4763040543 +51,,,,,,,,,, +52,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,0,9,2,13.0938301086 +52,CUP,SUM,1,0,0,1,0,197,57,0 +52,SPOON,SUM,1,0,1,0,0,1342,24,0 +52,,SUM,2,0,1,1,0,1548,83,13.0938301086 +52,,,,,,,,,, +53,,,,,,,,,, +53,BOWL,SUM,0,0,0,0,12,27,0,15.6246109009 +53,CUP,SUM,0,0,0,0,0,96,21,31.4201889038 +53,SPOON,SUM,0,0,0,0,2,83,2,20.5903668404 +53,,SUM,0,0,0,0,14,206,23,67.6351666451 +53,,,,,,,,,, +54,,,,,,,,,, +54,BOWL,SUM,0,0,0,0,0,8,0,10.5689430237 +54,CUP,SUM,0,0,0,0,0,12,1,10.1662979126 +54,SPOON,SUM,0,0,0,0,2,581,10,51.8434329033 +54,,SUM,0,0,0,0,2,601,11,72.5786738396 +54,,,,,,,,,, +55,,,,,,,,,, +55,BOWL,SUM,0,0,0,0,0,2,0,10.820032835 +55,CUP,SUM,0,0,0,0,0,13,5,10.5700120926 +55,SPOON,SUM,0,0,0,0,6,32,3,18.2946770191 +55,,SUM,0,0,0,0,6,47,8,39.6847219467 +55,,,,,,,,,, +56,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,10,65,4,19.6321089268 +56,CUP,SUM,0,0,0,0,0,52,16,29.6743969917 +56,SPOON,SUM,0,0,0,0,0,267,3,30.5450880527 +56,,SUM,0,0,0,0,10,384,23,79.8515939713 +56,,,,,,,,,, +57,,,,,,,,,, +57,BOWL,SUM,0,0,0,0,0,15,2,11.1037068367 +57,CUP,SUM,0,0,0,0,6,39,9,14.8277988434 +57,SPOON,SUM,0,0,0,0,0,56,0,16.633710146 +57,,SUM,0,0,0,0,6,110,11,42.565215826 +57,,,,,,,,,, +58,,,,,,,,,, +58,BOWL,SUM,0,0,0,0,14,3,0,16.5765419006 +58,CUP,SUM,0,0,0,0,0,54,14,18.8705611229 +58,SPOON,SUM,0,0,0,0,0,74,1,19.2443552017 +58,,SUM,0,0,0,0,14,131,15,54.6914582253 +58,,,,,,,,,, +59,,,,,,,,,, +59,BOWL,SUM,0,0,0,0,0,16,2,11.2475659847 +59,CUP,SUM,0,0,0,0,0,12,2,8.7903621197 +59,SPOON,SUM,0,0,0,0,0,62,8,19.7346060276 +59,,SUM,0,0,0,0,0,90,12,39.772534132 +59,,,,,,,,,, +60,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,0,260,32,44.2547709942 +60,CUP,SUM,1,0,0,1,0,174,59,0 +60,SPOON,SUM,0,0,0,0,0,22,4,17.351703167 +60,,SUM,1,0,0,1,0,456,95,61.6064741611 +60,,,,,,,,,, +61,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,0,9,0,10.7656891346 +61,CUP,SUM,0,0,0,0,2,70,18,32.990388155 +61,SPOON,SUM,0,0,0,0,0,64,1,18.9996800423 +61,,SUM,0,0,0,0,2,143,19,62.7557573318 +61,,,,,,,,,, +62,,,,,,,,,, +62,BOWL,SUM,0,0,0,0,0,13,2,11.0214238167 +62,CUP,SUM,1,0,1,0,0,263,111,0 +62,SPOON,SUM,0,0,0,0,0,63,4,22.3950200081 +62,,SUM,1,0,1,0,0,339,117,33.4164438248 +62,,,,,,,,,, +63,,,,,,,,,, +63,BOWL,SUM,0,0,0,0,2,62,11,20.5848851204 +63,CUP,SUM,0,0,0,0,0,13,7,13.5907969475 +63,SPOON,SUM,0,0,0,0,6,376,1,37.9228219986 +63,,SUM,0,0,0,0,8,451,19,72.0985040665 +63,,,,,,,,,, +64,,,,,,,,,, +64,BOWL,SUM,0,0,0,0,0,33,0,11.8647480011 +64,CUP,SUM,0,0,0,0,0,25,2,9.5135009289 +64,SPOON,SUM,0,0,0,0,0,79,3,19.5717380047 +64,,SUM,0,0,0,0,0,137,5,40.9499869347 +64,,,,,,,,,, +65,,,,,,,,,, +65,BOWL,SUM,0,0,0,0,0,6,6,14.1577968597 +65,CUP,SUM,0,0,0,0,0,36,18,20.8720901012 +65,SPOON,SUM,0,0,0,0,2,89,2,21.8143758774 +65,,SUM,0,0,0,0,2,131,26,56.8442628384 +65,,,,,,,,,, +66,,,,,,,,,, +66,BOWL,SUM,0,0,0,0,38,324,39,70.0933699608 +66,CUP,SUM,0,0,0,0,0,3,9,9.4921870232 +66,SPOON,SUM,0,0,0,0,0,1146,22,94.3172681332 +66,,SUM,0,0,0,0,38,1473,70,173.9028251171 +66,,,,,,,,,, +67,,,,,,,,,, +67,BOWL,SUM,0,0,0,0,2,11,0,11.8775010109 +67,CUP,SUM,0,0,0,0,0,17,8,12.2043759823 +67,SPOON,SUM,0,0,0,0,0,74,1,19.4430539608 +67,,SUM,0,0,0,0,2,102,9,43.524930954 +67,,,,,,,,,, +68,,,,,,,,,, +68,BOWL,SUM,0,0,0,0,0,0,0,11.2157299519 +68,CUP,SUM,1,0,0,1,0,143,51,0 +68,SPOON,SUM,0,0,0,0,2,95,0,18.9592459202 +68,,SUM,1,0,0,1,2,238,51,30.174975872 +68,,,,,,,,,, +69,,,,,,,,,, +69,BOWL,SUM,0,0,0,0,24,37,0,24.1727600098 +69,CUP,SUM,1,0,0,1,0,168,51,0 +69,SPOON,SUM,0,0,0,0,2,76,5,21.753677845 +69,,SUM,1,0,0,1,26,281,56,45.9264378548 +69,,,,,,,,,, +70,,,,,,,,,, +70,BOWL,SUM,0,0,0,0,0,18,0,11.0195031166 +70,CUP,SUM,0,0,0,0,0,19,9,15.5879240036 +70,SPOON,SUM,0,0,0,0,0,19,2,16.6347930431 +70,,SUM,0,0,0,0,0,56,11,43.2422201633 +70,,,,,,,,,, +71,,,,,,,,,, +71,BOWL,SUM,0,0,0,0,0,5,0,10.7056469917 +71,CUP,SUM,1,0,0,1,0,169,60,0 +71,SPOON,SUM,0,0,0,0,0,1,1,15.3312017918 +71,,SUM,1,0,0,1,0,175,61,26.0368487835 +71,,,,,,,,,, +72,,,,,,,,,, +72,BOWL,SUM,0,0,0,0,0,3,0,10.4185960293 +72,CUP,SUM,0,0,0,0,0,2,5,9.8050858974 +72,SPOON,SUM,1,0,1,0,0,1581,0,0 +72,,SUM,1,0,1,0,0,1586,5,20.2236819267 +72,,,,,,,,,, +73,,,,,,,,,, +73,BOWL,SUM,0,0,0,0,0,3,0,10.6616098881 +73,CUP,SUM,0,0,0,0,0,9,4,8.8089518547 +73,SPOON,SUM,0,0,0,0,0,107,3,20.7143628597 +73,,SUM,0,0,0,0,0,119,7,40.1849246025 +73,,,,,,,,,, +74,,,,,,,,,, +74,BOWL,SUM,0,0,0,0,2,97,0,16.5192990303 +74,CUP,SUM,0,0,0,0,0,4,6,10.0969400406 +74,SPOON,SUM,0,0,0,0,0,258,4,29.7985079288 +74,,SUM,0,0,0,0,2,359,10,56.4147469997 +74,,,,,,,,,, +75,,,,,,,,,, +75,BOWL,SUM,0,0,0,0,62,22,2,41.8906271458 +75,CUP,SUM,0,0,0,0,0,4,1,9.0816571712 +75,SPOON,SUM,0,0,0,0,0,91,2,20.5431218147 +75,,SUM,0,0,0,0,62,117,5,71.5154061317 +75,,,,,,,,,, +76,,,,,,,,,, +76,BOWL,SUM,0,0,0,0,0,6,0,11.4136059284 +76,CUP,SUM,0,0,0,0,0,20,5,14.5074560642 +76,SPOON,SUM,0,0,0,0,0,53,0,16.3756158352 +76,,SUM,0,0,0,0,0,79,5,42.2966778278 +76,,,,,,,,,, +77,,,,,,,,,, +77,BOWL,SUM,0,0,0,0,0,133,0,18.8972239494 +77,CUP,SUM,1,0,0,1,0,180,54,0 +77,SPOON,SUM,0,0,0,0,0,30,0,15.42060709 +77,,SUM,1,0,0,1,0,343,54,34.3178310394 +77,,,,,,,,,, +78,,,,,,,,,, +78,BOWL,SUM,0,0,0,0,0,96,11,22.4815039635 +78,CUP,SUM,0,0,0,0,0,9,3,10.7427890301 +78,SPOON,SUM,0,0,0,0,0,280,3,32.4994959831 +78,,SUM,0,0,0,0,0,385,17,65.7237889767 +78,,,,,,,,,, +79,,,,,,,,,, +79,BOWL,SUM,0,0,0,0,16,8,4,20.9991071224 +79,CUP,SUM,0,0,0,0,0,52,12,18.9013102055 +79,SPOON,SUM,0,0,0,0,0,11,3,16.0657000542 +79,,SUM,0,0,0,0,16,71,19,55.966117382 +79,,,,,,,,,, +80,,,,,,,,,, +80,BOWL,SUM,0,0,0,0,56,32,2,39.5567438602 +80,CUP,SUM,0,0,0,0,0,19,3,14.0536909103 +80,SPOON,SUM,0,0,0,0,6,103,0,22.8978619576 +80,,SUM,0,0,0,0,62,154,5,76.5082967281 +80,,,,,,,,,, +81,,,,,,,,,, +81,BOWL,SUM,0,0,0,0,4,54,0,15.0736551285 +81,CUP,SUM,1,0,1,0,0,195,111,0 +81,SPOON,SUM,0,0,0,0,0,0,0,13.859995842 +81,,SUM,1,0,1,0,4,249,111,28.9336509705 +81,,,,,,,,,, +82,,,,,,,,,, +82,BOWL,SUM,0,0,0,0,2,8,0,11.584100008 +82,CUP,SUM,0,0,0,0,0,101,29,45.3676578999 +82,SPOON,SUM,0,0,0,0,0,120,4,22.0861668587 +82,,SUM,0,0,0,0,2,229,33,79.0379247665 +82,,,,,,,,,, +83,,,,,,,,,, +83,BOWL,SUM,0,0,0,0,12,8,0,16.806317091 +83,CUP,SUM,0,0,0,0,0,46,15,28.5379421711 +83,SPOON,SUM,0,0,0,0,0,19,1,15.9478399754 +83,,SUM,0,0,0,0,12,73,16,61.2920992374 +83,,,,,,,,,, +84,,,,,,,,,, +84,BOWL,SUM,0,0,0,0,0,19,4,13.8516299725 +84,CUP,SUM,0,0,0,0,0,44,15,19.7465732098 +84,SPOON,SUM,0,0,0,0,0,2,6,17.5947320461 +84,,SUM,0,0,0,0,0,65,25,51.1929352283 +84,,,,,,,,,, +85,,,,,,,,,, +85,BOWL,SUM,0,0,0,0,0,86,10,20.6243190765 +85,CUP,SUM,0,0,0,0,0,7,3,9.3238930702 +85,SPOON,SUM,0,0,0,0,0,28,0,14.9070649147 +85,,SUM,0,0,0,0,0,121,13,44.8552770615 +85,,,,,,,,,, +86,,,,,,,,,, +86,BOWL,SUM,0,0,0,0,0,54,2,13.5944600105 +86,CUP,SUM,0,0,0,0,26,17,2,22.9473929405 +86,SPOON,SUM,0,0,0,0,0,16,1,15.8730139732 +86,,SUM,0,0,0,0,26,87,5,52.4148669243 +86,,,,,,,,,, +87,,,,,,,,,, +87,BOWL,SUM,0,0,0,0,0,5,0,10.6904401779 +87,CUP,SUM,1,0,0,1,0,194,55,0 +87,SPOON,SUM,0,0,0,0,0,25,2,14.5198729038 +87,,SUM,1,0,0,1,0,224,57,25.2103130817 +87,,,,,,,,,, +88,,,,,,,,,, +88,BOWL,SUM,0,0,0,0,2,3,0,11.2333109379 +88,CUP,SUM,0,0,0,0,0,10,11,10.7935409546 +88,SPOON,SUM,0,0,0,0,0,0,2,16.5548419952 +88,,SUM,0,0,0,0,2,13,13,38.5816938877 +88,,,,,,,,,, +89,,,,,,,,,, +89,BOWL,SUM,0,0,0,0,0,3,0,11.0083270073 +89,CUP,SUM,0,0,0,0,2,38,3,14.888628006 +89,SPOON,SUM,0,0,0,0,0,146,0,22.3399760723 +89,,SUM,0,0,0,0,2,187,3,48.2369310856 +89,,,,,,,,,, +90,,,,,,,,,, +90,BOWL,SUM,1,1,0,0,384,455,0,0 +90,CUP,SUM,0,0,0,0,0,18,3,9.6275150776 +90,SPOON,SUM,0,0,0,0,4,34,0,16.2325279713 +90,,SUM,1,1,0,0,388,507,3,25.8600430489 +90,,,,,,,,,, +91,,,,,,,,,, +91,BOWL,SUM,0,0,0,0,32,37,0,25.7029521465 +91,CUP,SUM,0,0,0,0,2,18,16,18.9562761784 +91,SPOON,SUM,0,0,0,0,0,345,3,33.6609969139 +91,,SUM,0,0,0,0,34,400,19,78.3202252388 +91,,,,,,,,,, +92,,,,,,,,,, +92,BOWL,SUM,0,0,0,0,62,154,2,45.2091629505 +92,CUP,SUM,0,0,0,0,0,17,6,9.3940708637 +92,SPOON,SUM,1,0,1,0,0,1581,0,0 +92,,SUM,1,0,1,0,62,1752,8,54.6032338142 +92,,,,,,,,,, +93,,,,,,,,,, +93,BOWL,SUM,0,0,0,0,12,146,14,30.498114109 +93,CUP,SUM,0,0,0,0,0,9,3,8.9187998772 +93,SPOON,SUM,0,0,0,0,0,56,1,17.8166339397 +93,,SUM,0,0,0,0,12,211,18,57.2335479259 +93,,,,,,,,,, +94,,,,,,,,,, +94,BOWL,SUM,0,0,0,0,0,8,6,14.1179759502 +94,CUP,SUM,0,0,0,0,6,40,24,24.8547098637 +94,SPOON,SUM,0,0,0,0,4,4,2,15.7429480553 +94,,SUM,0,0,0,0,10,52,32,54.7156338692 +94,,,,,,,,,, +95,,,,,,,,,, +95,BOWL,SUM,0,0,0,0,0,30,2,11.8965439796 +95,CUP,SUM,0,0,0,0,16,24,8,17.1013100147 +95,SPOON,SUM,0,0,0,0,0,3,0,14.0029571056 +95,,SUM,0,0,0,0,16,57,10,43.0008111 +95,,,,,,,,,, +96,,,,,,,,,, +96,BOWL,SUM,0,0,0,0,0,10,0,10.8888990879 +96,CUP,SUM,0,0,0,0,0,68,24,29.9105060101 +96,SPOON,SUM,0,0,0,0,0,6,2,14.0350959301 +96,,SUM,0,0,0,0,0,84,26,54.8345010281 +96,,,,,,,,,, +97,,,,,,,,,, +97,BOWL,SUM,0,0,0,0,0,35,4,12.9667840004 +97,CUP,SUM,0,0,0,0,0,17,4,9.39179492 +97,SPOON,SUM,0,0,0,0,14,162,4,32.4749798775 +97,,SUM,0,0,0,0,14,214,12,54.8335587978 +97,,,,,,,,,, +98,,,,,,,,,, +98,BOWL,SUM,0,0,0,0,0,5,0,10.9837229252 +98,CUP,SUM,0,0,0,0,10,40,5,19.5750529766 +98,SPOON,SUM,0,0,0,0,0,135,11,28.437404871 +98,,SUM,0,0,0,0,10,180,16,58.9961807728 +98,,,,,,,,,, +99,,,,,,,,,, +99,BOWL,SUM,0,0,0,0,0,10,1,10.8137669563 +99,CUP,SUM,0,0,0,0,0,86,19,27.307708025 +99,SPOON,SUM,0,0,0,0,4,171,0,25.0550508499 +99,,SUM,0,0,0,0,4,267,20,63.1765258312 +99,,,,,,,,,, +100,,,,,,,,,, +100,BOWL,SUM,0,0,0,0,0,2,0,13.052863121 +100,CUP,SUM,1,0,1,0,0,193,104,0 +100,SPOON,SUM,0,0,0,0,0,0,0,13.005450964 +100,,SUM,1,0,1,0,0,195,104,26.058314085 +100,,,,,,,,,, +101,,,,,,,,,, +101,BOWL,SUM,0,0,0,0,6,2,2,12.5409259796 +101,CUP,SUM,0,0,0,0,0,30,8,13.0243799686 +101,SPOON,SUM,0,0,0,0,2,236,0,26.5775129795 +101,,SUM,0,0,0,0,8,268,10,52.1428189278 +101,,,,,,,,,, +102,,,,,,,,,, +102,BOWL,SUM,0,0,0,0,0,51,9,18.0838210583 +102,CUP,SUM,0,0,0,0,0,115,30,47.7770311832 +102,SPOON,SUM,0,0,0,0,0,25,2,14.0097219944 +102,,SUM,0,0,0,0,0,191,41,79.8705742359 +102,,,,,,,,,, +103,,,,,,,,,, +103,BOWL,SUM,0,0,0,0,0,59,0,12.3781960011 +103,CUP,SUM,0,0,0,0,2,12,0,8.9038379192 +103,SPOON,SUM,0,0,0,0,0,71,2,19.169095993 +103,,SUM,0,0,0,0,2,142,2,40.4511299133 +103,,,,,,,,,, +104,,,,,,,,,, +104,BOWL,SUM,0,0,0,0,4,19,2,11.8891198635 +104,CUP,SUM,0,0,0,0,6,6,7,11.5673241615 +104,SPOON,SUM,1,0,1,0,0,1581,0,0 +104,,SUM,1,0,1,0,10,1606,9,23.456444025 +104,,,,,,,,,, +105,,,,,,,,,, +105,BOWL,SUM,0,0,0,0,24,23,2,20.0996642113 +105,CUP,SUM,0,0,0,0,0,36,18,18.0566039085 +105,SPOON,SUM,0,0,0,0,0,0,2,13.2131118774 +105,,SUM,0,0,0,0,24,59,22,51.3693799973 +105,,,,,,,,,, +106,,,,,,,,,, +106,BOWL,SUM,0,0,0,0,0,5,0,9.9733068943 +106,CUP,SUM,0,0,0,0,0,25,3,9.928757906 +106,SPOON,SUM,0,0,0,0,0,0,0,12.942317009 +106,,SUM,0,0,0,0,0,30,3,32.8443818092 +106,,,,,,,,,, +107,,,,,,,,,, +107,BOWL,SUM,1,0,1,0,6,1072,58,0 +107,CUP,SUM,0,0,0,0,0,26,3,10.9662048817 +107,SPOON,SUM,0,0,0,0,0,18,2,14.1761798859 +107,,SUM,1,0,1,0,6,1116,63,25.1423847675 +107,,,,,,,,,, +108,,,,,,,,,, +108,BOWL,SUM,0,0,0,0,4,130,6,19.6393640041 +108,CUP,SUM,0,0,0,0,0,56,27,34.7063281536 +108,SPOON,SUM,0,0,0,0,0,1,0,13.9060578346 +108,,SUM,0,0,0,0,4,187,33,68.2517499924 +108,,,,,,,,,, +109,,,,,,,,,, +109,BOWL,SUM,0,0,0,0,0,22,2,11.0673601627 +109,CUP,SUM,1,0,0,1,0,197,58,0 +109,SPOON,SUM,0,0,0,0,0,82,1,18.8893449306 +109,,SUM,1,0,0,1,0,301,61,29.9567050934 +109,,,,,,,,,, +110,,,,,,,,,, +110,BOWL,SUM,0,0,0,0,0,117,4,17.9724900723 +110,CUP,SUM,0,0,0,0,2,19,11,11.3279910088 +110,SPOON,SUM,0,0,0,0,0,124,0,19.381029129 +110,,SUM,0,0,0,0,2,260,15,48.68151021 +110,,,,,,,,,, +111,,,,,,,,,, +111,BOWL,SUM,0,0,0,0,0,10,0,10.5157001019 +111,CUP,SUM,1,0,0,1,0,189,60,0 +111,SPOON,SUM,0,0,0,0,0,142,2,20.7339730263 +111,,SUM,1,0,0,1,0,341,62,31.2496731281 +111,,,,,,,,,, +112,,,,,,,,,, +112,BOWL,SUM,0,0,0,0,50,21,2,33.0779030323 +112,CUP,SUM,0,0,0,0,2,12,0,9.1863090992 +112,SPOON,SUM,0,0,0,0,0,3,7,19.4600839615 +112,,SUM,0,0,0,0,52,36,9,61.724296093 +112,,,,,,,,,, +113,,,,,,,,,, +113,BOWL,SUM,0,0,0,0,0,11,0,10.6338779926 +113,CUP,SUM,0,0,0,0,0,66,21,34.1474359035 +113,SPOON,SUM,0,0,0,0,0,165,2,22.953042984 +113,,SUM,0,0,0,0,0,242,23,67.7343568802 +113,,,,,,,,,, +114,,,,,,,,,, +114,BOWL,SUM,0,0,0,0,0,15,0,10.3616189957 +114,CUP,SUM,1,0,0,1,0,183,51,0 +114,SPOON,SUM,1,0,1,0,0,1369,34,0 +114,,SUM,2,0,1,1,0,1567,85,10.3616189957 +114,,,,,,,,,, +115,,,,,,,,,, +115,BOWL,SUM,0,0,0,0,2,38,0,11.5191209316 +115,CUP,SUM,0,0,0,0,0,24,12,11.2278130054 +115,SPOON,SUM,0,0,0,0,0,148,2,20.8394069672 +115,,SUM,0,0,0,0,2,210,14,43.5863409042 +115,,,,,,,,,, +116,,,,,,,,,, +116,BOWL,SUM,0,0,0,0,2,12,0,11.414741993 +116,CUP,SUM,0,0,0,0,0,2,6,9.0881528854 +116,SPOON,SUM,0,0,0,0,2,34,2,16.2265329361 +116,,SUM,0,0,0,0,4,48,8,36.7294278145 +116,,,,,,,,,, +117,,,,,,,,,, +117,BOWL,SUM,0,0,0,0,6,242,16,32.5883061886 +117,CUP,SUM,1,0,0,1,0,170,55,0 +117,SPOON,SUM,0,0,0,0,0,5,2,13.3119039536 +117,,SUM,1,0,0,1,6,417,73,45.9002101421 +117,,,,,,,,,, +118,,,,,,,,,, +118,BOWL,SUM,0,0,0,0,0,5,0,9.9260480404 +118,CUP,SUM,0,0,0,0,0,155,51,71.4399929047 +118,SPOON,SUM,0,0,0,0,0,104,2,18.2192840576 +118,,SUM,0,0,0,0,0,264,53,99.5853250027 +118,,,,,,,,,, +119,,,,,,,,,, +119,BOWL,SUM,1,0,1,0,4,997,60,0 +119,CUP,SUM,0,0,0,0,2,11,4,9.324999094 +119,SPOON,SUM,0,0,0,0,0,0,0,13.5500349998 +119,,SUM,1,0,1,0,6,1008,64,22.8750340939 +119,,,,,,,,,, +120,,,,,,,,,, +120,BOWL,SUM,0,0,0,0,0,2,0,13.4374439716 +120,CUP,SUM,1,0,1,0,0,193,104,0 +120,SPOON,SUM,0,0,0,0,0,0,0,13.1776411533 +120,,SUM,1,0,1,0,0,195,104,26.615085125 +120,,,,,,,,,, +121,,,,,,,,,, +121,BOWL,SUM,0,0,0,0,6,2,2,12.487872839 +121,CUP,SUM,0,0,0,0,0,30,8,13.0732688904 +121,SPOON,SUM,0,0,0,0,2,236,0,26.862694025 +121,,SUM,0,0,0,0,8,268,10,52.4238357544 +121,,,,,,,,,, +122,,,,,,,,,, +122,BOWL,SUM,0,0,0,0,0,51,9,18.0135438442 +122,CUP,SUM,0,0,0,0,0,115,30,46.1706149578 +122,SPOON,SUM,0,0,0,0,0,25,2,13.8283209801 +122,,SUM,0,0,0,0,0,191,41,78.0124797821 +122,,,,,,,,,, +123,,,,,,,,,, +123,BOWL,SUM,0,0,0,0,0,59,0,13.620349884 +123,CUP,SUM,0,0,0,0,2,12,0,9.2849991322 +123,SPOON,SUM,0,0,0,0,0,71,2,19.8381080627 +123,,SUM,0,0,0,0,2,142,2,42.7434570789 +123,,,,,,,,,, +124,,,,,,,,,, +124,BOWL,SUM,0,0,0,0,4,19,2,12.1370089054 +124,CUP,SUM,0,0,0,0,6,6,7,11.6897261143 +124,SPOON,SUM,1,0,1,0,0,1581,0,0 +124,,SUM,1,0,1,0,10,1606,9,23.8267350197 +124,,,,,,,,,, +125,,,,,,,,,, +125,BOWL,SUM,0,0,0,0,24,23,2,21.7553641796 +125,CUP,SUM,0,0,0,0,0,36,18,18.2251048088 +125,SPOON,SUM,0,0,0,0,0,0,2,13.3595399857 +125,,SUM,0,0,0,0,24,59,22,53.3400089741 +125,,,,,,,,,, +126,,,,,,,,,, +126,BOWL,SUM,0,0,0,0,0,5,0,10.2600491047 +126,CUP,SUM,0,0,0,0,0,25,3,9.9712748528 +126,SPOON,SUM,0,0,0,0,0,0,0,13.4429469109 +126,,SUM,0,0,0,0,0,30,3,33.6742708683 +126,,,,,,,,,, +127,,,,,,,,,, +127,BOWL,SUM,1,0,1,0,6,1072,58,0 +127,CUP,SUM,0,0,0,0,0,26,3,10.6569919586 +127,SPOON,SUM,0,0,0,0,0,18,2,13.6693310738 +127,,SUM,1,0,1,0,6,1116,63,24.3263230324 +127,,,,,,,,,, +128,,,,,,,,,, +128,BOWL,SUM,0,0,0,0,4,130,6,19.7672979832 +128,CUP,SUM,0,0,0,0,0,56,27,33.953854084 +128,SPOON,SUM,0,0,0,0,0,1,0,13.0830252171 +128,,SUM,0,0,0,0,4,187,33,66.8041772842 +128,,,,,,,,,, +129,,,,,,,,,, +129,BOWL,SUM,0,0,0,0,0,22,2,10.5215389729 +129,CUP,SUM,1,0,0,1,0,197,58,0 +129,SPOON,SUM,0,0,0,0,0,82,1,18.2805221081 +129,,SUM,1,0,0,1,0,301,61,28.8020610809 +129,,,,,,,,,, +130,,,,,,,,,, +130,BOWL,SUM,0,0,0,0,0,117,4,17.7211158276 +130,CUP,SUM,0,0,0,0,2,19,11,11.0642318726 +130,SPOON,SUM,0,0,0,0,0,124,0,18.8533520699 +130,,SUM,0,0,0,0,2,260,15,47.63869977 +130,,,,,,,,,, +131,,,,,,,,,, +131,BOWL,SUM,0,0,0,0,0,10,0,10.4005208015 +131,CUP,SUM,1,0,0,1,0,189,60,0 +131,SPOON,SUM,0,0,0,0,0,142,2,20.7632501125 +131,,SUM,1,0,0,1,0,341,62,31.1637709141 +131,,,,,,,,,, +132,,,,,,,,,, +132,BOWL,SUM,0,0,0,0,50,21,2,33.5841741562 +132,CUP,SUM,0,0,0,0,2,12,0,8.9722499847 +132,SPOON,SUM,0,0,0,0,0,3,7,19.8991770744 +132,,SUM,0,0,0,0,52,36,9,62.4556012154 +132,,,,,,,,,, +133,,,,,,,,,, +133,BOWL,SUM,0,0,0,0,0,11,0,10.6335070133 +133,CUP,SUM,0,0,0,0,0,66,21,33.1778199673 +133,SPOON,SUM,0,0,0,0,0,165,2,22.2840919495 +133,,SUM,0,0,0,0,0,242,23,66.0954189301 +133,,,,,,,,,, +134,,,,,,,,,, +134,BOWL,SUM,0,0,0,0,0,15,0,10.217867136 +134,CUP,SUM,1,0,0,1,0,183,51,0 +134,SPOON,SUM,1,0,1,0,0,1369,34,0 +134,,SUM,2,0,1,1,0,1567,85,10.217867136 +134,,,,,,,,,, +135,,,,,,,,,, +135,BOWL,SUM,0,0,0,0,2,38,0,12.0610880852 +135,CUP,SUM,0,0,0,0,0,24,12,10.7331449986 +135,SPOON,SUM,0,0,0,0,0,148,2,21.1178889275 +135,,SUM,0,0,0,0,2,210,14,43.9121220112 +135,,,,,,,,,, +136,,,,,,,,,, +136,BOWL,SUM,0,0,0,0,2,12,0,11.5710420609 +136,CUP,SUM,0,0,0,0,0,2,6,9.2862541676 +136,SPOON,SUM,0,0,0,0,2,34,2,16.7110910416 +136,,SUM,0,0,0,0,4,48,8,37.56838727 +136,,,,,,,,,, +137,,,,,,,,,, +137,BOWL,SUM,0,0,0,0,6,242,16,32.6078951359 +137,CUP,SUM,1,0,0,1,0,170,55,0 +137,SPOON,SUM,0,0,0,0,0,5,2,13.8619267941 +137,,SUM,1,0,0,1,6,417,73,46.4698219299 +137,,,,,,,,,, +138,,,,,,,,,, +138,BOWL,SUM,0,0,0,0,0,5,0,10.3215880394 +138,CUP,SUM,0,0,0,0,0,155,51,72.0785529613 +138,SPOON,SUM,0,0,0,0,0,104,2,19.0179030895 +138,,SUM,0,0,0,0,0,264,53,101.4180440903 +138,,,,,,,,,, +139,,,,,,,,,, +139,BOWL,SUM,1,0,1,0,4,997,60,0 +139,CUP,SUM,0,0,0,0,2,11,4,9.3728189468 +139,SPOON,SUM,0,0,0,0,0,0,0,13.9937829971 +139,,SUM,1,0,1,0,6,1008,64,23.366601944 +139,,,,,,,,,, +140,,,,,,,,,, +140,BOWL,SUM,0,0,0,0,0,33,4,12.7718129158 +140,CUP,SUM,0,0,0,0,0,4,7,8.746819973 +140,SPOON,SUM,0,0,0,0,0,200,0,24.0200829506 +140,,SUM,0,0,0,0,0,237,11,45.5387158394 +140,,,,,,,,,, +141,,,,,,,,,, +141,BOWL,SUM,0,0,0,0,2,100,4,16.8514959812 +141,CUP,SUM,0,0,0,0,0,7,3,8.4621469975 +141,SPOON,SUM,0,0,0,0,0,82,5,19.2508199215 +141,,SUM,0,0,0,0,2,189,12,44.5644629002 +141,,,,,,,,,, +142,,,,,,,,,, +142,BOWL,SUM,1,0,1,0,0,1162,40,0 +142,CUP,SUM,0,0,0,0,0,8,4,8.6596560478 +142,SPOON,SUM,0,0,0,0,0,3,4,16.4936330318 +142,,SUM,1,0,1,0,0,1173,48,25.1532890797 +142,,,,,,,,,, +143,,,,,,,,,, +143,BOWL,SUM,0,0,0,0,0,6,0,10.3611459732 +143,CUP,SUM,0,0,0,0,2,25,9,16.1652078629 +143,SPOON,SUM,0,0,0,0,0,2,1,14.7900190353 +143,,SUM,0,0,0,0,2,33,10,41.3163728714 +143,,,,,,,,,, +144,,,,,,,,,, +144,BOWL,SUM,0,0,0,0,0,10,4,11.7943761349 +144,CUP,SUM,1,0,1,0,6,442,99,0 +144,SPOON,SUM,0,0,0,0,0,74,4,18.7802860737 +144,,SUM,1,0,1,0,6,526,107,30.5746622086 +144,,,,,,,,,, +145,,,,,,,,,, +145,BOWL,SUM,1,0,1,0,0,867,51,0 +145,CUP,SUM,1,0,0,1,2,192,55,0 +145,SPOON,SUM,0,0,0,0,0,4,3,15.5828361511 +145,,SUM,2,0,1,1,2,1063,109,15.5828361511 +145,,,,,,,,,, +146,,,,,,,,,, +146,BOWL,SUM,0,0,0,0,2,25,0,11.8025960922 +146,CUP,SUM,1,0,0,1,0,148,57,0 +146,SPOON,SUM,1,0,1,0,0,1228,48,0 +146,,SUM,2,0,1,1,2,1401,105,11.8025960922 +146,,,,,,,,,, +147,,,,,,,,,, +147,BOWL,SUM,0,0,0,0,22,96,0,23.4685959816 +147,CUP,SUM,0,0,0,0,0,20,13,21.5116789341 +147,SPOON,SUM,0,0,0,0,0,76,4,20.3646709919 +147,,SUM,0,0,0,0,22,192,17,65.3449459076 +147,,,,,,,,,, +148,,,,,,,,,, +148,BOWL,SUM,0,0,0,0,0,24,0,10.8587260246 +148,CUP,SUM,0,0,0,0,0,17,11,14.3026320934 +148,SPOON,SUM,0,0,0,0,0,5,0,14.0577509403 +148,,SUM,0,0,0,0,0,46,11,39.2191090584 +148,,,,,,,,,, +149,,,,,,,,,, +149,BOWL,SUM,0,0,0,0,6,32,0,13.3329739571 +149,CUP,SUM,0,0,0,0,0,11,7,11.877614975 +149,SPOON,SUM,0,0,0,0,6,42,2,18.4794118404 +149,,SUM,0,0,0,0,12,85,9,43.6900007725 +149,,,,,,,,,, +150,,,,,,,,,, +150,BOWL,SUM,0,0,0,0,24,88,0,25.7518019676 +150,CUP,SUM,0,0,0,0,0,16,2,8.6216621399 +150,SPOON,SUM,0,0,0,0,0,26,0,13.9143211842 +150,,SUM,0,0,0,0,24,130,2,48.2877852917 +150,,,,,,,,,, +151,,,,,,,,,, +151,BOWL,SUM,0,0,0,0,0,56,4,14.0004348755 +151,CUP,SUM,0,0,0,0,0,4,4,8.6389648914 +151,SPOON,SUM,1,0,1,0,0,1386,32,0 +151,,SUM,1,0,1,0,0,1446,40,22.6393997669 +151,,,,,,,,,, +152,,,,,,,,,, +152,BOWL,SUM,0,0,0,0,0,3,3,11.8796730042 +152,CUP,SUM,0,0,0,0,0,9,6,9.2024619579 +152,SPOON,SUM,0,0,0,0,0,37,1,16.9269230366 +152,,SUM,0,0,0,0,0,49,10,38.0090579987 +152,,,,,,,,,, +153,,,,,,,,,, +153,BOWL,SUM,0,0,0,0,0,13,0,10.6844830513 +153,CUP,SUM,0,0,0,0,0,29,6,14.9018540382 +153,SPOON,SUM,0,0,0,0,0,1,3,17.2449970245 +153,,SUM,0,0,0,0,0,43,9,42.8313341141 +153,,,,,,,,,, +154,,,,,,,,,, +154,BOWL,SUM,0,0,0,0,0,13,2,10.7967720032 +154,CUP,SUM,0,0,0,0,0,101,49,63.9648530483 +154,SPOON,SUM,0,0,0,0,0,0,0,14.0960309505 +154,,SUM,0,0,0,0,0,114,51,88.857656002 +154,,,,,,,,,, +155,,,,,,,,,, +155,BOWL,SUM,0,0,0,0,0,31,0,11.2310898304 +155,CUP,SUM,0,0,0,0,0,43,17,19.3982429504 +155,SPOON,SUM,0,0,0,0,0,90,0,17.8853108883 +155,,SUM,0,0,0,0,0,164,17,48.5146436691 +155,,,,,,,,,, +156,,,,,,,,,, +156,BOWL,SUM,0,0,0,0,0,16,4,12.4269850254 +156,CUP,SUM,0,0,0,0,0,25,7,12.9765338898 +156,SPOON,SUM,0,0,0,0,0,225,0,25.0939030647 +156,,SUM,0,0,0,0,0,266,11,50.4974219799 +156,,,,,,,,,, +157,,,,,,,,,, +157,BOWL,SUM,0,0,0,0,0,10,0,10.6649508476 +157,CUP,SUM,0,0,0,0,16,39,4,17.3831188679 +157,SPOON,SUM,0,0,0,0,0,0,1,15.3499379158 +157,,SUM,0,0,0,0,16,49,5,43.3980076313 +157,,,,,,,,,, +158,,,,,,,,,, +158,BOWL,SUM,0,0,0,0,0,12,2,10.4998750687 +158,CUP,SUM,0,0,0,0,0,19,0,8.7623171806 +158,SPOON,SUM,1,0,1,0,2,1409,36,0 +158,,SUM,1,0,1,0,2,1440,38,19.2621922493 +158,,,,,,,,,, +159,,,,,,,,,, +159,BOWL,SUM,0,0,0,0,2,352,40,51.0557990074 +159,CUP,SUM,1,0,0,1,10,201,56,0 +159,SPOON,SUM,0,0,0,0,0,291,0,31.0260760784 +159,,SUM,1,0,0,1,12,844,96,82.0818750858 +159,,,,,,,,,, +160,,,,,,,,,, +160,BOWL,SUM,0,0,0,0,0,12,1,12.0300059319 +160,CUP,SUM,1,0,0,1,0,217,51,0 +160,SPOON,SUM,0,0,0,0,0,170,0,23.0664989948 +160,,SUM,1,0,0,1,0,399,52,35.0965049267 +160,,,,,,,,,, +161,,,,,,,,,, +161,BOWL,SUM,1,0,1,0,56,1298,44,0 +161,CUP,SUM,0,0,0,0,0,19,2,9.081346035 +161,SPOON,SUM,0,0,0,0,0,67,3,18.9586360455 +161,,SUM,1,0,1,0,56,1384,49,28.0399820805 +161,,,,,,,,,, +162,,,,,,,,,, +162,BOWL,SUM,0,0,0,0,0,16,0,10.4507870674 +162,CUP,SUM,0,0,0,0,0,3,5,8.5080919266 +162,SPOON,SUM,0,0,0,0,0,217,0,24.6702678204 +162,,SUM,0,0,0,0,0,236,5,43.6291468143 +162,,,,,,,,,, +163,,,,,,,,,, +163,BOWL,SUM,0,0,0,0,62,104,0,41.2226960659 +163,CUP,SUM,1,0,0,1,0,211,59,0 +163,SPOON,SUM,0,0,0,0,0,0,0,13.6994919777 +163,,SUM,1,0,0,1,62,315,59,54.9221880436 +163,,,,,,,,,, +164,,,,,,,,,, +164,BOWL,SUM,0,0,0,0,0,2,0,10.4059929848 +164,CUP,SUM,1,0,0,1,0,200,57,0 +164,SPOON,SUM,0,0,0,0,2,306,0,30.6191298962 +164,,SUM,1,0,0,1,2,508,57,41.0251228809 +164,,,,,,,,,, +165,,,,,,,,,, +165,BOWL,SUM,0,0,0,0,0,28,0,11.5787570477 +165,CUP,SUM,0,0,0,0,0,23,0,9.1481831074 +165,SPOON,SUM,0,0,0,0,0,0,2,13.9163560867 +165,,SUM,0,0,0,0,0,51,2,34.6432962418 +165,,,,,,,,,, +166,,,,,,,,,, +166,BOWL,SUM,0,0,0,0,0,20,6,13.8988039494 +166,CUP,SUM,0,0,0,0,0,0,2,8.4368979931 +166,SPOON,SUM,0,0,0,0,0,3,2,13.4313969612 +166,,SUM,0,0,0,0,0,23,10,35.7670989037 +166,,,,,,,,,, +167,,,,,,,,,, +167,BOWL,SUM,0,0,0,0,0,10,0,11.2223939896 +167,CUP,SUM,0,0,0,0,0,15,14,11.6374850273 +167,SPOON,SUM,0,0,0,0,6,132,0,21.7782142162 +167,,SUM,0,0,0,0,6,157,14,44.6380932331 +167,,,,,,,,,, +168,,,,,,,,,, +168,BOWL,SUM,0,0,0,0,56,19,0,36.5412931442 +168,CUP,SUM,0,0,0,0,0,35,8,12.0704109669 +168,SPOON,SUM,0,0,0,0,0,5,2,16.5440368652 +168,,SUM,0,0,0,0,56,59,10,65.1557409763 +168,,,,,,,,,, +169,,,,,,,,,, +169,BOWL,SUM,0,0,0,0,0,13,2,10.7951610088 +169,CUP,SUM,0,0,0,0,0,121,36,52.4618201256 +169,SPOON,SUM,0,0,0,0,0,2,2,14.3835790157 +169,,SUM,0,0,0,0,0,136,40,77.6405601501 +169,,,,,,,,,, +170,,,,,,,,,, +170,BOWL,SUM,0,0,0,0,0,24,4,12.6789000034 +170,CUP,SUM,0,0,0,0,0,59,16,20.9312999249 +170,SPOON,SUM,0,0,0,0,0,1,0,14.2320370674 +170,,SUM,0,0,0,0,0,84,20,47.8422369957 +170,,,,,,,,,, +171,,,,,,,,,, +171,BOWL,SUM,0,0,0,0,0,16,0,10.6809389591 +171,CUP,SUM,0,0,0,0,30,53,14,37.4141750336 +171,SPOON,SUM,0,0,0,0,6,63,1,18.490183115 +171,,SUM,0,0,0,0,36,132,15,66.5852971077 +171,,,,,,,,,, +172,,,,,,,,,, +172,BOWL,SUM,0,0,0,0,0,4,2,10.482749939 +172,CUP,SUM,0,0,0,0,0,3,0,8.3468878269 +172,SPOON,SUM,0,0,0,0,0,67,2,17.9105660915 +172,,SUM,0,0,0,0,0,74,4,36.7402038574 +172,,,,,,,,,, +173,,,,,,,,,, +173,BOWL,SUM,0,0,0,0,0,50,1,13.0639851093 +173,CUP,SUM,0,0,0,0,0,5,0,8.4901649952 +173,SPOON,SUM,0,0,0,0,0,55,0,15.7602910995 +173,,SUM,0,0,0,0,0,110,1,37.3144412041 +173,,,,,,,,,, +174,,,,,,,,,, +174,BOWL,SUM,0,0,0,0,0,84,4,16.1807880402 +174,CUP,SUM,0,0,0,0,0,42,13,21.9846179485 +174,SPOON,SUM,1,0,1,0,0,1590,0,0 +174,,SUM,1,0,1,0,0,1716,17,38.1654059887 +174,,,,,,,,,, +175,,,,,,,,,, +175,BOWL,SUM,0,0,0,0,0,37,11,18.5271849632 +175,CUP,SUM,0,0,0,0,0,49,9,19.2986450195 +175,SPOON,SUM,0,0,0,0,0,88,1,18.9491381645 +175,,SUM,0,0,0,0,0,174,21,56.7749681473 +175,,,,,,,,,, +176,,,,,,,,,, +176,BOWL,SUM,0,0,0,0,2,71,5,17.0128009319 +176,CUP,SUM,0,0,0,0,2,16,8,12.498059988 +176,SPOON,SUM,0,0,0,0,6,0,2,16.7299399376 +176,,SUM,0,0,0,0,10,87,15,46.2408008575 +176,,,,,,,,,, +177,,,,,,,,,, +177,BOWL,SUM,0,0,0,0,0,16,2,11.3769130707 +177,CUP,SUM,0,0,0,0,0,68,24,38.3872539997 +177,SPOON,SUM,0,0,0,0,10,187,0,28.3270149231 +177,,SUM,0,0,0,0,10,271,26,78.0911819935 +177,,,,,,,,,, +178,,,,,,,,,, +178,BOWL,SUM,0,0,0,0,0,4,0,10.2285051346 +178,CUP,SUM,0,0,0,0,0,23,4,9.2670040131 +178,SPOON,SUM,0,0,0,0,0,43,1,16.83466506 +178,,SUM,0,0,0,0,0,70,5,36.3301742077 +178,,,,,,,,,, +179,,,,,,,,,, +179,BOWL,SUM,0,0,0,0,0,49,0,11.7545390129 +179,CUP,SUM,1,0,1,0,0,346,110,0 +179,SPOON,SUM,0,0,0,0,0,4,3,17.0355088711 +179,,SUM,1,0,1,0,0,399,113,28.790047884 +179,,,,,,,,,, +180,,,,,,,,,, +180,BOWL,SUM,0,0,0,0,0,9,4,12.1283998489 +180,CUP,SUM,0,0,0,0,0,15,4,8.9259200096 +180,SPOON,SUM,0,0,0,0,0,3,1,14.9800620079 +180,,SUM,0,0,0,0,0,27,9,36.0343818665 +180,,,,,,,,,, +181,,,,,,,,,, +181,BOWL,SUM,0,0,0,0,6,3,0,12.6310510635 +181,CUP,SUM,1,0,0,1,0,210,57,0 +181,SPOON,SUM,0,0,0,0,0,157,1,23.7194049358 +181,,SUM,1,0,0,1,6,370,58,36.3504559994 +181,,,,,,,,,, +182,,,,,,,,,, +182,BOWL,SUM,0,0,0,0,0,12,1,12.5822198391 +182,CUP,SUM,1,0,0,1,0,179,59,0 +182,SPOON,SUM,0,0,0,0,0,48,0,16.1056759357 +182,,SUM,1,0,0,1,0,239,60,28.6878957748 +182,,,,,,,,,, +183,,,,,,,,,, +183,BOWL,SUM,0,0,0,0,0,2,4,12.471503973 +183,CUP,SUM,0,0,0,0,0,13,0,8.5534260273 +183,SPOON,SUM,0,0,0,0,0,24,3,16.3540019989 +183,,SUM,0,0,0,0,0,39,7,37.3789319992 +183,,,,,,,,,, +184,,,,,,,,,, +184,BOWL,SUM,1,0,1,0,0,983,69,0 +184,CUP,SUM,0,0,0,0,0,14,9,16.2027759552 +184,SPOON,SUM,0,0,0,0,0,50,0,16.6958909035 +184,,SUM,1,0,1,0,0,1047,78,32.8986668587 +184,,,,,,,,,, +185,,,,,,,,,, +185,BOWL,SUM,0,0,0,0,0,21,0,10.7679769993 +185,CUP,SUM,0,0,0,0,0,25,12,18.5015289783 +185,SPOON,SUM,0,0,0,0,0,12,0,13.2783169746 +185,,SUM,0,0,0,0,0,58,12,42.5478229523 +185,,,,,,,,,, +186,,,,,,,,,, +186,BOWL,SUM,0,0,0,0,0,15,0,10.3319990635 +186,CUP,SUM,0,0,0,0,0,57,10,21.5417628288 +186,SPOON,SUM,0,0,0,0,0,284,8,34.6240530014 +186,,SUM,0,0,0,0,0,356,18,66.4978148937 +186,,,,,,,,,, +187,,,,,,,,,, +187,BOWL,SUM,0,0,0,0,0,15,0,10.8381860256 +187,CUP,SUM,1,0,1,0,0,227,110,0 +187,SPOON,SUM,0,0,0,0,0,410,6,38.1361851692 +187,,SUM,1,0,1,0,0,652,116,48.9743711948 +187,,,,,,,,,, +188,,,,,,,,,, +188,BOWL,SUM,1,0,1,0,6,952,72,0 +188,CUP,SUM,0,0,0,0,0,15,6,9.4639840126 +188,SPOON,SUM,0,0,0,0,2,286,4,35.5005531311 +188,,SUM,1,0,1,0,8,1253,82,44.9645371437 +188,,,,,,,,,, +189,,,,,,,,,, +189,BOWL,SUM,0,0,0,0,0,57,2,12.6757290363 +189,CUP,SUM,0,0,0,0,0,16,3,8.9909579754 +189,SPOON,SUM,0,0,0,0,0,82,2,18.0899319649 +189,,SUM,0,0,0,0,0,155,7,39.7566189766 +189,,,,,,,,,, +190,,,,,,,,,, +190,BOWL,SUM,0,0,0,0,0,1,2,10.4237420559 +190,CUP,SUM,0,0,0,0,0,18,6,10.4538919926 +190,SPOON,SUM,0,0,0,0,0,33,0,15.8117828369 +190,,SUM,0,0,0,0,0,52,8,36.6894168854 +190,,,,,,,,,, +191,,,,,,,,,, +191,BOWL,SUM,0,0,0,0,2,10,1,12.6614360809 +191,CUP,SUM,0,0,0,0,0,22,1,10.393253088 +191,SPOON,SUM,0,0,0,0,0,20,0,14.3082411289 +191,,SUM,0,0,0,0,2,52,2,37.3629302979 +191,,,,,,,,,, +192,,,,,,,,,, +192,BOWL,SUM,0,0,0,0,0,49,0,12.7961928844 +192,CUP,SUM,0,0,0,0,0,39,7,13.8595490456 +192,SPOON,SUM,0,0,0,0,2,35,2,16.6537849903 +192,,SUM,0,0,0,0,2,123,9,43.3095269203 +192,,,,,,,,,, +193,,,,,,,,,, +193,BOWL,SUM,0,0,0,0,2,50,4,15.05072999 +193,CUP,SUM,1,0,1,0,0,217,110,0 +193,SPOON,SUM,0,0,0,0,0,41,2,16.1056468487 +193,,SUM,1,0,1,0,2,308,116,31.1563768387 +193,,,,,,,,,, +194,,,,,,,,,, +194,BOWL,SUM,0,0,0,0,0,19,0,10.4766149521 +194,CUP,SUM,1,0,0,1,0,172,57,0 +194,SPOON,SUM,0,0,0,0,0,198,14,30.790446043 +194,,SUM,1,0,0,1,0,389,71,41.2670609951 +194,,,,,,,,,, +195,,,,,,,,,, +195,BOWL,SUM,0,0,0,0,2,12,0,11.68780303 +195,CUP,SUM,1,0,0,1,0,178,51,0 +195,SPOON,SUM,0,0,0,0,0,88,0,18.5776808262 +195,,SUM,1,0,0,1,2,278,51,30.2654838562 +195,,,,,,,,,, +196,,,,,,,,,, +196,BOWL,SUM,0,0,0,0,0,8,2,11.1820042133 +196,CUP,SUM,1,0,1,0,2,136,111,0 +196,SPOON,SUM,0,0,0,0,0,13,4,17.2649579048 +196,,SUM,1,0,1,0,2,157,117,28.4469621181 +196,,,,,,,,,, +197,,,,,,,,,, +197,BOWL,SUM,0,0,0,0,2,103,17,26.9245710373 +197,CUP,SUM,0,0,0,0,16,18,5,18.645359993 +197,SPOON,SUM,0,0,0,0,0,16,4,16.0492010117 +197,,SUM,0,0,0,0,18,137,26,61.6191320419 +197,,,,,,,,,, +198,,,,,,,,,, +198,BOWL,SUM,0,0,0,0,0,4,0,10.1968820095 +198,CUP,SUM,0,0,0,0,0,175,49,46.0071649551 +198,SPOON,SUM,0,0,0,0,0,1,0,13.782378912 +198,,SUM,0,0,0,0,0,180,49,69.9864258766 +198,,,,,,,,,, +199,,,,,,,,,, +199,BOWL,SUM,0,0,0,0,0,14,0,10.8508141041 +199,CUP,SUM,0,0,0,0,0,51,13,21.980009079 +199,SPOON,SUM,0,0,0,0,0,12,0,15.2578251362 +199,,SUM,0,0,0,0,0,77,13,48.0886483192 +199,,,,,,,,,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/Pr2_Hr_Sim_Mod.csv b/cram_knowrob/cram_knowrob_vr/experiments/Pr2_Hr_Sim_Mod.csv new file mode 100644 index 0000000000..a0a0f27956 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/Pr2_Hr_Sim_Mod.csv @@ -0,0 +1,603 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,0,11,101,30.947895050048828 +0,CUP,SUM,0,0,0,0,0,2,12,6.757516145706177 +0,SPOON,SUM,0,0,0,0,0,1,6,11.062914848327637 +0,,SUM,0,0,0,0,0,14,119,48.76832604408264 +0,, +1,, +1,BOWL,SUM,1,0,1,0,0,54,204,0.0 +1,CUP,SUM,0,0,0,0,0,0,25,10.552206039428711 +1,SPOON,SUM,0,0,0,0,0,3,1,10.046876907348633 +1,,SUM,1,0,1,0,0,57,230,20.599082946777344 +1,, +2,, +2,BOWL,SUM,0,0,0,0,0,1,39,15.53513503074646 +2,CUP,SUM,0,0,0,0,0,3,18,9.428974866867065 +2,SPOON,SUM,0,0,0,0,16,10,40,23.712773084640503 +2,,SUM,0,0,0,0,16,14,97,48.67688298225403 +2,, +3,, +3,BOWL,SUM,0,0,0,0,0,1,15,13.767441987991333 +3,CUP,SUM,0,0,0,0,0,0,4,5.255272150039673 +3,SPOON,SUM,0,0,0,0,8,3,3,13.062561988830566 +3,,SUM,0,0,0,0,8,4,22,32.08527612686157 +3,, +4,, +4,BOWL,SUM,0,0,0,0,2,8,44,15.6176438331604 +4,CUP,SUM,0,0,0,0,0,1,13,6.98077392578125 +4,SPOON,SUM,0,0,0,0,0,1,4,10.228117942810059 +4,,SUM,0,0,0,0,2,10,61,32.82653570175171 +4,, +5,, +5,BOWL,SUM,1,0,1,0,16,36,204,0.0 +5,CUP,SUM,0,0,0,0,8,4,7,9.982322931289673 +5,SPOON,SUM,0,0,0,0,0,2,12,12.382373094558716 +5,,SUM,1,0,1,0,24,42,223,22.36469602584839 +5,, +6,, +6,BOWL,SUM,0,0,0,0,8,3,7,11.168004035949707 +6,CUP,SUM,0,0,0,0,0,0,6,4.450785875320435 +6,SPOON,SUM,0,0,0,0,0,1,16,12.690342903137207 +6,,SUM,0,0,0,0,8,4,29,28.30913281440735 +6,, +7,, +7,BOWL,SUM,0,0,0,0,8,0,6,11.877129793167114 +7,CUP,SUM,0,0,0,0,0,1,14,7.1929240226745605 +7,SPOON,SUM,0,0,0,0,10,0,8,14.81130599975586 +7,,SUM,0,0,0,0,18,1,28,33.881359815597534 +7,, +8,, +8,BOWL,SUM,0,0,0,0,0,0,4,8.286001920700073 +8,CUP,SUM,0,0,0,0,8,0,8,7.998787879943848 +8,SPOON,SUM,0,0,0,0,2,1,0,10.407246112823486 +8,,SUM,0,0,0,0,10,1,12,26.692035913467407 +8,, +9,, +9,BOWL,SUM,0,0,0,0,0,0,4,8.119594097137451 +9,CUP,SUM,0,0,0,0,0,0,11,7.226028919219971 +9,SPOON,SUM,0,0,0,0,8,1,6,15.145843029022217 +9,,SUM,0,0,0,0,8,1,21,30.49146604537964 +9,, +10,, +10,BOWL,SUM,0,0,0,0,0,0,3,7.55772590637207 +10,CUP,SUM,0,0,0,0,8,1,6,7.361175060272217 +10,SPOON,SUM,0,0,0,0,0,1,0,9.437873125076294 +10,,SUM,0,0,0,0,8,2,9,24.35677409172058 +10,, +11,, +11,BOWL,SUM,0,0,0,0,0,2,12,11.058701038360596 +11,CUP,SUM,0,0,0,0,0,0,9,6.512531995773315 +11,SPOON,SUM,0,0,0,0,0,3,22,13.890827894210815 +11,,SUM,0,0,0,0,0,5,43,31.462060928344727 +11,, +12,, +12,BOWL,SUM,1,0,1,0,8,68,204,0.0 +12,CUP,SUM,0,0,0,0,0,1,25,8.89723515510559 +12,SPOON,SUM,0,0,0,0,0,0,4,10.443244934082031 +12,,SUM,1,0,1,0,8,69,233,19.340480089187622 +12,, +13,, +13,BOWL,SUM,0,0,0,0,0,2,15,12.459026098251343 +13,CUP,SUM,0,0,0,0,0,0,4,4.932958126068115 +13,SPOON,SUM,0,0,0,0,8,2,12,16.124733209609985 +13,,SUM,0,0,0,0,8,4,31,33.51671743392944 +13,, +14,, +14,BOWL,SUM,0,0,0,0,0,0,3,7.806452989578247 +14,CUP,SUM,0,0,0,0,0,2,2,3.8844149112701416 +14,SPOON,SUM,1,0,1,0,4,86,196,0.0 +14,,SUM,1,0,1,0,4,88,201,11.690867900848389 +14,, +15,, +15,BOWL,SUM,0,0,0,0,8,2,16,14.482784032821655 +15,CUP,SUM,0,0,0,0,0,3,12,8.19175100326538 +15,SPOON,SUM,1,0,1,0,0,72,204,0.0 +15,,SUM,1,0,1,0,8,77,232,22.674535036087036 +15,, +16,, +16,BOWL,SUM,0,0,0,0,8,1,8,10.785851001739502 +16,CUP,SUM,0,0,0,0,0,3,17,8.56073808670044 +16,SPOON,SUM,0,0,0,0,0,8,81,25.5260329246521 +16,,SUM,0,0,0,0,8,12,106,44.87262201309204 +16,, +17,, +17,BOWL,SUM,1,0,1,0,0,31,204,0.0 +17,CUP,SUM,0,0,0,0,8,1,30,20.39389395713806 +17,SPOON,SUM,0,0,0,0,0,0,1,11.205448865890503 +17,,SUM,1,0,1,0,8,32,235,31.599342823028564 +17,, +18,, +18,BOWL,SUM,1,0,1,0,0,30,204,0.0 +18,CUP,SUM,0,0,0,0,0,1,6,5.273311138153076 +18,SPOON,SUM,0,0,0,0,0,2,1,10.706218004226685 +18,,SUM,1,0,1,0,0,33,211,15.97952914237976 +18,, +19,, +19,BOWL,SUM,0,0,0,0,8,5,16,14.567909955978394 +19,CUP,SUM,0,0,0,0,0,1,7,7.32523512840271 +19,SPOON,SUM,0,0,0,0,0,1,0,10.447367906570435 +19,,SUM,0,0,0,0,8,7,23,32.34051299095154 +19,, +20,, +20,BOWL,SUM,1,0,1,0,24,28,204,0.0 +20,CUP,SUM,0,0,0,0,8,1,8,13.280457019805908 +20,SPOON,SUM,0,0,0,0,0,2,16,16.712249040603638 +20,,SUM,1,0,1,0,32,31,228,29.992706060409546 +20,, +21,, +21,BOWL,SUM,0,0,0,0,0,1,14,11.126348972320557 +21,CUP,SUM,0,0,0,0,0,3,15,7.763705015182495 +21,SPOON,SUM,1,0,1,0,16,82,204,0.0 +21,,SUM,1,0,1,0,16,86,233,18.89005398750305 +21,, +22,, +22,BOWL,SUM,0,0,0,0,0,6,32,14.609799861907959 +22,CUP,SUM,0,0,0,0,0,0,5,5.957469940185547 +22,SPOON,SUM,0,0,0,0,0,3,33,18.1270489692688 +22,,SUM,0,0,0,0,0,9,70,38.694318771362305 +22,, +23,, +23,BOWL,SUM,0,0,0,0,0,1,2,8.711052179336548 +23,CUP,SUM,0,0,0,0,0,0,4,6.325968980789185 +23,SPOON,SUM,0,0,0,0,24,3,1,27.381815910339355 +23,,SUM,0,0,0,0,24,4,7,42.41883707046509 +23,, +24,, +24,BOWL,SUM,1,0,1,0,16,64,204,0.0 +24,CUP,SUM,0,0,0,0,0,21,173,51.07543706893921 +24,SPOON,SUM,0,0,0,0,0,3,32,18.02010488510132 +24,,SUM,1,0,1,0,16,88,409,69.09554195404053 +24,, +25,, +25,BOWL,SUM,0,0,0,0,8,1,4,13.44439697265625 +25,CUP,SUM,0,0,0,0,0,0,19,8.008301019668579 +25,SPOON,SUM,0,0,0,0,0,1,0,12.161245822906494 +25,,SUM,0,0,0,0,8,2,23,33.61394381523132 +25,, +26,, +26,BOWL,SUM,0,0,0,0,0,3,15,13.277894973754883 +26,CUP,SUM,0,0,0,0,0,0,11,10.962982892990112 +26,SPOON,SUM,0,0,0,0,0,0,26,17.281687021255493 +26,,SUM,0,0,0,0,0,3,52,41.52256488800049 +26,, +27,, +27,BOWL,SUM,0,0,0,0,0,1,0,7.927381992340088 +27,CUP,SUM,0,0,0,0,0,0,9,6.361402988433838 +27,SPOON,SUM,0,0,0,0,20,3,14,25.287647008895874 +27,,SUM,0,0,0,0,20,4,23,39.5764319896698 +27,, +28,, +28,BOWL,SUM,0,0,0,0,0,2,8,10.272153854370117 +28,CUP,SUM,0,0,0,0,0,0,18,8.025156021118164 +28,SPOON,SUM,1,0,1,0,40,56,204,0.0 +28,,SUM,1,0,1,0,40,58,230,18.29730987548828 +28,, +29,, +29,BOWL,SUM,0,0,0,0,0,0,6,10.29205584526062 +29,CUP,SUM,0,0,0,0,0,2,21,10.242625951766968 +29,SPOON,SUM,0,0,0,0,0,0,1,12.116567850112915 +29,,SUM,0,0,0,0,0,2,28,32.6512496471405 +29,, +30,, +30,BOWL,SUM,0,0,0,0,8,3,46,25.41502094268799 +30,CUP,SUM,0,0,0,0,0,0,16,9.71445107460022 +30,SPOON,SUM,0,0,0,0,0,2,15,14.874921083450317 +30,,SUM,0,0,0,0,8,5,77,50.004393100738525 +30,, +31,, +31,BOWL,SUM,0,0,0,0,0,2,0,8.627493858337402 +31,CUP,SUM,0,0,0,0,72,2,17,48.1632981300354 +31,SPOON,SUM,0,0,0,0,8,3,13,18.513195991516113 +31,,SUM,0,0,0,0,80,7,30,75.30398797988892 +31,, +32,, +32,BOWL,SUM,0,0,0,0,0,4,21,13.773112773895264 +32,CUP,SUM,0,0,0,0,24,3,8,21.706571102142334 +32,SPOON,SUM,0,0,0,0,0,1,5,13.453920125961304 +32,,SUM,0,0,0,0,24,8,34,48.9336040019989 +32,, +33,, +33,BOWL,SUM,0,0,0,0,0,0,23,15.409810066223145 +33,CUP,SUM,0,0,0,0,0,0,17,10.398370027542114 +33,SPOON,SUM,1,0,1,0,36,42,204,0.0 +33,,SUM,1,0,1,0,36,42,244,25.80818009376526 +33,, +34,, +34,BOWL,SUM,0,0,0,0,0,0,2,9.265542984008789 +34,CUP,SUM,0,0,0,0,0,0,11,7.431578874588013 +34,SPOON,SUM,0,0,0,0,2,1,0,12.320930004119873 +34,,SUM,0,0,0,0,2,1,13,29.018051862716675 +34,, +35,, +35,BOWL,SUM,0,0,0,0,8,4,18,21.273263931274414 +35,CUP,SUM,0,0,0,0,0,2,9,7.87228798866272 +35,SPOON,SUM,0,0,0,0,0,9,40,20.16071891784668 +35,,SUM,0,0,0,0,8,15,67,49.30627083778381 +35,, +36,, +36,BOWL,SUM,0,0,0,0,0,0,0,7.731735944747925 +36,CUP,SUM,0,0,0,0,0,1,23,8.87150502204895 +36,SPOON,SUM,0,0,0,0,0,1,4,11.947299003601074 +36,,SUM,0,0,0,0,0,2,27,28.55053997039795 +36,, +37,, +37,BOWL,SUM,0,0,0,0,0,2,30,15.662863969802856 +37,CUP,SUM,0,0,0,0,0,0,5,7.417399168014526 +37,SPOON,SUM,0,0,0,0,0,1,1,11.969904899597168 +37,,SUM,0,0,0,0,0,3,36,35.05016803741455 +37,, +38,, +38,BOWL,SUM,0,0,0,0,0,1,16,12.21382999420166 +38,CUP,SUM,1,0,1,0,8,18,51,0.0 +38,SPOON,SUM,1,0,1,0,8,85,204,0.0 +38,,SUM,2,0,2,0,16,104,271,12.21382999420166 +38,, +39,, +39,BOWL,SUM,0,0,0,0,0,0,13,13.705271005630493 +39,CUP,SUM,0,0,0,0,0,0,32,10.173105955123901 +39,SPOON,SUM,0,0,0,0,0,1,2,11.856977939605713 +39,,SUM,0,0,0,0,0,1,47,35.73535490036011 +39,, +40,, +40,BOWL,SUM,0,0,0,0,0,15,139,41.478070974349976 +40,CUP,SUM,0,0,0,0,0,1,14,11.863762855529785 +40,SPOON,SUM,0,0,0,0,0,1,9,13.706906080245972 +40,,SUM,0,0,0,0,0,17,162,67.04873991012573 +40,, +41,, +41,BOWL,SUM,0,0,0,0,0,0,7,10.941974878311157 +41,CUP,SUM,0,0,0,0,8,0,10,12.403064966201782 +41,SPOON,SUM,0,0,0,0,0,0,1,11.583636999130249 +41,,SUM,0,0,0,0,8,0,18,34.92867684364319 +41,, +42,, +42,BOWL,SUM,0,0,0,0,0,2,30,15.485456943511963 +42,CUP,SUM,0,0,0,0,0,1,22,9.095629930496216 +42,SPOON,SUM,0,0,0,0,0,1,5,13.356741189956665 +42,,SUM,0,0,0,0,0,4,57,37.937828063964844 +42,, +43,, +43,BOWL,SUM,0,0,0,0,8,15,80,31.662474870681763 +43,CUP,SUM,0,0,0,0,0,0,7,7.184250831604004 +43,SPOON,SUM,0,0,0,0,0,1,8,13.374405860900879 +43,,SUM,0,0,0,0,8,16,95,52.221131563186646 +43,, +44,, +44,BOWL,SUM,0,0,0,0,40,3,9,32.507761001586914 +44,CUP,SUM,0,0,0,0,0,0,11,8.499835968017578 +44,SPOON,SUM,0,0,0,0,2,1,3,13.63094186782837 +44,,SUM,0,0,0,0,42,4,23,54.63853883743286 +44,, +45,, +45,BOWL,SUM,0,0,0,0,8,1,26,21.200900077819824 +45,CUP,SUM,0,0,0,0,56,4,19,47.527421951293945 +45,SPOON,SUM,0,0,0,0,0,1,1,13.102787971496582 +45,,SUM,0,0,0,0,64,6,46,81.83111000061035 +45,, +46,, +46,BOWL,SUM,0,0,0,0,0,5,101,29.560819149017334 +46,CUP,SUM,1,0,1,0,0,39,153,0.0 +46,SPOON,SUM,0,0,0,0,0,1,0,12.06042194366455 +46,,SUM,1,0,1,0,0,45,254,41.621241092681885 +46,, +47,, +47,BOWL,SUM,0,0,0,0,0,2,55,25.000555992126465 +47,CUP,SUM,0,0,0,0,0,1,4,7.548130035400391 +47,SPOON,SUM,0,0,0,0,0,0,0,11.247426986694336 +47,,SUM,0,0,0,0,0,3,59,43.79611301422119 +47,, +48,, +48,BOWL,SUM,0,0,0,0,0,8,67,27.018110990524292 +48,CUP,SUM,0,0,0,0,8,1,4,11.367005109786987 +48,SPOON,SUM,0,0,0,0,0,0,20,16.628227949142456 +48,,SUM,0,0,0,0,8,9,91,55.013344049453735 +48,, +49,, +49,BOWL,SUM,1,0,1,0,0,82,204,0.0 +49,CUP,SUM,0,0,0,0,0,0,2,6.556262969970703 +49,SPOON,SUM,0,0,0,0,0,1,6,13.07364296913147 +49,,SUM,1,0,1,0,0,83,212,19.629905939102173 +49,, +50,, +50,BOWL,SUM,0,0,0,0,0,2,30,18.62345790863037 +50,CUP,SUM,0,0,0,0,0,2,8,8.239843130111694 +50,SPOON,SUM,0,0,0,0,24,3,10,29.568562030792236 +50,,SUM,0,0,0,0,24,7,48,56.4318630695343 +50,, +51,, +51,BOWL,SUM,0,0,0,0,0,1,8,10.541808128356934 +51,CUP,SUM,0,0,0,0,0,9,28,13.681670188903809 +51,SPOON,SUM,0,0,0,0,0,0,0,11.978713989257813 +51,,SUM,0,0,0,0,0,10,36,36.202192306518555 +51,, +52,, +52,BOWL,SUM,0,0,0,0,0,3,28,15.332066059112549 +52,CUP,SUM,0,0,0,0,40,1,6,33.51446509361267 +52,SPOON,SUM,0,0,0,0,8,0,4,16.747199058532715 +52,,SUM,0,0,0,0,48,4,38,65.59373021125793 +52,, +53,, +53,BOWL,SUM,0,0,0,0,0,1,22,19.81544804573059 +53,CUP,SUM,0,0,0,0,0,4,14,10.472105979919434 +53,SPOON,SUM,0,0,0,0,0,1,0,12.246814966201782 +53,,SUM,0,0,0,0,0,6,36,42.53436899185181 +53,, +54,, +54,BOWL,SUM,0,0,0,0,0,3,0,9.31118392944336 +54,CUP,SUM,0,0,0,0,0,2,9,7.5386879444122314 +54,SPOON,SUM,0,0,0,0,0,2,9,14.29137396812439 +54,,SUM,0,0,0,0,0,7,18,31.14124584197998 +54,, +55,, +55,BOWL,SUM,1,0,1,0,0,43,204,0.0 +55,CUP,SUM,0,0,0,0,0,2,29,19.920816898345947 +55,SPOON,SUM,0,0,0,0,0,2,4,12.95712399482727 +55,,SUM,1,0,1,0,0,47,237,32.87794089317322 +55,, +56,, +56,BOWL,SUM,0,0,0,0,0,1,12,10.506341934204102 +56,CUP,SUM,0,0,0,0,0,0,11,7.810647964477539 +56,SPOON,SUM,0,0,0,0,2,5,37,20.260270833969116 +56,,SUM,0,0,0,0,2,6,60,38.57726073265076 +56,, +57,, +57,BOWL,SUM,0,0,0,0,0,0,7,11.16220998764038 +57,CUP,SUM,0,0,0,0,0,0,6,7.841785907745361 +57,SPOON,SUM,1,0,1,0,0,58,204,0.0 +57,,SUM,1,0,1,0,0,58,217,19.003995895385742 +57,, +58,, +58,BOWL,SUM,0,0,0,0,0,2,11,11.295140981674194 +58,CUP,SUM,0,0,0,0,0,1,13,8.545651912689209 +58,SPOON,SUM,0,0,0,0,0,5,32,18.816601991653442 +58,,SUM,0,0,0,0,0,8,56,38.657394886016846 +58,, +59,, +59,BOWL,SUM,0,0,0,0,32,4,35,37.10544395446777 +59,CUP,SUM,0,0,0,0,0,0,2,5.746957063674927 +59,SPOON,SUM,0,0,0,0,0,1,4,13.116594076156616 +59,,SUM,0,0,0,0,32,5,41,55.968995094299316 +59,, +60,, +60,BOWL,SUM,0,0,0,0,0,0,6,11.471202850341797 +60,CUP,SUM,0,0,0,0,0,1,14,8.007760047912598 +60,SPOON,SUM,0,0,0,0,0,7,20,15.872313022613525 +60,,SUM,0,0,0,0,0,8,40,35.35127592086792 +60,, +61,, +61,BOWL,SUM,0,0,0,0,0,0,34,19.023357152938843 +61,CUP,SUM,0,0,0,0,0,4,21,9.41598391532898 +61,SPOON,SUM,0,0,0,0,0,0,1,11.418191194534302 +61,,SUM,0,0,0,0,0,4,56,39.857532262802124 +61,, +62,, +62,BOWL,SUM,0,0,0,0,0,3,29,13.806430101394653 +62,CUP,SUM,0,0,0,0,8,0,2,11.367779970169067 +62,SPOON,SUM,0,0,0,0,0,0,8,12.685835838317871 +62,,SUM,0,0,0,0,8,3,39,37.86004590988159 +62,, +63,, +63,BOWL,SUM,1,0,1,0,16,62,204,0.0 +63,CUP,SUM,0,0,0,0,0,5,9,9.952462911605835 +63,SPOON,SUM,0,0,0,0,0,2,36,19.851469039916992 +63,,SUM,1,0,1,0,16,69,249,29.803931951522827 +63,, +64,, +64,BOWL,SUM,1,0,1,0,0,22,204,0.0 +64,CUP,SUM,0,0,0,0,0,0,7,8.96185302734375 +64,SPOON,SUM,0,0,0,0,0,0,5,13.860907077789307 +64,,SUM,1,0,1,0,0,22,216,22.822760105133057 +64,, +65,, +65,BOWL,SUM,0,0,0,0,8,1,4,14.96309208869934 +65,CUP,SUM,0,0,0,0,0,0,21,16.118754148483276 +65,SPOON,SUM,0,0,0,0,0,1,0,17.147149085998535 +65,,SUM,0,0,0,0,8,2,25,48.22899532318115 +65,, +66,, +66,BOWL,SUM,0,0,0,0,0,0,4,14.041270017623901 +66,CUP,SUM,1,0,1,0,8,29,51,0.0 +66,SPOON,SUM,0,0,0,0,0,2,6,21.430290937423706 +66,,SUM,1,0,1,0,8,31,61,35.47156095504761 +66,, +67,, +67,BOWL,SUM,0,0,0,0,0,0,5,16.31893301010132 +67,CUP,SUM,0,0,0,0,0,0,4,13.015959978103638 +67,SPOON,SUM,0,0,0,0,0,8,32,26.566251039505005 +67,,SUM,0,0,0,0,0,8,41,55.90114402770996 +67,, +68,, +68,BOWL,SUM,0,0,0,0,0,4,5,17.156047821044922 +68,CUP,SUM,0,0,0,0,16,2,17,40.60695004463196 +68,SPOON,SUM,0,0,0,0,0,0,5,19.6299729347229 +68,,SUM,0,0,0,0,16,6,27,77.39297080039978 +68,, +69,, +69,BOWL,SUM,0,0,0,0,0,0,1,15.722517013549805 +69,CUP,SUM,0,0,0,0,0,1,8,14.97144103050232 +69,SPOON,SUM,0,0,0,0,0,0,1,19.38455605506897 +69,,SUM,0,0,0,0,0,1,10,50.078514099121094 +69,, +70,, +70,BOWL,SUM,0,0,0,0,8,3,34,45.04253697395325 +70,CUP,SUM,0,0,0,0,48,3,4,96.3755989074707 +70,SPOON,SUM,0,0,0,0,0,1,1,20.96127700805664 +70,,SUM,0,0,0,0,56,7,39,162.3794128894806 +70,, +71,, +71,BOWL,SUM,0,0,0,0,8,1,2,30.286651134490967 +71,CUP,SUM,0,0,0,0,0,0,23,19.809657096862793 +71,SPOON,SUM,0,0,0,0,0,3,20,25.906453847885132 +71,,SUM,0,0,0,0,8,4,45,76.00276207923889 +71,, +72,, +72,BOWL,SUM,0,0,0,0,0,9,8,18.753429889678955 +72,CUP,SUM,0,0,0,0,0,0,3,16.55836319923401 +72,SPOON,SUM,0,0,0,0,0,0,4,21.050112009048462 +72,,SUM,0,0,0,0,0,9,15,56.361905097961426 +72,, +73,, +73,BOWL,SUM,0,0,0,0,0,1,4,18.710783004760742 +73,CUP,SUM,0,0,0,0,8,1,5,32.107779026031494 +73,SPOON,SUM,0,0,0,0,0,4,14,24.72735095024109 +73,,SUM,0,0,0,0,8,6,23,75.54591298103333 +73,, +74,, +74,BOWL,SUM,0,0,0,0,0,1,9,21.384639978408813 +74,CUP,SUM,0,0,0,0,0,3,18,21.04399585723877 +74,SPOON,SUM,0,0,0,0,16,11,81,67.34350681304932 +74,,SUM,0,0,0,0,16,15,108,109.7721426486969 +74,, +75,, +75,BOWL,SUM,0,0,0,0,0,1,1,19.803544998168945 +75,CUP,SUM,0,0,0,0,0,12,12,23.10753607749939 +75,SPOON,SUM,0,0,0,0,0,1,1,22.766600847244263 +75,,SUM,0,0,0,0,0,14,14,65.6776819229126 +75,, +76,, +76,BOWL,SUM,0,0,0,0,0,0,3,19.689048051834106 +76,CUP,SUM,0,0,0,0,0,0,9,18.0261709690094 +76,SPOON,SUM,0,0,0,0,8,2,24,45.245166063308716 +76,,SUM,0,0,0,0,8,2,36,82.96038508415222 +76,, +77,, +77,BOWL,SUM,0,0,0,0,8,3,32,44.15650296211243 +77,CUP,SUM,0,0,0,0,0,11,130,49.6575391292572 +77,SPOON,SUM,0,0,0,0,0,0,1,23.591279983520508 +77,,SUM,0,0,0,0,8,14,163,117.40532207489014 +77,, +78,, +78,BOWL,SUM,0,0,0,0,0,0,3,21.63160800933838 +78,CUP,SUM,0,0,0,0,0,1,35,23.42210292816162 +78,SPOON,SUM,0,0,0,0,0,0,1,24.503586053848267 +78,,SUM,0,0,0,0,0,1,39,69.55729699134827 +78,, +79,, +79,BOWL,SUM,0,0,0,0,0,4,17,25.353588104248047 +79,CUP,SUM,0,0,0,0,0,0,9,21.17424488067627 +79,SPOON,SUM,0,0,0,0,0,1,14,27.04420804977417 +79,,SUM,0,0,0,0,0,5,40,73.57204103469849 +79,, +80,, +80,BOWL,SUM,0,0,0,0,0,11,48,34.152053117752075 +80,CUP,SUM,0,0,0,0,8,0,5,38.54307198524475 +80,SPOON,SUM,0,0,0,0,8,6,23,50.80345392227173 +80,,SUM,0,0,0,0,16,17,76,123.49857902526855 +80,, +81,, +81,BOWL,SUM,0,0,0,0,0,0,14,24.944035053253174 +81,CUP,SUM,0,0,0,0,0,2,6,22.62965703010559 +81,SPOON,SUM,0,0,0,0,8,5,28,53.3036150932312 +81,,SUM,0,0,0,0,8,7,48,100.87730717658997 +81,, +82,, +82,BOWL,SUM,0,0,0,0,0,2,4,23.01076102256775 +82,CUP,SUM,0,0,0,0,0,0,7,22.0569429397583 +82,SPOON,SUM,0,0,0,0,0,0,4,26.545329093933105 +82,,SUM,0,0,0,0,0,2,15,71.61303305625916 +82,, +83,, +83,BOWL,SUM,1,0,1,0,8,16,204,0.0 +83,CUP,SUM,1,0,1,0,0,24,51,0.0 +83,SPOON,SUM,0,0,0,0,0,1,6,30.773342847824097 +83,,SUM,2,0,2,0,8,41,261,30.773342847824097 +83,, +84,, +84,BOWL,SUM,0,0,0,0,0,3,24,27.948878049850464 +84,CUP,SUM,0,0,0,0,0,3,10,25.068488836288452 +84,SPOON,SUM,0,0,0,0,0,1,12,30.626184225082397 +84,,SUM,0,0,0,0,0,7,46,83.64355111122131 +84,, +85,, +85,BOWL,SUM,0,0,0,0,0,5,10,28.260425090789795 +85,CUP,SUM,0,0,0,0,0,0,9,23.8317449092865 +85,SPOON,SUM,0,0,0,0,0,0,2,29.55102014541626 +85,,SUM,0,0,0,0,0,5,21,81.64319014549255 +85,, +86,, +86,BOWL,SUM,0,0,0,0,0,0,10,27.73209500312805 +86,CUP,SUM,0,0,0,0,0,1,10,25.82732319831848 +86,SPOON,SUM,1,0,1,0,8,61,204,0.0 +86,,SUM,1,0,1,0,8,62,224,53.55941820144653 +86,, +87,, +87,BOWL,SUM,0,0,0,0,0,2,20,31.206475973129272 +87,CUP,SUM,0,0,0,0,6,1,21,29.47005581855774 +87,SPOON,SUM,0,0,0,0,0,21,52,40.739145040512085 +87,,SUM,0,0,0,0,6,24,93,101.4156768321991 +87,, +88,, +88,BOWL,SUM,0,0,0,0,0,3,19,33.0957670211792 +88,CUP,SUM,0,0,0,0,0,1,4,24.39895796775818 +88,SPOON,SUM,0,0,0,0,0,0,0,30.506335973739624 +88,,SUM,0,0,0,0,0,4,23,88.001060962677 +88,, +89,, +89,BOWL,SUM,0,0,0,0,8,1,9,49.990017890930176 +89,CUP,SUM,0,0,0,0,0,0,6,24.002909898757935 +89,SPOON,SUM,0,0,0,0,0,4,0,29.419127941131592 +89,,SUM,0,0,0,0,8,5,15,103.4120557308197 +89,, +90,, +90,BOWL,SUM,0,0,0,0,0,2,19,33.06211185455322 +90,CUP,SUM,0,0,0,0,0,4,17,28.42617678642273 +90,SPOON,SUM,0,0,0,0,0,2,0,29.618002891540527 +90,,SUM,0,0,0,0,0,8,36,91.10629153251648 +90,, +91,, +91,BOWL,SUM,0,0,0,0,0,1,1,25.663330078125 +91,CUP,SUM,0,0,0,0,0,1,27,34.9258451461792 +91,SPOON,SUM,0,0,0,0,0,1,6,32.08036494255066 +91,,SUM,0,0,0,0,0,3,34,92.66954016685486 +91,, +92,, +92,BOWL,SUM,0,0,0,0,0,1,8,27.704323053359985 +92,CUP,SUM,0,0,0,0,8,2,21,56.95499396324158 +92,SPOON,SUM,0,0,0,0,8,2,4,53.45513105392456 +92,,SUM,0,0,0,0,16,5,33,138.11444807052612 +92,, +93,, +93,BOWL,SUM,0,0,0,0,0,0,13,29.481024980545044 +93,CUP,SUM,0,0,0,0,0,1,5,25.398113012313843 +93,SPOON,SUM,0,0,0,0,8,2,14,58.326716899871826 +93,,SUM,0,0,0,0,8,3,32,113.20585489273071 +93,, +94,, +94,BOWL,SUM,0,0,0,0,0,1,5,26.875535011291504 +94,CUP,SUM,1,0,1,0,0,39,357,0.0 +94,SPOON,SUM,0,0,0,0,2,3,16,34.51984095573425 +94,,SUM,1,0,1,0,2,43,378,61.39537596702576 +94,, +95,, +95,BOWL,SUM,0,0,0,0,0,3,19,32.01110911369324 +95,CUP,SUM,1,0,1,0,0,23,51,0.0 +95,SPOON,SUM,0,0,0,0,8,0,0,54.63603901863098 +95,,SUM,1,0,1,0,8,26,70,86.64714813232422 +95,, +96,, +96,BOWL,SUM,0,0,0,0,0,3,45,39.32174110412598 +96,CUP,SUM,1,0,1,0,8,64,51,0.0 +96,SPOON,SUM,0,0,0,0,8,4,12,19.99161195755005 +96,,SUM,1,0,1,0,16,71,108,59.313353061676025 +96,, +97,, +97,BOWL,SUM,0,0,0,0,0,0,0,25.710938930511475 +97,CUP,SUM,0,0,0,0,0,2,4,25.750849962234497 +97,SPOON,SUM,0,0,0,0,0,2,16,33.67877006530762 +97,,SUM,0,0,0,0,0,4,20,85.14055895805359 +97,, +98,, +98,BOWL,SUM,0,0,0,0,0,9,30,33.88756799697876 +98,CUP,SUM,0,0,0,0,0,0,2,24.371878147125244 +98,SPOON,SUM,0,0,0,0,8,8,17,59.70134711265564 +98,,SUM,0,0,0,0,8,17,49,117.96079325675964 +98,, +99,, +99,BOWL,SUM,0,0,0,0,0,1,31,32.74997591972351 +99,CUP,SUM,0,0,0,0,0,2,6,26.52825689315796 +99,SPOON,SUM,1,0,1,0,20,46,204,0.0 +99,,SUM,1,0,1,0,20,49,241,59.27823281288147 +99,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/Pr2_VR_sim__VR_PR2_orig_kitchen_var_data_offset_22.csv b/cram_knowrob/cram_knowrob_vr/experiments/Pr2_VR_sim__VR_PR2_orig_kitchen_var_data_offset_22.csv new file mode 100644 index 0000000000..6a5fa1d0e1 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/Pr2_VR_sim__VR_PR2_orig_kitchen_var_data_offset_22.csv @@ -0,0 +1,603 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,0,4,4,17.38674306869507 +0,CUP,SUM,1,0,0,1,0,336,70,0.0 +0,SPOON,SUM,0,0,0,0,0,2,0,14.158383131027222 +0,,SUM,1,0,0,1,0,342,74,31.54512619972229 +0,, +1,, +1,BOWL,SUM,0,0,0,0,0,44,6,15.820966005325317 +1,CUP,SUM,0,0,0,0,6,26,5,16.324048042297363 +1,SPOON,SUM,0,0,0,0,0,358,1,37.488423109054565 +1,,SUM,0,0,0,0,6,428,12,69.63343715667725 +1,, +2,, +2,BOWL,SUM,0,0,0,0,2,318,16,38.21247601509094 +2,CUP,SUM,0,0,0,0,0,4,2,11.197307825088501 +2,SPOON,SUM,0,0,0,0,30,470,0,56.631958961486816 +2,,SUM,0,0,0,0,32,792,18,106.04174280166626 +2,, +3,, +3,BOWL,SUM,0,0,0,0,136,140,11,84.6933240890503 +3,CUP,SUM,0,0,0,0,0,95,25,40.52929711341858 +3,SPOON,SUM,0,0,0,0,0,230,10,33.19463300704956 +3,,SUM,0,0,0,0,136,465,46,158.41725420951843 +3,, +4,, +4,BOWL,SUM,0,0,0,0,0,19,1,13.272509813308716 +4,CUP,SUM,0,0,0,0,0,6,1,9.672878980636597 +4,SPOON,SUM,0,0,0,0,0,95,1,19.15848994255066 +4,,SUM,0,0,0,0,0,120,3,42.10387873649597 +4,, +5,, +5,BOWL,SUM,0,0,0,0,2,10,0,11.854227781295776 +5,CUP,SUM,0,0,0,0,0,77,26,42.77812099456787 +5,SPOON,SUM,0,0,0,0,0,60,11,25.41764998435974 +5,,SUM,0,0,0,0,2,147,37,80.04999876022339 +5,, +6,, +6,BOWL,SUM,0,0,0,0,0,7,2,11.380239009857178 +6,CUP,SUM,0,0,0,0,0,25,13,13.7520170211792 +6,SPOON,SUM,0,0,0,0,2,53,2,20.646291971206665 +6,,SUM,0,0,0,0,2,85,17,45.77854800224304 +6,, +7,, +7,BOWL,SUM,0,0,0,0,0,43,12,20.595612049102783 +7,CUP,SUM,0,0,0,0,0,42,5,15.395230054855347 +7,SPOON,SUM,0,0,0,0,0,255,1,31.796453952789307 +7,,SUM,0,0,0,0,0,340,18,67.78729605674744 +7,, +8,, +8,BOWL,SUM,0,0,0,0,0,15,1,13.313484191894531 +8,CUP,SUM,0,0,0,0,2,45,7,14.536288976669312 +8,SPOON,SUM,0,0,0,0,0,50,0,16.836424112319946 +8,,SUM,0,0,0,0,2,110,8,44.68619728088379 +8,, +9,, +9,BOWL,SUM,0,0,0,0,2,12,4,13.97064995765686 +9,CUP,SUM,0,0,0,0,0,36,4,13.520473957061768 +9,SPOON,SUM,0,0,0,0,0,261,3,31.707485914230347 +9,,SUM,0,0,0,0,2,309,11,59.198609828948975 +9,, +10,, +10,BOWL,SUM,0,0,0,0,56,710,16,86.75786304473877 +10,CUP,SUM,0,0,0,0,0,11,5,9.974384069442749 +10,SPOON,SUM,0,0,0,0,0,5,0,14.488665103912354 +10,,SUM,0,0,0,0,56,726,21,111.22091221809387 +10,, +11,, +11,BOWL,SUM,0,0,0,0,0,80,27,34.93830895423889 +11,CUP,SUM,0,0,0,0,0,11,2,9.749168872833252 +11,SPOON,SUM,0,0,0,0,0,3,6,19.567821979522705 +11,,SUM,0,0,0,0,0,94,35,64.25529980659485 +11,, +12,, +12,BOWL,SUM,1,0,1,0,0,457,98,0.0 +12,CUP,SUM,1,0,0,1,0,379,56,0.0 +12,SPOON,SUM,0,0,0,0,0,115,4,22.5176260471344 +12,,SUM,2,0,1,1,0,951,158,22.5176260471344 +12,, +13,, +13,BOWL,SUM,0,0,0,0,0,76,18,26.49917197227478 +13,CUP,SUM,1,0,1,0,10,196,112,0.0 +13,SPOON,SUM,0,0,0,0,0,33,4,17.605313062667847 +13,,SUM,1,0,1,0,10,305,134,44.10448503494263 +13,, +14,, +14,BOWL,SUM,0,0,0,0,0,23,0,11.861204147338867 +14,CUP,SUM,0,0,0,0,0,98,28,34.514238119125366 +14,SPOON,SUM,0,0,0,0,0,92,0,19.491858959197998 +14,,SUM,0,0,0,0,0,213,28,65.86730122566223 +14,, +15,, +15,BOWL,SUM,0,0,0,0,0,19,0,11.802428007125854 +15,CUP,SUM,0,0,0,0,0,39,1,11.981474876403809 +15,SPOON,SUM,0,0,0,0,6,39,0,19.100377082824707 +15,,SUM,0,0,0,0,6,97,1,42.88427996635437 +15,, +16,, +16,BOWL,SUM,0,0,0,0,2,20,0,12.98158311843872 +16,CUP,SUM,0,0,0,0,2,186,52,84.85480499267578 +16,SPOON,SUM,0,0,0,0,2,67,0,19.979596853256226 +16,,SUM,0,0,0,0,6,273,52,117.81598496437073 +16,, +17,, +17,BOWL,SUM,0,0,0,0,2,15,6,15.340914011001587 +17,CUP,SUM,0,0,0,0,0,53,17,19.39366316795349 +17,SPOON,SUM,0,0,0,0,2,2,0,15.511380910873413 +17,,SUM,0,0,0,0,4,70,23,50.24595808982849 +17,, +18,, +18,BOWL,SUM,0,0,0,0,24,24,0,23.06280207633972 +18,CUP,SUM,0,0,0,0,0,282,63,88.79449987411499 +18,SPOON,SUM,0,0,0,0,0,14,19,32.017959117889404 +18,,SUM,0,0,0,0,24,320,82,143.87526106834412 +18,, +19,, +19,BOWL,SUM,0,0,0,0,0,4,8,16.704933166503906 +19,CUP,SUM,0,0,0,0,4,22,0,11.471373081207275 +19,SPOON,SUM,0,0,0,0,2,14,0,16.613867044448853 +19,,SUM,0,0,0,0,6,40,8,44.790173292160034 +19,, +20,, +20,BOWL,SUM,1,0,1,0,82,758,90,0.0 +20,CUP,SUM,1,0,1,0,0,143,70,0.0 +20,SPOON,SUM,0,0,0,0,0,98,0,21.09627389907837 +20,,SUM,2,0,2,0,82,999,160,21.09627389907837 +20,, +21,, +21,BOWL,SUM,0,0,0,0,0,45,2,14.059705972671509 +21,CUP,SUM,0,0,0,0,2,142,29,54.852001905441284 +21,SPOON,SUM,0,0,0,0,0,38,0,17.346137046813965 +21,,SUM,0,0,0,0,2,225,31,86.25784492492676 +21,, +22,, +22,BOWL,SUM,0,0,0,0,0,49,16,24.793577194213867 +22,CUP,SUM,0,0,0,0,0,6,2,10.184190034866333 +22,SPOON,SUM,0,0,0,0,0,691,12,66.92617583274841 +22,,SUM,0,0,0,0,0,746,30,101.90394306182861 +22,, +23,, +23,BOWL,SUM,0,0,0,0,4,27,8,19.05445098876953 +23,CUP,SUM,0,0,0,0,0,160,31,57.652284145355225 +23,SPOON,SUM,0,0,0,0,22,98,2,31.120989084243774 +23,,SUM,0,0,0,0,26,285,41,107.82772421836853 +23,, +24,, +24,BOWL,SUM,0,0,0,0,0,19,0,11.895342111587524 +24,CUP,SUM,0,0,0,0,0,5,2,9.706305027008057 +24,SPOON,SUM,0,0,0,0,0,1,3,16.64503002166748 +24,,SUM,0,0,0,0,0,25,5,38.24667716026306 +24,, +25,, +25,BOWL,SUM,0,0,0,0,0,18,0,11.651329040527344 +25,CUP,SUM,0,0,0,0,0,34,6,13.819875001907349 +25,SPOON,SUM,0,0,0,0,0,23,0,15.71885895729065 +25,,SUM,0,0,0,0,0,75,6,41.19006299972534 +25,, +26,, +26,BOWL,SUM,0,0,0,0,2,35,2,13.419137001037598 +26,CUP,SUM,0,0,0,0,0,0,3,10.03205394744873 +26,SPOON,SUM,0,0,0,0,0,22,1,16.649123907089233 +26,,SUM,0,0,0,0,2,57,6,40.10031485557556 +26,, +27,, +27,BOWL,SUM,0,0,0,0,0,91,0,15.825905084609985 +27,CUP,SUM,0,0,0,0,0,19,2,12.083311080932617 +27,SPOON,SUM,0,0,0,0,0,37,0,17.37863302230835 +27,,SUM,0,0,0,0,0,147,2,45.28784918785095 +27,, +28,, +28,BOWL,SUM,0,0,0,0,0,25,0,12.103953123092651 +28,CUP,SUM,0,0,0,0,0,14,18,14.451349973678589 +28,SPOON,SUM,0,0,0,0,2,362,0,37.68951487541199 +28,,SUM,0,0,0,0,2,401,18,64.24481797218323 +28,, +29,, +29,BOWL,SUM,0,0,0,0,2,37,4,14.978721141815186 +29,CUP,SUM,1,0,0,1,0,284,89,0.0 +29,SPOON,SUM,0,0,0,0,0,19,4,16.99510097503662 +29,,SUM,1,0,0,1,2,340,97,31.973822116851807 +29,, +30,, +30,BOWL,SUM,0,0,0,0,0,4,0,11.686330080032349 +30,CUP,SUM,0,0,0,0,0,10,2,10.009263038635254 +30,SPOON,SUM,0,0,0,0,0,81,5,22.782968997955322 +30,,SUM,0,0,0,0,0,95,7,44.478562116622925 +30,, +31,, +31,BOWL,SUM,0,0,0,0,6,7,0,13.974137783050537 +31,CUP,SUM,0,0,0,0,0,88,22,35.31103205680847 +31,SPOON,SUM,0,0,0,0,0,95,0,21.127153158187866 +31,,SUM,0,0,0,0,6,190,22,70.41232299804688 +31,, +32,, +32,BOWL,SUM,0,0,0,0,2,22,1,14.771456956863403 +32,CUP,SUM,1,0,1,0,0,208,112,0.0 +32,SPOON,SUM,0,0,0,0,0,45,0,18.225878953933716 +32,,SUM,1,0,1,0,2,275,113,32.99733591079712 +32,, +33,, +33,BOWL,SUM,0,0,0,0,0,12,1,13.478455066680908 +33,CUP,SUM,0,0,0,0,2,110,60,69.3212149143219 +33,SPOON,SUM,0,0,0,0,0,106,5,29.214197158813477 +33,,SUM,0,0,0,0,2,228,66,112.01386713981628 +33,, +34,, +34,BOWL,SUM,0,0,0,0,0,399,36,53.698949098587036 +34,CUP,SUM,0,0,0,0,2,230,44,72.55121397972107 +34,SPOON,SUM,0,0,0,0,0,79,0,20.014590978622437 +34,,SUM,0,0,0,0,2,708,80,146.26475405693054 +34,, +35,, +35,BOWL,SUM,0,0,0,0,0,60,16,24.811307907104492 +35,CUP,SUM,0,0,0,0,0,20,9,10.866365909576416 +35,SPOON,SUM,0,0,0,0,0,99,6,23.278811931610107 +35,,SUM,0,0,0,0,0,179,31,58.956485748291016 +35,, +36,, +36,BOWL,SUM,0,0,0,0,0,5,0,12.774794816970825 +36,CUP,SUM,0,0,0,0,0,68,17,26.796857833862305 +36,SPOON,SUM,0,0,0,0,0,4,12,29.017534971237183 +36,,SUM,0,0,0,0,0,77,29,68.58918762207031 +36,, +37,, +37,BOWL,SUM,0,0,0,0,2,15,0,12.767246007919312 +37,CUP,SUM,0,0,0,0,0,3,6,9.979308843612671 +37,SPOON,SUM,1,0,1,0,2,1241,44,0.0 +37,,SUM,1,0,1,0,4,1259,50,22.746554851531982 +37,, +38,, +38,BOWL,SUM,0,0,0,0,0,15,2,11.984149932861328 +38,CUP,SUM,1,0,1,0,0,564,101,0.0 +38,SPOON,SUM,0,0,0,0,0,155,0,24.09766387939453 +38,,SUM,1,0,1,0,0,734,103,36.08181381225586 +38,, +39,, +39,BOWL,SUM,0,0,0,0,0,71,4,16.21770405769348 +39,CUP,SUM,0,0,0,0,0,11,6,10.551981925964355 +39,SPOON,SUM,0,0,0,0,0,115,0,21.79610800743103 +39,,SUM,0,0,0,0,0,197,10,48.56579399108887 +39,, +40,, +40,BOWL,SUM,0,0,0,0,0,52,9,20.864085912704468 +40,CUP,SUM,1,0,0,1,0,409,72,0.0 +40,SPOON,SUM,0,0,0,0,2,361,4,44.54509997367859 +40,,SUM,1,0,0,1,2,822,85,65.40918588638306 +40,, +41,, +41,BOWL,SUM,0,0,0,0,0,20,4,14.121052980422974 +41,CUP,SUM,0,0,0,0,4,30,12,18.79146099090576 +41,SPOON,SUM,0,0,0,0,0,262,1,33.14855980873108 +41,,SUM,0,0,0,0,4,312,17,66.06107378005981 +41,, +42,, +42,BOWL,SUM,0,0,0,0,0,11,0,11.774681091308594 +42,CUP,SUM,0,0,0,0,0,7,2,9.787084817886353 +42,SPOON,SUM,0,0,0,0,0,165,2,27.280728101730347 +42,,SUM,0,0,0,0,0,183,4,48.84249401092529 +42,, +43,, +43,BOWL,SUM,0,0,0,0,0,9,0,11.613464832305908 +43,CUP,SUM,0,0,0,0,0,14,1,10.241597175598145 +43,SPOON,SUM,0,0,0,0,0,9,3,16.639904975891113 +43,,SUM,0,0,0,0,0,32,4,38.494966983795166 +43,, +44,, +44,BOWL,SUM,0,0,0,0,0,173,12,28.22457003593445 +44,CUP,SUM,1,0,0,1,0,283,84,0.0 +44,SPOON,SUM,0,0,0,0,0,73,19,34.27674102783203 +44,,SUM,1,0,0,1,0,529,115,62.50131106376648 +44,, +45,, +45,BOWL,SUM,0,0,0,0,0,43,10,19.343662977218628 +45,CUP,SUM,0,0,0,0,0,6,4,9.900611877441406 +45,SPOON,SUM,0,0,0,0,0,114,0,21.655517101287842 +45,,SUM,0,0,0,0,0,163,14,50.899791955947876 +45,, +46,, +46,BOWL,SUM,0,0,0,0,0,22,6,15.674717903137207 +46,CUP,SUM,1,0,0,1,6,261,77,0.0 +46,SPOON,SUM,0,0,0,0,0,821,0,67.37232303619385 +46,,SUM,1,0,0,1,6,1104,83,83.04704093933105 +46,, +47,, +47,BOWL,SUM,0,0,0,0,0,30,2,13.080656051635742 +47,CUP,SUM,0,0,0,0,0,15,2,10.850200891494751 +47,SPOON,SUM,0,0,0,0,0,99,4,27.336440086364746 +47,,SUM,0,0,0,0,0,144,8,51.26729702949524 +47,, +48,, +48,BOWL,SUM,0,0,0,0,0,37,1,12.508074045181274 +48,CUP,SUM,0,0,0,0,0,39,12,15.159426927566528 +48,SPOON,SUM,0,0,0,0,0,44,8,21.767677783966064 +48,,SUM,0,0,0,0,0,120,21,49.43517875671387 +48,, +49,, +49,BOWL,SUM,0,0,0,0,2,25,14,23.225387811660767 +49,CUP,SUM,0,0,0,0,0,3,6,10.077811002731323 +49,SPOON,SUM,0,0,0,0,0,702,21,72.64942598342896 +49,,SUM,0,0,0,0,2,730,41,105.95262479782104 +49,, +50,, +50,BOWL,SUM,0,0,0,0,0,19,0,12.473503828048706 +50,CUP,SUM,0,0,0,0,8,7,0,14.601938009262085 +50,SPOON,SUM,0,0,0,0,0,12,11,25.100987911224365 +50,,SUM,0,0,0,0,8,38,11,52.176429748535156 +50,, +51,, +51,BOWL,SUM,0,0,0,0,0,36,0,13.868879079818726 +51,CUP,SUM,0,0,0,0,2,41,20,25.1647789478302 +51,SPOON,SUM,1,0,1,0,0,1098,54,0.0 +51,,SUM,1,0,1,0,2,1175,74,39.033658027648926 +51,, +52,, +52,BOWL,SUM,0,0,0,0,6,16,12,22.55021905899048 +52,CUP,SUM,0,0,0,0,0,87,19,33.13393187522888 +52,SPOON,SUM,1,0,1,0,0,1352,34,0.0 +52,,SUM,1,0,1,0,6,1455,65,55.68415093421936 +52,, +53,, +53,BOWL,SUM,0,0,0,0,2,24,0,13.518126010894775 +53,CUP,SUM,0,0,0,0,2,160,29,47.23987317085266 +53,SPOON,SUM,0,0,0,0,6,2,4,19.085577964782715 +53,,SUM,0,0,0,0,10,186,33,79.84357714653015 +53,, +54,, +54,BOWL,SUM,0,0,0,0,0,7,1,14.0173020362854 +54,CUP,SUM,0,0,0,0,2,26,2,11.214240074157715 +54,SPOON,SUM,1,0,1,0,2,1378,87,0.0 +54,,SUM,1,0,1,0,4,1411,90,25.231542110443115 +54,, +55,, +55,BOWL,SUM,0,0,0,0,58,48,2,39.83039903640747 +55,CUP,SUM,0,0,0,0,16,48,16,27.675708055496216 +55,SPOON,SUM,0,0,0,0,0,62,2,22.49181604385376 +55,,SUM,0,0,0,0,74,158,20,89.99792313575745 +55,, +56,, +56,BOWL,SUM,0,0,0,0,0,27,2,12.510334014892578 +56,CUP,SUM,0,0,0,0,0,9,7,10.75282096862793 +56,SPOON,SUM,0,0,0,0,18,504,1,58.29476308822632 +56,,SUM,0,0,0,0,18,540,10,81.55791807174683 +56,, +57,, +57,BOWL,SUM,0,0,0,0,2,3,0,12.155151844024658 +57,CUP,SUM,0,0,0,0,0,14,2,10.41283106803894 +57,SPOON,SUM,0,0,0,0,0,592,3,57.227410078048706 +57,,SUM,0,0,0,0,2,609,5,79.7953929901123 +57,, +58,, +58,BOWL,SUM,0,0,0,0,0,18,0,11.875622987747192 +58,CUP,SUM,0,0,0,0,0,206,49,77.31166696548462 +58,SPOON,SUM,0,0,0,0,0,158,1,27.641334056854248 +58,,SUM,0,0,0,0,0,382,50,116.82862401008606 +58,, +59,, +59,BOWL,SUM,0,0,0,0,0,21,0,12.605969190597534 +59,CUP,SUM,1,0,0,1,0,306,54,0.0 +59,SPOON,SUM,0,0,0,0,2,95,1,22.58433508872986 +59,,SUM,1,0,0,1,2,422,55,35.19030427932739 +59,, +60,, +60,BOWL,SUM,0,0,0,0,0,45,0,14.203117847442627 +60,CUP,SUM,0,0,0,0,2,36,3,13.188416004180908 +60,SPOON,SUM,0,0,0,0,0,32,2,21.207638025283813 +60,,SUM,0,0,0,0,2,113,5,48.59917187690735 +60,, +61,, +61,BOWL,SUM,1,0,1,0,8,1222,36,0.0 +61,CUP,SUM,1,0,0,1,0,267,78,0.0 +61,SPOON,SUM,0,0,0,0,0,0,0,15.800107955932617 +61,,SUM,2,0,1,1,8,1489,114,15.800107955932617 +61,, +62,, +62,BOWL,SUM,0,0,0,0,0,7,2,12.735338926315308 +62,CUP,SUM,0,0,0,0,6,12,2,12.747550964355469 +62,SPOON,SUM,0,0,0,0,4,127,8,31.792898893356323 +62,,SUM,0,0,0,0,10,146,12,57.2757887840271 +62,, +63,, +63,BOWL,SUM,0,0,0,0,40,46,18,45.77597093582153 +63,CUP,SUM,1,0,1,0,8,440,78,0.0 +63,SPOON,SUM,0,0,0,0,0,34,5,20.749449014663696 +63,,SUM,1,0,1,0,48,520,101,66.52541995048523 +63,, +64,, +64,BOWL,SUM,0,0,0,0,0,14,6,15.514228820800781 +64,CUP,SUM,1,0,1,0,6,201,110,0.0 +64,SPOON,SUM,0,0,0,0,0,291,0,33.98711705207825 +64,,SUM,1,0,1,0,6,506,116,49.50134587287903 +64,, +65,, +65,BOWL,SUM,0,0,0,0,0,1,0,11.537220001220703 +65,CUP,SUM,0,0,0,0,0,2,2,10.131298065185547 +65,SPOON,SUM,0,0,0,0,16,96,0,28.320728063583374 +65,,SUM,0,0,0,0,16,99,2,49.989246129989624 +65,, +66,, +66,BOWL,SUM,0,0,0,0,8,116,10,25.670140027999878 +66,CUP,SUM,0,0,0,0,0,40,5,15.879999160766602 +66,SPOON,SUM,0,0,0,0,0,4,6,18.688222885131836 +66,,SUM,0,0,0,0,8,160,21,60.238362073898315 +66,, +67,, +67,BOWL,SUM,0,0,0,0,2,52,0,14.953797101974487 +67,CUP,SUM,0,0,0,0,0,74,24,36.98026919364929 +67,SPOON,SUM,0,0,0,0,0,4,5,20.152978897094727 +67,,SUM,0,0,0,0,2,130,29,72.0870451927185 +67,, +68,, +68,BOWL,SUM,0,0,0,0,0,13,0,11.877889156341553 +68,CUP,SUM,0,0,0,0,0,2,1,9.669941902160645 +68,SPOON,SUM,0,0,0,0,0,191,0,26.35793900489807 +68,,SUM,0,0,0,0,0,206,1,47.90577006340027 +68,, +69,, +69,BOWL,SUM,0,0,0,0,24,39,6,27.577190160751343 +69,CUP,SUM,0,0,0,0,0,15,2,10.448669910430908 +69,SPOON,SUM,0,0,0,0,0,21,0,15.932729959487915 +69,,SUM,0,0,0,0,24,75,8,53.958590030670166 +69,, +70,, +70,BOWL,SUM,0,0,0,0,56,44,0,39.468672037124634 +70,CUP,SUM,1,0,0,1,0,354,58,0.0 +70,SPOON,SUM,0,0,0,0,0,1,0,15.693617820739746 +70,,SUM,1,0,0,1,56,399,58,55.16228985786438 +70,, +71,, +71,BOWL,SUM,0,0,0,0,0,73,6,17.444552898406982 +71,CUP,SUM,0,0,0,0,8,36,14,20.914746046066284 +71,SPOON,SUM,0,0,0,0,0,120,9,29.361998081207275 +71,,SUM,0,0,0,0,8,229,29,67.72129702568054 +71,, +72,, +72,BOWL,SUM,0,0,0,0,0,119,20,31.700427055358887 +72,CUP,SUM,0,0,0,0,2,18,6,11.379082918167114 +72,SPOON,SUM,0,0,0,0,6,1,0,16.88980507850647 +72,,SUM,0,0,0,0,8,138,26,59.96931505203247 +72,, +73,, +73,BOWL,SUM,0,0,0,0,0,16,0,12.14620304107666 +73,CUP,SUM,0,0,0,0,0,7,2,10.126204013824463 +73,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +73,,SUM,1,0,1,0,0,1604,2,22.272407054901123 +73,, +74,, +74,BOWL,SUM,0,0,0,0,0,8,1,13.581148862838745 +74,CUP,SUM,0,0,0,0,2,47,8,15.094358205795288 +74,SPOON,SUM,0,0,0,0,0,78,0,20.048393964767456 +74,,SUM,0,0,0,0,2,133,9,48.72390103340149 +74,, +75,, +75,BOWL,SUM,0,0,0,0,0,14,4,14.664841890335083 +75,CUP,SUM,0,0,0,0,0,48,11,20.113159894943237 +75,SPOON,SUM,0,0,0,0,0,3,0,15.394704103469849 +75,,SUM,0,0,0,0,0,65,15,50.17270588874817 +75,, +76,, +76,BOWL,SUM,0,0,0,0,0,21,0,12.546725988388062 +76,CUP,SUM,0,0,0,0,0,44,12,24.49989104270935 +76,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +76,,SUM,1,0,1,0,0,1646,12,37.04661703109741 +76,, +77,, +77,BOWL,SUM,1,0,1,0,0,560,96,0.0 +77,CUP,SUM,0,0,0,0,0,23,6,11.070840835571289 +77,SPOON,SUM,0,0,0,0,0,12,0,15.531301975250244 +77,,SUM,1,0,1,0,0,595,102,26.602142810821533 +77,, +78,, +78,BOWL,SUM,0,0,0,0,0,55,0,14.31379508972168 +78,CUP,SUM,0,0,0,0,0,6,0,10.400300025939941 +78,SPOON,SUM,0,0,0,0,0,26,5,19.083147048950195 +78,,SUM,0,0,0,0,0,87,5,43.797242164611816 +78,, +79,, +79,BOWL,SUM,0,0,0,0,2,117,26,38.09994387626648 +79,CUP,SUM,0,0,0,0,0,41,10,13.656544923782349 +79,SPOON,SUM,0,0,0,0,0,9,6,19.111271858215332 +79,,SUM,0,0,0,0,2,167,42,70.86776065826416 +79,, +80,, +80,BOWL,SUM,0,0,0,0,0,24,8,17.989253997802734 +80,CUP,SUM,0,0,0,0,0,42,2,11.776211023330688 +80,SPOON,SUM,0,0,0,0,0,40,2,20.904775142669678 +80,,SUM,0,0,0,0,0,106,12,50.6702401638031 +80,, +81,, +81,BOWL,SUM,0,0,0,0,6,9,0,14.120737075805664 +81,CUP,SUM,0,0,0,0,58,105,16,51.303086042404175 +81,SPOON,SUM,0,0,0,0,26,5,0,28.01622200012207 +81,,SUM,0,0,0,0,90,119,16,93.44004511833191 +81,, +82,, +82,BOWL,SUM,0,0,0,0,0,22,1,13.982795000076294 +82,CUP,SUM,0,0,0,0,4,13,4,11.723069190979004 +82,SPOON,SUM,0,0,0,0,2,296,3,38.96694803237915 +82,,SUM,0,0,0,0,6,331,8,64.67281222343445 +82,, +83,, +83,BOWL,SUM,0,0,0,0,2,9,2,13.053606033325195 +83,CUP,SUM,0,0,0,0,0,35,2,12.043537855148315 +83,SPOON,SUM,0,0,0,0,0,147,4,26.7385151386261 +83,,SUM,0,0,0,0,2,191,8,51.83565902709961 +83,, +84,, +84,BOWL,SUM,0,0,0,0,0,272,31,46.66932511329651 +84,CUP,SUM,0,0,0,0,0,5,4,13.400423049926758 +84,SPOON,SUM,0,0,0,0,0,47,7,22.81483292579651 +84,,SUM,0,0,0,0,0,324,42,82.88458108901978 +84,, +85,, +85,BOWL,SUM,0,0,0,0,0,6,1,13.810908079147339 +85,CUP,SUM,0,0,0,0,0,52,24,27.527513027191162 +85,SPOON,SUM,0,0,0,0,2,0,0,16.052397966384888 +85,,SUM,0,0,0,0,2,58,25,57.39081907272339 +85,, +86,, +86,BOWL,SUM,0,0,0,0,0,103,5,20.53606605529785 +86,CUP,SUM,1,0,1,0,0,108,111,0.0 +86,SPOON,SUM,0,0,0,0,0,55,4,23.56334090232849 +86,,SUM,1,0,1,0,0,266,120,44.09940695762634 +86,, +87,, +87,BOWL,SUM,0,0,0,0,0,28,8,18.0699679851532 +87,CUP,SUM,0,0,0,0,0,18,4,10.44173002243042 +87,SPOON,SUM,0,0,0,0,0,164,0,25.945157766342163 +87,,SUM,0,0,0,0,0,210,12,54.45685577392578 +87,, +88,, +88,BOWL,SUM,0,0,0,0,0,626,58,85.26969909667969 +88,CUP,SUM,1,0,1,0,0,206,99,0.0 +88,SPOON,SUM,0,0,0,0,4,19,1,19.631336212158203 +88,,SUM,1,0,1,0,4,851,158,104.90103530883789 +88,, +89,, +89,BOWL,SUM,1,0,1,0,2,618,92,0.0 +89,CUP,SUM,0,0,0,0,0,30,8,11.457655906677246 +89,SPOON,SUM,0,0,0,0,10,16,1,21.982760906219482 +89,,SUM,1,0,1,0,12,664,101,33.44041681289673 +89,, +90,, +90,BOWL,SUM,0,0,0,0,2,180,28,40.01838707923889 +90,CUP,SUM,1,0,1,0,0,259,110,0.0 +90,SPOON,SUM,1,0,1,0,30,1592,0,0.0 +90,,SUM,2,0,2,0,32,2031,138,40.01838707923889 +90,, +91,, +91,BOWL,SUM,0,0,0,0,0,23,6,15.89646291732788 +91,CUP,SUM,1,0,1,0,4,224,108,0.0 +91,SPOON,SUM,0,0,0,0,0,4,1,16.622205018997192 +91,,SUM,1,0,1,0,4,251,115,32.51866793632507 +91,, +92,, +92,BOWL,SUM,0,0,0,0,0,59,10,20.597641944885254 +92,CUP,SUM,0,0,0,0,8,15,2,14.607192993164063 +92,SPOON,SUM,0,0,0,0,0,10,6,19.250631093978882 +92,,SUM,0,0,0,0,8,84,18,54.4554660320282 +92,, +93,, +93,BOWL,SUM,1,0,1,0,10,776,86,0.0 +93,CUP,SUM,0,0,0,0,0,153,41,58.912423849105835 +93,SPOON,SUM,0,0,0,0,10,285,6,47.04146599769592 +93,,SUM,1,0,1,0,20,1214,133,105.95388984680176 +93,, +94,, +94,BOWL,SUM,0,0,0,0,0,12,0,12.001936912536621 +94,CUP,SUM,0,0,0,0,6,21,5,12.916265964508057 +94,SPOON,SUM,1,0,1,0,8,687,86,0.0 +94,,SUM,1,0,1,0,14,720,91,24.918202877044678 +94,, +95,, +95,BOWL,SUM,0,0,0,0,0,19,1,14.619529008865356 +95,CUP,SUM,0,0,0,0,0,10,1,12.39228892326355 +95,SPOON,SUM,0,0,0,0,2,46,0,17.273895025253296 +95,,SUM,0,0,0,0,2,75,2,44.2857129573822 +95,, +96,, +96,BOWL,SUM,0,0,0,0,0,261,36,48.63484811782837 +96,CUP,SUM,0,0,0,0,0,54,18,23.738415002822876 +96,SPOON,SUM,0,0,0,0,0,1,4,17.53434419631958 +96,,SUM,0,0,0,0,0,316,58,89.90760731697083 +96,, +97,, +97,BOWL,SUM,0,0,0,0,0,26,0,12.667067050933838 +97,CUP,SUM,0,0,0,0,0,9,2,10.593016862869263 +97,SPOON,SUM,0,0,0,0,2,1,14,31.34060502052307 +97,,SUM,0,0,0,0,2,36,16,54.60068893432617 +97,, +98,, +98,BOWL,SUM,0,0,0,0,0,7,0,12.194375038146973 +98,CUP,SUM,0,0,0,0,0,278,66,102.71326112747192 +98,SPOON,SUM,0,0,0,0,0,153,8,30.04104995727539 +98,,SUM,0,0,0,0,0,438,74,144.9486861228943 +98,, +99,, +99,BOWL,SUM,0,0,0,0,2,1,0,12.725702047348022 +99,CUP,SUM,0,0,0,0,0,31,0,10.700498819351196 +99,SPOON,SUM,0,0,0,0,0,6,6,20.37502884864807 +99,,SUM,0,0,0,0,2,38,6,43.80122971534729 +99,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_BOXY_Orig_kitchen_var_data_offset_30.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_BOXY_Orig_kitchen_var_data_offset_30.csv new file mode 100644 index 0000000000..54a5927fa3 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_BOXY_Orig_kitchen_var_data_offset_30.csv @@ -0,0 +1,228 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,1,0,1,0,8,1830,0,0 +0,CUP,SUM,1,0,0,1,0,1587,0,0 +0,SPOON,SUM,1,0,1,0,0,1791,0,0 +0,,SUM,3,0,2,1,8,5208,0,0 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,0,289,2,42.744343996 +1,CUP,SUM,1,1,0,0,0,1519,0,0 +1,SPOON,SUM,1,0,1,0,0,2856,0,0 +1,,SUM,2,1,1,0,0,4664,2,42.744343996 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,1,0,1,0,0,1611,0,0 +2,CUP,SUM,1,0,1,0,2,1587,0,0 +2,SPOON,SUM,1,0,1,0,0,1581,0,0 +2,,SUM,3,0,3,0,2,4779,0,0 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,1,0,1,0,0,1595,0,0 +3,CUP,SUM,1,0,0,1,2,1617,8,0 +3,SPOON,SUM,1,0,1,0,6,1661,0,0 +3,,SUM,3,0,2,1,8,4873,8,0 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,1,0,1,0,0,1508,22,0 +4,CUP,SUM,1,0,1,0,0,1196,38,0 +4,SPOON,SUM,1,1,0,0,0,1519,0,0 +4,,SUM,3,1,2,0,0,4223,60,0 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,1,1,0,0,0,1519,0,0 +5,CUP,SUM,1,0,1,0,24,1590,0,0 +5,SPOON,SUM,0,0,0,0,0,43,9,28.0870261192 +5,,SUM,2,1,1,0,24,3152,9,28.0870261192 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,1,0,1,0,0,1685,0,0 +6,CUP,SUM,1,0,0,1,0,1586,0,0 +6,SPOON,SUM,1,1,0,0,0,1519,0,0 +6,,SUM,3,1,1,1,0,4790,0,0 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,1,1,0,0,0,1519,0,0 +7,CUP,SUM,1,0,0,1,0,1638,2,0 +7,SPOON,SUM,0,0,0,0,0,155,3,37.8270099163 +7,,SUM,2,1,0,1,0,3312,5,37.8270099163 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,1,0,1,0,6,1950,0,0 +8,CUP,SUM,1,0,1,0,0,1573,13,0 +8,SPOON,SUM,1,0,1,0,0,1596,0,0 +8,,SUM,3,0,3,0,6,5119,13,0 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,1,0,1,0,0,1655,0,0 +9,CUP,SUM,1,0,1,0,0,1359,30,0 +9,SPOON,SUM,1,0,1,0,0,1581,0,0 +9,,SUM,3,0,3,0,0,4595,30,0 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,1,0,1,0,8,1591,0,0 +10,CUP,SUM,1,1,0,0,0,1519,0,0 +10,SPOON,SUM,1,0,1,0,0,1581,0,0 +10,,SUM,3,1,2,0,8,4691,0,0 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,1,0,1,0,2,1593,0,0 +11,CUP,SUM,1,0,1,0,6,1620,0,0 +11,SPOON,SUM,1,0,1,0,0,1595,0,0 +11,,SUM,3,0,3,0,8,4808,0,0 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,1,0,1,0,6,1851,0,0 +12,CUP,SUM,1,0,0,1,0,1696,12,0 +12,SPOON,SUM,1,0,1,0,0,1596,0,0 +12,,SUM,3,0,2,1,6,5143,12,0 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,1,0,1,0,2,1585,0,0 +13,CUP,SUM,1,0,1,0,0,1583,0,0 +13,SPOON,SUM,1,1,0,0,0,1519,0,0 +13,,SUM,3,1,2,0,2,4687,0,0 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,1,0,1,0,2,1482,10,0 +14,CUP,SUM,1,0,0,1,0,1673,7,0 +14,SPOON,SUM,0,0,0,0,10,85,6,35.0460329056 +14,,SUM,2,0,1,1,12,3240,23,35.0460329056 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,2,863,4,101.2259221077 +15,CUP,SUM,1,0,1,0,16,1378,34,0 +15,SPOON,SUM,0,0,0,0,0,36,0,21.7152149677 +15,,SUM,1,0,1,0,18,2277,38,122.9411370754 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,1,1,0,0,0,1519,0,0 +16,CUP,SUM,1,1,0,0,0,1519,0,0 +16,SPOON,SUM,1,0,1,0,0,1583,0,0 +16,,SUM,3,2,1,0,0,4621,0,0 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,1,0,1,0,0,1729,0,0 +17,CUP,SUM,1,0,0,1,0,1707,15,0 +17,SPOON,SUM,0,0,0,0,2,6,0,20.3135428429 +17,,SUM,2,0,1,1,2,3442,15,20.3135428429 +17,,,,,,,,,, +18,, +18,BOWL,SUM,1,0,1,0,8,1830,0,0.0 +18,CUP,SUM,1,0,0,1,0,1587,0,0.0 +18,SPOON,SUM,1,0,1,0,0,1791,0,0.0 +18,,SUM,3,0,2,1,8,5208,0,0.0 +18,, +19,, +19,BOWL,SUM,0,0,0,0,0,289,2,42.44897699356079 +19,CUP,SUM,1,1,0,0,0,1519,0,0.0 +19,SPOON,SUM,1,0,1,0,0,2856,0,0.0 +19,,SUM,2,1,1,0,0,4664,2,42.44897699356079 +19,, +20,, +20,BOWL,SUM,1,0,1,0,0,1611,0,0.0 +20,CUP,SUM,1,0,1,0,2,1587,0,0.0 +20,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +20,,SUM,3,0,3,0,2,4779,0,0.0 +20,, +21,, +21,BOWL,SUM,1,0,1,0,0,1595,0,0.0 +21,CUP,SUM,1,0,0,1,2,1617,8,0.0 +21,SPOON,SUM,1,0,1,0,6,1661,0,0.0 +21,,SUM,3,0,2,1,8,4873,8,0.0 +21,, +22,, +22,BOWL,SUM,1,0,1,0,0,1508,22,0.0 +22,CUP,SUM,1,0,1,0,0,1196,38,0.0 +22,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +22,,SUM,3,1,2,0,0,4223,60,0.0 +22,, +23,, +23,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +23,CUP,SUM,1,0,1,0,24,1590,0,0.0 +23,SPOON,SUM,0,0,0,0,0,43,9,28.091552019119263 +23,,SUM,2,1,1,0,24,3152,9,28.091552019119263 +23,, +24,, +24,BOWL,SUM,1,0,1,0,0,1685,0,0.0 +24,CUP,SUM,1,0,0,1,0,1586,0,0.0 +24,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +24,,SUM,3,1,1,1,0,4790,0,0.0 +24,, +25,, +25,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +25,CUP,SUM,1,0,0,1,0,1638,2,0.0 +25,SPOON,SUM,0,0,0,0,0,155,3,37.28891706466675 +25,,SUM,2,1,0,1,0,3312,5,37.28891706466675 +25,, +26,, +26,BOWL,SUM,1,0,1,0,6,1950,0,0.0 +26,CUP,SUM,1,0,1,0,0,1573,13,0.0 +26,SPOON,SUM,1,0,1,0,0,1596,0,0.0 +26,,SUM,3,0,3,0,6,5119,13,0.0 +26,, +27,, +27,BOWL,SUM,1,0,1,0,0,1655,0,0.0 +27,CUP,SUM,1,0,1,0,0,1359,30,0.0 +27,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +27,,SUM,3,0,3,0,0,4595,30,0.0 +27,, +28,, +28,BOWL,SUM,1,0,1,0,8,1591,0,0.0 +28,CUP,SUM,1,1,0,0,0,1519,0,0.0 +28,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +28,,SUM,3,1,2,0,8,4691,0,0.0 +28,, +29,, +29,BOWL,SUM,1,0,1,0,2,1593,0,0.0 +29,CUP,SUM,1,0,1,0,6,1620,0,0.0 +29,SPOON,SUM,1,0,1,0,0,1595,0,0.0 +29,,SUM,3,0,3,0,8,4808,0,0.0 +29,, +30,, +30,BOWL,SUM,1,0,1,0,6,1851,0,0.0 +30,CUP,SUM,1,0,0,1,0,1696,12,0.0 +30,SPOON,SUM,1,0,1,0,0,1596,0,0.0 +30,,SUM,3,0,2,1,6,5143,12,0.0 +30,, +31,, +31,BOWL,SUM,1,0,1,0,2,1585,0,0.0 +31,CUP,SUM,1,0,1,0,0,1583,0,0.0 +31,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +31,,SUM,3,1,2,0,2,4687,0,0.0 +31,, +32,, +32,BOWL,SUM,1,0,1,0,2,1482,10,0.0 +32,CUP,SUM,1,0,0,1,0,1673,7,0.0 +32,SPOON,SUM,0,0,0,0,10,85,6,34.86566090583801 +32,,SUM,2,0,1,1,12,3240,23,34.86566090583801 +32,, +33,, +33,BOWL,SUM,0,0,0,0,2,863,4,102.65951704978943 +33,CUP,SUM,1,0,1,0,16,1378,34,0.0 +33,SPOON,SUM,0,0,0,0,0,36,0,21.17066192626953 +33,,SUM,1,0,1,0,18,2277,38,123.83017897605896 +33,, +34,, +34,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +34,CUP,SUM,1,1,0,0,0,1519,0,0.0 +34,SPOON,SUM,1,0,1,0,0,1583,0,0.0 +34,,SUM,3,2,1,0,0,4621,0,0.0 +34,, +35,, +35,BOWL,SUM,1,0,1,0,0,1729,0,0.0 +35,CUP,SUM,1,0,0,1,0,1707,15,0.0 +35,SPOON,SUM,0,0,0,0,2,6,0,20.28973913192749 +35,,SUM,2,0,1,1,2,3442,15,20.28973913192749 +35,, +36,, +36,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +36,CUP,SUM,1,0,0,1,0,1774,10,0.0 +36,SPOON,SUM,1,0,1,0,8,1590,0,0.0 +36,,SUM,3,1,1,1,8,4883,10,0.0 +36,, +37,, +37,BOWL,SUM,0,0,0,0,0,142,5,42.090176820755005 +37,CUP,SUM,1,0,0,1,6,1658,4,0.0 diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_BOXY_orig_kitchen_new_var_and_orig_data_offset_70.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_BOXY_orig_kitchen_new_var_and_orig_data_offset_70.csv new file mode 100644 index 0000000000..eef9bf29a8 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_BOXY_orig_kitchen_new_var_and_orig_data_offset_70.csv @@ -0,0 +1,609 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,138,15,75.3049719334 +0,CUP,SUM,0,0,0,0,2,70,32,101.0338499546 +0,SPOON,SUM,0,0,0,0,0,17,5,29.6104519367 +0,,SUM,0,0,0,0,2,225,52,205.9492738247 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,8,15,2,30.0878350735 +1,CUP,SUM,0,0,0,0,0,16,23,53.1738681793 +1,SPOON,SUM,0,0,0,0,0,6,1,27.0789780617 +1,,SUM,0,0,0,0,8,37,26,110.3406813145 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,0,16,0,22.844892025 +2,CUP,SUM,0,0,0,0,0,19,11,41.6243469715 +2,SPOON,SUM,0,0,0,0,0,23,0,22.9717931747 +2,,SUM,0,0,0,0,0,58,11,87.4410321712 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,2,112,8,50.6702320576 +3,CUP,SUM,0,0,0,0,0,36,38,96.9589431286 +3,SPOON,SUM,0,0,0,0,0,76,6,39.0840120316 +3,,SUM,0,0,0,0,2,224,52,186.7131872177 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,5,0,22.2387940884 +4,CUP,SUM,1,0,0,1,6,248,55,0 +4,SPOON,SUM,1,0,0,1,0,121,160,0 +4,,SUM,2,0,0,2,6,374,215,22.2387940884 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,1,0,1,0,8,390,54,0 +5,CUP,SUM,1,0,0,1,0,213,60,0 +5,SPOON,SUM,0,0,0,0,0,5,3,27.2612359524 +5,,SUM,2,0,1,1,8,608,117,27.2612359524 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,0,9,2,22.673058033 +6,CUP,SUM,0,0,0,0,6,31,22,70.6414401531 +6,SPOON,SUM,0,0,0,0,0,18,3,29.1131939888 +6,,SUM,0,0,0,0,6,58,27,122.4276921749 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,6,44,0,29.2684800625 +7,CUP,SUM,0,0,0,0,2,10,22,50.4349210262 +7,SPOON,SUM,0,0,0,0,2,67,3,40.0919339657 +7,,SUM,0,0,0,0,10,121,25,119.7953350544 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,0,264,11,68.3371310234 +8,CUP,SUM,0,0,0,0,0,3,12,31.7061481476 +8,SPOON,SUM,0,0,0,0,2,2,2,24.1988868713 +8,,SUM,0,0,0,0,2,269,25,124.2421660423 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,14,0,22.1489799023 +9,CUP,SUM,0,0,0,0,0,24,8,26.4787039757 +9,SPOON,SUM,1,0,1,0,16,1388,34,0 +9,,SUM,1,0,1,0,16,1426,42,48.6276838779 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,35,4,37.4450759888 +10,CUP,SUM,0,0,0,0,0,14,11,35.7762589455 +10,SPOON,SUM,0,0,0,0,0,106,3,43.3681871891 +10,,SUM,0,0,0,0,0,155,18,116.5895221233 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,8,23,0,29.5855660439 +11,CUP,SUM,0,0,0,0,2,20,11,31.2170681953 +11,SPOON,SUM,0,0,0,0,0,11,0,22.9288828373 +11,,SUM,0,0,0,0,10,54,11,83.7315170765 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,0,85,13,48.7828521729 +12,CUP,SUM,0,0,0,0,0,10,7,49.15802598 +12,SPOON,SUM,0,0,0,0,2,0,7,34.1048510075 +12,,SUM,0,0,0,0,2,95,27,132.0457291603 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,1,0,1,0,12,146,48,0 +13,CUP,SUM,0,0,0,0,2,28,8,26.8728108406 +13,SPOON,SUM,0,0,0,0,0,0,0,22.0772559643 +13,,SUM,1,0,1,0,14,174,56,48.9500668049 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,8,35,10,40.2132132053 +14,CUP,SUM,0,0,0,0,2,34,20,53.6867389679 +14,SPOON,SUM,1,0,1,0,48,14,36,0 +14,,SUM,1,0,1,0,58,83,66,93.8999521732 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,0,24,4,23.7854220867 +15,CUP,SUM,0,0,0,0,0,11,15,36.8389351368 +15,SPOON,SUM,0,0,0,0,6,40,0,31.5841948986 +15,,SUM,0,0,0,0,6,75,19,92.2085521221 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,5,0,21.5564608574 +16,CUP,SUM,0,0,0,0,6,43,25,81.4871928692 +16,SPOON,SUM,0,0,0,0,0,20,0,23.3314340115 +16,,SUM,0,0,0,0,6,68,25,126.375087738 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,0,11,2,24.2253239155 +17,CUP,SUM,0,0,0,0,4,17,12,38.069560051 +17,SPOON,SUM,0,0,0,0,0,70,2,33.4789128304 +17,,SUM,0,0,0,0,4,98,16,95.7737967968 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,0,6,0,21.8025951385 +18,CUP,SUM,1,0,1,0,58,225,35,0 +18,SPOON,SUM,0,0,0,0,0,25,8,34.8848772049 +18,,SUM,1,0,1,0,58,256,43,56.6874723434 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,8,1,22.1267249584 +19,CUP,SUM,0,0,0,0,2,22,12,38.0360929966 +19,SPOON,SUM,0,0,0,0,2,71,4,39.7218999863 +19,,SUM,0,0,0,0,4,101,17,99.8847179413 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,0,27,7,33.7247149944 +20,CUP,SUM,0,0,0,0,0,8,14,41.7777559757 +20,SPOON,SUM,0,0,0,0,2,0,0,23.593711853 +20,,SUM,0,0,0,0,2,35,21,99.0961828232 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,41,7,34.5562520027 +21,CUP,SUM,0,0,0,0,0,28,9,31.5579710007 +21,SPOON,SUM,0,0,0,0,0,177,4,57.1589159966 +21,,SUM,0,0,0,0,0,246,20,123.2731389999 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,0,5,4,24.3156139851 +22,CUP,SUM,0,0,0,0,8,24,14,43.9151771069 +22,SPOON,SUM,0,0,0,0,2,4,8,45.6140639782 +22,,SUM,0,0,0,0,10,33,26,113.8448550701 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,11,0,22.6986539364 +23,CUP,SUM,0,0,0,0,8,23,19,74.667265892 +23,SPOON,SUM,0,0,0,0,0,2,1,23.3947808743 +23,,SUM,0,0,0,0,8,36,20,120.7607007027 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,2,14,2,23.6628961563 +24,CUP,SUM,0,0,0,0,0,30,14,33.3227729797 +24,SPOON,SUM,0,0,0,0,0,33,0,24.9240260124 +24,,SUM,0,0,0,0,2,77,16,81.9096951485 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,0,4,0,22.9974930286 +25,CUP,SUM,0,0,0,0,0,30,11,33.0719721317 +25,SPOON,SUM,0,0,0,0,2,3,9,42.8371989727 +25,,SUM,0,0,0,0,2,37,20,98.9066641331 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,0,11,0,22.7645571232 +26,CUP,SUM,0,0,0,0,2,33,9,35.5580170155 +26,SPOON,SUM,0,0,0,0,0,117,3,42.593362093 +26,,SUM,0,0,0,0,2,161,12,100.9159362316 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,0,11,6,32.8555231094 +27,CUP,SUM,0,0,0,0,4,11,9,41.8360049725 +27,SPOON,SUM,0,0,0,0,0,0,4,33.3327448368 +27,,SUM,0,0,0,0,4,22,19,108.0242729187 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,0,10,0,22.9736251831 +28,CUP,SUM,0,0,0,0,0,36,15,42.8179748058 +28,SPOON,SUM,0,0,0,0,2,198,6,63.0742871761 +28,,SUM,0,0,0,0,2,244,21,128.8658871651 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,0,9,0,22.3223969936 +29,CUP,SUM,0,0,0,0,0,64,29,83.3439390659 +29,SPOON,SUM,1,0,1,0,18,1003,25,0 +29,,SUM,1,0,1,0,18,1076,54,105.6663360596 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,2,16,2,24.2006759644 +30,CUP,SUM,0,0,0,0,2,42,11,43.6746821404 +30,SPOON,SUM,1,0,1,0,38,6,51,0 +30,,SUM,1,0,1,0,42,64,64,67.8753581047 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,0,27,1,27.6088960171 +31,CUP,SUM,0,0,0,0,0,17,8,32.2501180172 +31,SPOON,SUM,0,0,0,0,4,178,4,54.8282170296 +31,,SUM,0,0,0,0,4,222,13,114.6872310638 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,0,6,0,22.2594530582 +32,CUP,SUM,1,0,0,1,0,230,57,0 +32,SPOON,SUM,1,0,0,1,6,22,176,0 +32,,SUM,2,0,0,2,6,258,233,22.2594530582 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,45,4,33.3577020168 +33,CUP,SUM,0,0,0,0,0,24,13,42.7964229584 +33,SPOON,SUM,0,0,0,0,0,130,0,43.0040519238 +33,,SUM,0,0,0,0,0,199,17,119.158176899 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,2,14,0,24.1062018871 +34,CUP,SUM,0,0,0,0,0,36,13,49.8619787693 +34,SPOON,SUM,0,0,0,0,6,17,4,30.124587059 +34,,SUM,0,0,0,0,8,67,17,104.0927677155 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,0,41,12,44.4348330498 +35,CUP,SUM,1,0,1,0,40,80,52,0 +35,SPOON,SUM,0,0,0,0,0,1,0,22.407171011 +35,,SUM,1,0,1,0,40,122,64,66.8420040607 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,0,26,2,24.1208410263 +36,CUP,SUM,1,0,0,1,14,196,55,0 +36,SPOON,SUM,0,0,0,0,0,10,3,27.7520360947 +36,,SUM,1,0,0,1,14,232,60,51.872877121 +36,,,,,,,,,, +37,, +37,BOWL,SUM,0,0,0,0,0,29,7,40.24803304672241 +37,CUP,SUM,0,0,0,0,0,44,26,71.00444293022156 +37,SPOON,SUM,0,0,0,0,2,9,3,29.34636092185974 +37,,SUM,0,0,0,0,2,82,36,140.5988368988037 +37,, +38,, +38,BOWL,SUM,0,0,0,0,0,3,0,22.307039976119995 +38,CUP,SUM,0,0,0,0,0,35,21,65.91069316864014 +38,SPOON,SUM,1,0,1,0,0,1503,19,0.0 +38,,SUM,1,0,1,0,0,1541,40,88.21773314476013 +38,, +39,, +39,BOWL,SUM,0,0,0,0,0,10,4,26.073523998260498 +39,CUP,SUM,0,0,0,0,6,18,14,42.443419218063354 +39,SPOON,SUM,0,0,0,0,0,0,0,21.592854022979736 +39,,SUM,0,0,0,0,6,28,18,90.10979723930359 +39,, +40,, +40,BOWL,SUM,0,0,0,0,10,6,4,30.61063504219055 +40,CUP,SUM,0,0,0,0,0,43,20,56.45544195175171 +40,SPOON,SUM,1,0,1,0,78,62,19,0.0 +40,,SUM,1,0,1,0,88,111,43,87.06607699394226 +40,, +41,, +41,BOWL,SUM,0,0,0,0,0,7,0,20.901190042495728 +41,CUP,SUM,0,0,0,0,0,22,9,44.18484592437744 +41,SPOON,SUM,0,0,0,0,0,25,5,31.846824169158936 +41,,SUM,0,0,0,0,0,54,14,96.9328601360321 +41,, +42,, +42,BOWL,SUM,1,0,1,0,10,145,53,0.0 +42,CUP,SUM,0,0,0,0,0,30,18,44.71636199951172 +42,SPOON,SUM,0,0,0,0,0,2,2,22.53639316558838 +42,,SUM,1,0,1,0,10,177,73,67.2527551651001 +42,, +43,, +43,BOWL,SUM,0,0,0,0,0,8,6,30.527074098587036 +43,CUP,SUM,0,0,0,0,0,21,13,65.4583649635315 +43,SPOON,SUM,0,0,0,0,0,0,0,20.84694504737854 +43,,SUM,0,0,0,0,0,29,19,116.83238410949707 +43,, +44,, +44,BOWL,SUM,0,0,0,0,2,101,5,41.21380400657654 +44,CUP,SUM,0,0,0,0,0,14,9,29.503537893295288 +44,SPOON,SUM,0,0,0,0,0,97,0,35.230247020721436 +44,,SUM,0,0,0,0,2,212,14,105.94758892059326 +44,, +45,, +45,BOWL,SUM,0,0,0,0,74,28,2,78.47235298156738 +45,CUP,SUM,0,0,0,0,2,9,13,31.771130084991455 +45,SPOON,SUM,0,0,0,0,0,2,6,32.3676540851593 +45,,SUM,0,0,0,0,76,39,21,142.61113715171814 +45,, +46,, +46,BOWL,SUM,0,0,0,0,0,14,0,21.345391035079956 +46,CUP,SUM,0,0,0,0,8,33,12,41.80863904953003 +46,SPOON,SUM,0,0,0,0,0,17,4,22.64025902748108 +46,,SUM,0,0,0,0,8,64,16,85.79428911209106 +46,, +47,, +47,BOWL,SUM,0,0,0,0,0,17,1,25.600780963897705 +47,CUP,SUM,0,0,0,0,4,92,35,112.95112800598145 +47,SPOON,SUM,0,0,0,0,0,159,1,44.457180976867676 +47,,SUM,0,0,0,0,4,268,37,183.00908994674683 +47,, +48,, +48,BOWL,SUM,0,0,0,0,0,6,0,20.269055128097534 +48,CUP,SUM,0,0,0,0,0,10,11,38.28371596336365 +48,SPOON,SUM,0,0,0,0,0,14,2,22.384089946746826 +48,,SUM,0,0,0,0,0,30,13,80.93686103820801 +48,, +49,, +49,BOWL,SUM,0,0,0,0,2,9,6,27.56825089454651 +49,CUP,SUM,0,0,0,0,2,13,12,36.260333776474 +49,SPOON,SUM,0,0,0,0,0,73,0,31.788787841796875 +49,,SUM,0,0,0,0,4,95,18,95.61737251281738 +49,, +50,, +50,BOWL,SUM,0,0,0,0,0,9,0,20.9182448387146 +50,CUP,SUM,1,0,1,0,28,171,59,0.0 +50,SPOON,SUM,0,0,0,0,2,116,1,38.36218595504761 +50,,SUM,1,0,1,0,30,296,60,59.28043079376221 +50,, +51,, +51,BOWL,SUM,0,0,0,0,10,83,25,91.92238211631775 +51,CUP,SUM,0,0,0,0,6,9,9,35.28575110435486 +51,SPOON,SUM,0,0,0,0,0,13,4,28.198916912078857 +51,,SUM,0,0,0,0,16,105,38,155.40705013275146 +51,, +52,, +52,BOWL,SUM,0,0,0,0,2,25,0,21.521638870239258 +52,CUP,SUM,0,0,0,0,0,4,10,24.527239084243774 +52,SPOON,SUM,0,0,0,0,2,114,11,61.12362790107727 +52,,SUM,0,0,0,0,4,143,21,107.1725058555603 +52,, +53,, +53,BOWL,SUM,0,0,0,0,0,9,0,20.768600940704346 +53,CUP,SUM,0,0,0,0,0,8,12,30.264410972595215 +53,SPOON,SUM,1,0,1,0,16,1168,30,0.0 +53,,SUM,1,0,1,0,16,1185,42,51.03301191329956 +53,, +54,, +54,BOWL,SUM,0,0,0,0,0,17,5,34.02131509780884 +54,CUP,SUM,0,0,0,0,0,17,9,33.027060985565186 +54,SPOON,SUM,0,0,0,0,0,48,0,26.675041913986206 +54,,SUM,0,0,0,0,0,82,14,93.72341799736023 +54,, +55,, +55,BOWL,SUM,0,0,0,0,0,8,0,21.32369613647461 +55,CUP,SUM,0,0,0,0,10,28,12,43.620399951934814 +55,SPOON,SUM,0,0,0,0,0,105,1,40.78609800338745 +55,,SUM,0,0,0,0,10,141,13,105.73019409179688 +55,, +56,, +56,BOWL,SUM,0,0,0,0,4,17,4,26.46792197227478 +56,CUP,SUM,0,0,0,0,0,12,12,31.883935928344727 +56,SPOON,SUM,0,0,0,0,0,104,0,35.69884991645813 +56,,SUM,0,0,0,0,4,133,16,94.05070781707764 +56,, +57,, +57,BOWL,SUM,0,0,0,0,0,49,13,41.03926110267639 +57,CUP,SUM,0,0,0,0,2,14,14,31.39384913444519 +57,SPOON,SUM,0,0,0,0,0,37,3,30.554031133651733 +57,,SUM,0,0,0,0,2,100,30,102.98714137077332 +57,, +58,, +58,BOWL,SUM,0,0,0,0,0,14,0,21.322528839111328 +58,CUP,SUM,1,0,1,0,34,197,68,0.0 +58,SPOON,SUM,0,0,0,0,0,132,5,45.48689603805542 +58,,SUM,1,0,1,0,34,343,73,66.80942487716675 +58,, +59,, +59,BOWL,SUM,0,0,0,0,0,6,4,26.555953979492188 +59,CUP,SUM,0,0,0,0,0,7,10,25.26873803138733 +59,SPOON,SUM,0,0,0,0,8,4,7,41.705342054367065 +59,,SUM,0,0,0,0,8,17,21,93.53003406524658 +59,, +60,, +60,BOWL,SUM,0,0,0,0,2,31,2,23.180285930633545 +60,CUP,SUM,0,0,0,0,2,22,22,56.070045948028564 +60,SPOON,SUM,0,0,0,0,8,103,2,43.05188798904419 +60,,SUM,0,0,0,0,12,156,26,122.3022198677063 +60,, +61,, +61,BOWL,SUM,0,0,0,0,2,13,0,21.60236620903015 +61,CUP,SUM,0,0,0,0,0,4,12,30.110875844955444 +61,SPOON,SUM,0,0,0,0,0,27,3,28.10906195640564 +61,,SUM,0,0,0,0,2,44,15,79.82230401039124 +61,, +62,, +62,BOWL,SUM,0,0,0,0,0,12,8,44.784417152404785 +62,CUP,SUM,0,0,0,0,0,2,8,24.957260131835938 +62,SPOON,SUM,0,0,0,0,0,72,5,45.1629581451416 +62,,SUM,0,0,0,0,0,86,21,114.90463542938232 +62,, +63,, +63,BOWL,SUM,0,0,0,0,0,3,0,20.793582916259766 +63,CUP,SUM,0,0,0,0,0,6,10,24.969738960266113 +63,SPOON,SUM,0,0,0,0,0,3,2,23.46364402770996 +63,,SUM,0,0,0,0,0,12,12,69.22696590423584 +63,, +64,, +64,BOWL,SUM,0,0,0,0,0,27,2,22.754467964172363 +64,CUP,SUM,0,0,0,0,2,17,10,26.882348775863647 +64,SPOON,SUM,0,0,0,0,0,20,2,22.46682095527649 +64,,SUM,0,0,0,0,2,64,14,72.1036376953125 +64,, +65,, +65,BOWL,SUM,0,0,0,0,2,52,36,93.57299900054932 +65,CUP,SUM,0,0,0,0,0,23,21,50.831258058547974 +65,SPOON,SUM,0,0,0,0,0,24,0,22.120885133743286 +65,,SUM,0,0,0,0,2,99,57,166.52514219284058 +65,, +66,, +66,BOWL,SUM,0,0,0,0,0,8,0,21.518718957901 +66,CUP,SUM,0,0,0,0,0,17,13,48.18896698951721 +66,SPOON,SUM,0,0,0,0,0,4,2,22.375599145889282 +66,,SUM,0,0,0,0,0,29,15,92.0832850933075 +66,, +67,, +67,BOWL,SUM,0,0,0,0,0,20,0,21.409648895263672 +67,CUP,SUM,0,0,0,0,0,26,12,30.5950710773468 +67,SPOON,SUM,1,0,1,0,76,218,23,0.0 +67,,SUM,1,0,1,0,76,264,35,52.004719972610474 +67,, +68,, +68,BOWL,SUM,0,0,0,0,0,6,2,21.777693033218384 +68,CUP,SUM,0,0,0,0,0,3,7,24.324465036392212 +68,SPOON,SUM,1,0,1,0,34,17,47,0.0 +68,,SUM,1,0,1,0,34,26,56,46.102158069610596 +68,, +69,, +69,BOWL,SUM,1,0,1,0,4,520,61,0.0 +69,CUP,SUM,0,0,0,0,0,4,8,28.0465190410614 +69,SPOON,SUM,0,0,0,0,10,123,0,43.455127000808716 +69,,SUM,1,0,1,0,14,647,69,71.50164604187012 +69,, +70,, +70,BOWL,SUM,0,0,0,0,0,6,0,20.82529902458191 +70,CUP,SUM,0,0,0,0,0,33,29,75.97404408454895 +70,SPOON,SUM,0,0,0,0,0,11,4,24.326442003250122 +70,,SUM,0,0,0,0,0,50,33,121.12578511238098 +70,, +71,, +71,BOWL,SUM,0,0,0,0,4,101,47,183.15310716629028 +71,CUP,SUM,0,0,0,0,0,31,21,59.244802951812744 +71,SPOON,SUM,0,0,0,0,0,130,1,41.5876030921936 +71,,SUM,0,0,0,0,4,262,69,283.98551321029663 +71,, +72,, +72,BOWL,SUM,0,0,0,0,0,6,0,20.633179903030396 +72,CUP,SUM,0,0,0,0,4,7,17,50.930447816848755 +72,SPOON,SUM,0,0,0,0,2,554,12,119.83056092262268 +72,,SUM,0,0,0,0,6,567,29,191.39418864250183 +72,, +73,, +73,BOWL,SUM,0,0,0,0,0,168,5,44.95041108131409 +73,CUP,SUM,0,0,0,0,0,9,12,34.26213598251343 +73,SPOON,SUM,0,0,0,0,0,1,0,22.002171993255615 +73,,SUM,0,0,0,0,0,178,17,101.21471905708313 +73,, +74,, +74,BOWL,SUM,0,0,0,0,2,50,0,27.079575061798096 +74,CUP,SUM,0,0,0,0,2,15,12,36.539175033569336 +74,SPOON,SUM,0,0,0,0,6,25,0,24.48731303215027 +74,,SUM,0,0,0,0,10,90,12,88.1060631275177 +74,, +75,, +75,BOWL,SUM,0,0,0,0,2,2,4,22.32215404510498 +75,CUP,SUM,0,0,0,0,0,17,9,39.879425048828125 +75,SPOON,SUM,0,0,0,0,0,2,6,31.45821714401245 +75,,SUM,0,0,0,0,2,21,19,93.65979623794556 +75,, +76,, +76,BOWL,SUM,0,0,0,0,2,7,1,23.749891996383667 +76,CUP,SUM,1,0,0,1,0,189,58,0.0 +76,SPOON,SUM,0,0,0,0,0,5,2,21.89387083053589 +76,,SUM,1,0,0,1,2,201,61,45.643762826919556 +76,, +77,, +77,BOWL,SUM,0,0,0,0,0,21,0,20.86746907234192 +77,CUP,SUM,0,0,0,0,2,20,14,40.2749080657959 +77,SPOON,SUM,0,0,0,0,0,91,1,35.96913409233093 +77,,SUM,0,0,0,0,2,132,15,97.11151123046875 +77,, +78,, +78,BOWL,SUM,0,0,0,0,0,11,6,35.37967801094055 +78,CUP,SUM,1,0,1,0,50,235,55,0.0 +78,SPOON,SUM,0,0,0,0,0,29,0,22.093551874160767 +78,,SUM,1,0,1,0,50,275,61,57.47322988510132 +78,, +79,, +79,BOWL,SUM,0,0,0,0,0,54,1,26.944404125213623 +79,CUP,SUM,0,0,0,0,0,41,21,49.0862557888031 +79,SPOON,SUM,0,0,0,0,0,19,0,22.14700412750244 +79,,SUM,0,0,0,0,0,114,22,98.17766404151917 +79,, +80,, +80,BOWL,SUM,0,0,0,0,0,30,2,23.43761897087097 +80,CUP,SUM,0,0,0,0,0,12,10,25.297131061553955 +80,SPOON,SUM,1,0,1,0,74,213,21,0.0 +80,,SUM,1,0,1,0,74,255,33,48.73475003242493 +80,, +81,, +81,BOWL,SUM,1,0,1,0,2,358,63,0.0 +81,CUP,SUM,0,0,0,0,0,26,12,54.76095199584961 +81,SPOON,SUM,0,0,0,0,6,5,0,23.15953302383423 +81,,SUM,1,0,1,0,8,389,75,77.92048501968384 +81,, +82,, +82,BOWL,SUM,0,0,0,0,0,1164,40,254.94066095352173 +82,CUP,SUM,0,0,0,0,0,7,9,24.841611862182617 +82,SPOON,SUM,0,0,0,0,0,96,5,41.073246002197266 +82,,SUM,0,0,0,0,0,1267,54,320.8555188179016 +82,, +83,, +83,BOWL,SUM,0,0,0,0,0,86,16,52.312026023864746 +83,CUP,SUM,0,0,0,0,0,10,11,51.78516411781311 +83,SPOON,SUM,0,0,0,0,0,27,1,23.947245121002197 +83,,SUM,0,0,0,0,0,123,28,128.04443526268005 +83,, +84,, +84,BOWL,SUM,0,0,0,0,0,2,2,22.1021409034729 +84,CUP,SUM,0,0,0,0,0,11,10,25.351792097091675 +84,SPOON,SUM,0,0,0,0,0,83,0,32.21228504180908 +84,,SUM,0,0,0,0,0,96,12,79.66621804237366 +84,, +85,, +85,BOWL,SUM,0,0,0,0,0,48,0,22.181363105773926 +85,CUP,SUM,0,0,0,0,0,25,19,49.34154200553894 +85,SPOON,SUM,0,0,0,0,0,130,8,44.812100887298584 +85,,SUM,0,0,0,0,0,203,27,116.33500599861145 +85,, +86,, +86,BOWL,SUM,0,0,0,0,0,8,0,21.13679599761963 +86,CUP,SUM,0,0,0,0,2,32,24,61.08252501487732 +86,SPOON,SUM,0,0,0,0,0,107,1,42.088578939437866 +86,,SUM,0,0,0,0,2,147,25,124.30789995193481 +86,, +87,, +87,BOWL,SUM,0,0,0,0,6,539,18,123.83187818527222 +87,CUP,SUM,1,0,0,1,0,177,53,0.0 +87,SPOON,SUM,0,0,0,0,0,5,2,21.16129183769226 +87,,SUM,1,0,0,1,6,721,73,144.99317002296448 +87,, +88,, +88,BOWL,SUM,0,0,0,0,0,3,2,21.50955295562744 +88,CUP,SUM,1,0,1,0,40,206,44,0.0 +88,SPOON,SUM,0,0,0,0,2,159,1,50.71727108955383 +88,,SUM,1,0,1,0,42,368,47,72.22682404518127 +88,, +89,, +89,BOWL,SUM,0,0,0,0,0,15,1,25.47061800956726 +89,CUP,SUM,1,0,1,0,22,333,68,0.0 +89,SPOON,SUM,0,0,0,0,0,9,0,21.463151931762695 +89,,SUM,1,0,1,0,22,357,69,46.933769941329956 +89,, +90,, +90,BOWL,SUM,0,0,0,0,2,79,11,59.22461199760437 +90,CUP,SUM,0,0,0,0,0,6,7,24.521049976348877 +90,SPOON,SUM,0,0,0,0,0,559,18,119.77789211273193 +90,,SUM,0,0,0,0,2,644,36,203.52355408668518 +90,, +91,, +91,BOWL,SUM,0,0,0,0,0,21,0,20.882314920425415 +91,CUP,SUM,1,0,0,1,8,175,57,0.0 +91,SPOON,SUM,1,0,0,1,0,74,170,0.0 +91,,SUM,2,0,0,2,8,270,227,20.882314920425415 +91,, +92,, +92,BOWL,SUM,0,0,0,0,6,4,2,22.83968496322632 +92,CUP,SUM,1,0,0,1,0,168,52,0.0 +92,SPOON,SUM,0,0,0,0,2,24,3,28.669395923614502 +92,,SUM,1,0,0,1,8,196,57,51.50908088684082 +92,, +93,, +93,BOWL,SUM,1,0,1,0,6,249,50,0.0 +93,CUP,SUM,0,0,0,0,0,18,7,24.565680027008057 +93,SPOON,SUM,0,0,0,0,0,0,4,28.672372102737427 +93,,SUM,1,0,1,0,6,267,61,53.23805212974548 +93,, +94,, +94,BOWL,SUM,0,0,0,0,0,12,9,35.96805214881897 +94,CUP,SUM,0,0,0,0,0,6,9,29.720420122146606 +94,SPOON,SUM,0,0,0,0,0,13,0,21.349557876586914 +94,,SUM,0,0,0,0,0,31,18,87.03803014755249 +94,, +95,, +95,BOWL,SUM,0,0,0,0,0,31,8,32.04552698135376 +95,CUP,SUM,0,0,0,0,0,75,32,97.09082198143005 +95,SPOON,SUM,0,0,0,0,0,176,2,45.793112993240356 +95,,SUM,0,0,0,0,0,282,42,174.92946195602417 +95,, +96,, +96,BOWL,SUM,0,0,0,0,0,35,4,31.052915811538696 +96,CUP,SUM,0,0,0,0,0,7,8,28.62856888771057 +96,SPOON,SUM,0,0,0,0,0,56,0,28.61168384552002 +96,,SUM,0,0,0,0,0,98,12,88.29316854476929 +96,, +97,, +97,BOWL,SUM,0,0,0,0,0,12,2,22.535700798034668 +97,CUP,SUM,0,0,0,0,8,62,28,90.53108191490173 +97,SPOON,SUM,0,0,0,0,0,13,2,23.228179931640625 +97,,SUM,0,0,0,0,8,87,32,136.29496264457703 +97,, +98,, +98,BOWL,SUM,0,0,0,0,10,16,4,29.92440104484558 +98,CUP,SUM,1,0,1,0,38,166,43,0.0 +98,SPOON,SUM,0,0,0,0,0,38,2,26.19374704360962 +98,,SUM,1,0,1,0,48,220,49,56.1181480884552 +98,, +99,, +99,BOWL,SUM,0,0,0,0,0,10,4,22.145445108413696 +99,CUP,SUM,0,0,0,0,0,16,10,35.24067306518555 +99,SPOON,SUM,0,0,0,0,2,6,0,22.119751930236816 +99,,SUM,0,0,0,0,2,32,14,79.50587010383606 +99,, +100,, +100,BOWL,SUM,0,0,0,0,0,251,40,139.56932592391968 +100,CUP,SUM,0,0,0,0,10,23,11,41.81484794616699 +100,SPOON,SUM,0,0,0,0,0,124,13,65.87700915336609 +100,,SUM,0,0,0,0,10,398,64,247.26118302345276 +100,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_BOXY_orig_kitchen_new_var_only_data_offset_40.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_BOXY_orig_kitchen_new_var_only_data_offset_40.csv new file mode 100644 index 0000000000..c448831903 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_BOXY_orig_kitchen_new_var_only_data_offset_40.csv @@ -0,0 +1,468 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,1,0,1,0,0,1730,8,0 +0,CUP,SUM,0,0,0,0,8,119,9,34.7705729008 +0,SPOON,SUM,0,0,0,0,0,413,4,68.6477711201 +0,,SUM,1,0,1,0,8,2262,21,103.4183440208 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,2,30,3,23.72239995 +1,CUP,SUM,0,0,0,0,0,18,0,15.6956329346 +1,SPOON,SUM,0,0,0,0,6,216,13,53.5215101242 +1,,SUM,0,0,0,0,8,264,16,92.9395430088 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,1,0,1,0,0,1478,9,0 +2,CUP,SUM,1,0,1,0,0,1171,56,0 +2,SPOON,SUM,1,0,1,0,2,1582,0,0 +2,,SUM,3,0,3,0,2,4231,65,0 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,8,52,3,30.1395099163 +3,CUP,SUM,1,0,1,0,6,1663,0,0 +3,SPOON,SUM,0,0,0,0,0,11,3,24.8143157959 +3,,SUM,1,0,1,0,14,1726,6,54.9538257122 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,73,0,21.8089170456 +4,CUP,SUM,0,0,0,0,10,553,42,96.6059780121 +4,SPOON,SUM,0,0,0,0,0,30,1,23.2702269554 +4,,SUM,0,0,0,0,10,656,43,141.6851220131 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,0,284,0,42.817499876 +5,CUP,SUM,1,0,1,0,8,469,101,0 +5,SPOON,SUM,0,0,0,0,0,3,0,19.8554189205 +5,,SUM,1,0,1,0,8,756,101,62.6729187965 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,6,977,4,112.022936821 +6,CUP,SUM,1,0,1,0,0,712,97,0 +6,SPOON,SUM,1,0,1,0,0,1651,0,0 +6,,SUM,2,0,2,0,6,3340,101,112.022936821 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,0,194,9,44.0687229633 +7,CUP,SUM,0,0,0,0,0,114,1,25.2158870697 +7,SPOON,SUM,1,0,1,0,18,1589,0,0 +7,,SUM,1,0,1,0,18,1897,10,69.284610033 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,1,0,1,0,2,1509,9,0 +8,CUP,SUM,0,0,0,0,2,108,0,23.0277988911 +8,SPOON,SUM,0,0,0,0,2,577,12,88.3502869606 +8,,SUM,1,0,1,0,6,2194,21,111.3780858517 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,6,1275,45,173.8780109882 +9,CUP,SUM,0,0,0,0,0,62,2,19.6882851124 +9,SPOON,SUM,0,0,0,0,0,413,1,60.7821500301 +9,,SUM,0,0,0,0,6,1750,48,254.3484461308 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,1,0,1,0,0,1320,23,0 +10,CUP,SUM,0,0,0,0,0,98,6,23.3440771103 +10,SPOON,SUM,1,0,1,0,8,1764,0,0 +10,,SUM,2,0,2,0,8,3182,29,23.3440771103 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,0,78,9,38.0424048901 +11,CUP,SUM,1,0,1,0,12,1440,27,0 +11,SPOON,SUM,1,0,1,0,0,2017,0,0 +11,,SUM,2,0,2,0,12,3535,36,38.0424048901 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,0,255,1,41.9302330017 +12,CUP,SUM,1,0,1,0,0,331,123,0 +12,SPOON,SUM,0,0,0,0,0,1,2,23.3973939419 +12,,SUM,1,0,1,0,0,587,126,65.3276269436 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,1,0,1,0,6,1581,0,0 +13,CUP,SUM,1,0,1,0,0,1060,66,0 +13,SPOON,SUM,0,0,0,0,0,8,0,22.4223480225 +13,,SUM,2,0,2,0,6,2649,66,22.4223480225 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,0,135,6,41.803055048 +14,CUP,SUM,0,0,0,0,0,114,4,24.4368078709 +14,SPOON,SUM,1,0,1,0,0,1581,0,0 +14,,SUM,1,0,1,0,0,1830,10,66.2398629189 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,0,35,4,19.4931669235 +15,CUP,SUM,1,0,1,0,24,604,86,0 +15,SPOON,SUM,0,0,0,0,0,5,0,20.1734828949 +15,,SUM,1,0,1,0,24,644,90,39.6666498184 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,142,2,29.8151988983 +16,CUP,SUM,1,1,0,0,0,1519,0,0 +16,SPOON,SUM,1,0,1,0,6,1683,0,0 +16,,SUM,2,1,1,0,6,3344,2,29.8151988983 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,0,72,8,37.171859026 +17,CUP,SUM,1,0,1,0,10,1426,22,0 +17,SPOON,SUM,0,0,0,0,0,3,3,26.9861700535 +17,,SUM,1,0,1,0,10,1501,33,64.1580290794 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,0,271,0,40.0632600784 +18,CUP,SUM,1,0,1,0,0,1262,48,0 +18,SPOON,SUM,0,0,0,0,2,84,6,36.7575480938 +18,,SUM,1,0,1,0,2,1617,54,76.8208081722 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,37,2,22.3562581539 +19,CUP,SUM,1,0,1,0,14,1029,55,0 +19,SPOON,SUM,0,0,0,0,0,109,1,32.7672879696 +19,,SUM,1,0,1,0,14,1175,58,55.1235461235 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,4,302,1,46.1566500664 +20,CUP,SUM,0,0,0,0,8,286,9,54.274009943 +20,SPOON,SUM,0,0,0,0,0,47,4,24.3452339172 +20,,SUM,0,0,0,0,12,635,14,124.7758939266 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,77,0,24.8697860241 +21,CUP,SUM,1,0,1,0,2,1497,19,0 +21,SPOON,SUM,0,0,0,0,6,405,2,61.1222782135 +21,,SUM,1,0,1,0,8,1979,21,85.9920642376 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,1,1,0,0,0,1519,0,0 +22,CUP,SUM,0,0,0,0,0,57,7,19.3956680298 +22,SPOON,SUM,1,0,1,0,0,1907,0,0 +22,,SUM,2,1,1,0,0,3483,7,19.3956680298 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,42,1,24.1156539917 +23,CUP,SUM,1,0,1,0,0,509,91,0 +23,SPOON,SUM,0,0,0,0,54,603,4,101.6069741249 +23,,SUM,1,0,1,0,54,1154,96,125.7226281166 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,1,1,0,0,0,1519,0,0 +24,CUP,SUM,1,0,1,0,2,239,112,0 +24,SPOON,SUM,1,0,1,0,2,1583,0,0 +24,,SUM,3,1,2,0,4,3341,112,0 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,0,9,0,18.4134161472 +25,CUP,SUM,1,0,1,0,8,1228,52,0 +25,SPOON,SUM,1,0,1,0,0,1612,0,0 +25,,SUM,2,0,2,0,8,2849,52,18.4134161472 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,0,97,4,32.7678849697 +26,CUP,SUM,0,0,0,0,4,150,12,34.4456989765 +26,SPOON,SUM,0,0,0,0,8,119,1,39.0967988968 +26,,SUM,0,0,0,0,12,366,17,106.310382843 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,0,110,5,43.3442578316 +27,CUP,SUM,1,0,1,0,20,1168,55,0 +27,SPOON,SUM,0,0,0,0,0,339,0,50.8776061535 +27,,SUM,1,0,1,0,20,1617,60,94.2218639851 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,1,0,1,0,0,1395,12,0 +28,CUP,SUM,1,0,0,1,0,1595,6,0 +28,SPOON,SUM,1,0,1,0,0,1581,0,0 +28,,SUM,3,0,2,1,0,4571,18,0 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,1,0,1,0,0,1584,0,0 +29,CUP,SUM,1,0,1,0,8,460,111,0 +29,SPOON,SUM,0,0,0,0,0,501,2,75.4763920307 +29,,SUM,2,0,2,0,8,2545,113,75.4763920307 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,1,0,1,0,0,1611,0,0 +30,CUP,SUM,0,0,0,0,2,83,9,28.8974950314 +30,SPOON,SUM,1,0,1,0,2,1526,8,0 +30,,SUM,2,0,2,0,4,3220,17,28.8974950314 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,2,475,8,69.3630821705 +31,CUP,SUM,0,0,0,0,0,118,13,30.3873419762 +31,SPOON,SUM,1,1,0,0,0,1519,0,0 +31,,SUM,1,1,0,0,2,2112,21,99.7504241467 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,1,0,1,0,0,1582,6,0 +32,CUP,SUM,0,0,0,0,0,1082,8,123.5007100105 +32,SPOON,SUM,0,0,0,0,2,147,1,39.6166009903 +32,,SUM,1,0,1,0,2,2811,15,163.1173110008 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,6,340,18,83.7678849697 +33,CUP,SUM,0,0,0,0,0,29,8,18.6580560207 +33,SPOON,SUM,0,0,0,0,0,96,1,32.1100139618 +33,,SUM,0,0,0,0,6,465,27,134.5359549522 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,1,0,1,0,6,1611,0,0 +34,CUP,SUM,0,0,0,0,0,36,7,18.7877790928 +34,SPOON,SUM,1,0,1,0,0,2059,10,0 +34,,SUM,2,0,2,0,6,3706,17,18.7877790928 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,0,151,9,45.2996709347 +35,CUP,SUM,1,0,1,0,2,1213,54,0 +35,SPOON,SUM,1,0,1,0,0,1712,0,0 +35,,SUM,2,0,2,0,2,3076,63,45.2996709347 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,6,106,1,30.2788350582 +36,CUP,SUM,1,0,1,0,0,434,109,0 +36,SPOON,SUM,1,0,1,0,48,1427,11,0 +36,,SUM,2,0,2,0,54,1967,121,30.2788350582 +36,,,,,,,,,, +37,,,,,,,,,, +37,BOWL,SUM,0,0,0,0,0,32,0,17.8252677917 +37,CUP,SUM,0,0,0,0,0,52,8,22.2810180187 +37,SPOON,SUM,1,0,1,0,0,1583,0,0 +37,,SUM,1,0,1,0,0,1667,8,40.1062858105 +37,,,,,,,,,, +38,,,,,,,,,, +38,BOWL,SUM,1,0,1,0,0,1565,9,0 +38,CUP,SUM,1,0,1,0,0,822,89,0 +38,SPOON,SUM,0,0,0,0,10,79,18,55.9562389851 +38,,SUM,2,0,2,0,10,2466,116,55.9562389851 +38,,,,,,,,,, +39,,,,,,,,,, +39,BOWL,SUM,1,0,1,0,6,2168,0,0 +39,CUP,SUM,0,0,0,0,0,44,9,24.623529911 +39,SPOON,SUM,0,0,0,0,0,332,2,52.1815450191 +39,,SUM,1,0,1,0,6,2544,11,76.8050749302 +39,,,,,,,,,, +40,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,0,11,5,26.4386639595 +40,CUP,SUM,1,0,1,0,10,1485,16,0 +40,SPOON,SUM,0,0,0,0,0,91,0,28.8207840919 +40,,SUM,1,0,1,0,10,1587,21,55.2594480515 +40,,,,,,,,,, +41,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,0,63,0,22.6465399265 +41,CUP,SUM,1,0,1,0,10,1472,19,0 +41,SPOON,SUM,0,0,0,0,0,133,4,44.2571890354 +41,,SUM,1,0,1,0,10,1668,23,66.9037289619 +41,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,1,0,1,0,2,1602,3,0 +42,CUP,SUM,1,0,0,1,0,1529,7,0 +42,SPOON,SUM,1,0,1,0,6,1590,0,0 +42,,SUM,3,0,2,1,8,4721,10,0 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,8,235,3,50.807352066 +43,CUP,SUM,1,0,1,0,58,789,38,0 +43,SPOON,SUM,0,0,0,0,0,9,2,21.6586279869 +43,,SUM,1,0,1,0,66,1033,43,72.4659800529 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,1,0,1,0,0,2972,13,0 +44,CUP,SUM,0,0,0,0,0,623,5,81.8591668606 +44,SPOON,SUM,1,0,1,0,0,1583,0,0 +44,,SUM,2,0,2,0,0,5178,18,81.8591668606 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,0,50,0,19.8483669758 +45,CUP,SUM,0,0,0,0,0,59,1,23.1129689217 +45,SPOON,SUM,1,0,1,0,4,1584,0,0 +45,,SUM,1,0,1,0,4,1693,1,42.9613358974 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,0,41,3,27.5056848526 +46,CUP,SUM,1,0,1,0,24,1307,20,0 +46,SPOON,SUM,0,0,0,0,0,22,4,26.5176100731 +46,,SUM,1,0,1,0,24,1370,27,54.0232949257 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,1,0,1,0,0,1598,0,0 +47,CUP,SUM,1,0,0,1,0,1526,7,0 +47,SPOON,SUM,1,0,1,0,12,748,36,0 +47,,SUM,3,0,2,1,12,3872,43,0 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,1,0,1,0,2,1586,0,0 +48,CUP,SUM,0,0,0,0,0,303,18,59.1899659634 +48,SPOON,SUM,0,0,0,0,0,28,5,27.075772047 +48,,SUM,1,0,1,0,2,1917,23,86.2657380104 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,2,122,11,58.7340948582 +49,CUP,SUM,1,0,1,0,0,696,74,0 +49,SPOON,SUM,1,0,1,0,0,1573,5,0 +49,,SUM,2,0,2,0,2,2391,90,58.7340948582 +49,,,,,,,,,, +50,,,,,,,,,, +50,BOWL,SUM,0,0,0,0,0,128,4,29.277618885 +50,CUP,SUM,1,0,1,0,8,1317,21,0 +50,SPOON,SUM,1,0,1,0,0,1485,10,0 +50,,SUM,2,0,2,0,8,2930,35,29.277618885 +50,,,,,,,,,, +51,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,0,191,12,59.5478820801 +51,CUP,SUM,0,0,0,0,2,20,8,21.6435570717 +51,SPOON,SUM,0,0,0,0,0,45,0,23.8010799885 +51,,SUM,0,0,0,0,2,256,20,104.9925191402 +51,,,,,,,,,, +52,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,14,647,12,94.6494660378 +52,CUP,SUM,1,0,1,0,0,901,83,0 +52,SPOON,SUM,0,0,0,0,4,289,17,73.2316141129 +52,,SUM,1,0,1,0,18,1837,112,167.8810801506 +52,,,,,,,,,, +53,,,,,,,,,, +53,BOWL,SUM,0,0,0,0,0,240,2,41.2062108517 +53,CUP,SUM,1,0,1,0,12,1186,51,0 +53,SPOON,SUM,0,0,0,0,22,711,3,106.6509411335 +53,,SUM,1,0,1,0,34,2137,56,147.8571519852 +53,,,,,,,,,, +54,,,,,,,,,, +54,BOWL,SUM,0,0,0,0,0,699,4,81.8336138725 +54,CUP,SUM,0,0,0,0,0,401,13,65.9413769245 +54,SPOON,SUM,0,0,0,0,0,8,1,24.5036940575 +54,,SUM,0,0,0,0,0,1108,18,172.2786848545 +54,,,,,,,,,, +55,,,,,,,,,, +55,BOWL,SUM,1,0,1,0,0,1458,13,0 +55,CUP,SUM,0,0,0,0,2,932,17,126.2690579891 +55,SPOON,SUM,1,0,1,0,0,1434,19,0 +55,,SUM,2,0,2,0,2,3824,49,126.2690579891 +55,,,,,,,,,, +56,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,0,94,3,28.5904221535 +56,CUP,SUM,0,0,0,0,0,763,21,104.3427670002 +56,SPOON,SUM,0,0,0,0,8,3,1,30.3946731091 +56,,SUM,0,0,0,0,8,860,25,163.3278622627 +56,,,,,,,,,, +57,,,,,,,,,, +57,BOWL,SUM,1,0,1,0,0,1590,0,0 +57,CUP,SUM,0,0,0,0,0,45,9,23.9881029129 +57,SPOON,SUM,1,0,1,0,0,1583,0,0 +57,,SUM,2,0,2,0,0,3218,9,23.9881029129 +57,,,,,,,,,, +58,,,,,,,,,, +58,BOWL,SUM,0,0,0,0,2,230,8,57.2075610161 +58,CUP,SUM,1,0,1,0,4,917,82,0 +58,SPOON,SUM,0,0,0,0,0,41,19,42.8211479187 +58,,SUM,1,0,1,0,6,1188,109,100.0287089348 +58,,,,,,,,,, +59,,,,,,,,,, +59,BOWL,SUM,1,0,1,0,2,1865,0,0 +59,CUP,SUM,0,0,0,0,0,795,45,148.8393220901 +59,SPOON,SUM,1,0,1,0,2,1597,0,0 +59,,SUM,2,0,2,0,4,4257,45,148.8393220901 +59,,,,,,,,,, +60,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,0,92,14,61.791093111 +60,CUP,SUM,0,0,0,0,0,65,6,22.4349088669 +60,SPOON,SUM,1,0,1,0,0,2173,0,0 +60,,SUM,1,0,1,0,0,2330,20,84.2260019779 +60,,,,,,,,,, +61,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,0,14,2,19.6066668034 +61,CUP,SUM,1,0,0,1,0,1181,49,0 +61,SPOON,SUM,1,0,1,0,0,1582,0,0 +61,,SUM,2,0,1,1,0,2777,51,19.6066668034 +61,,,,,,,,,, +62,,,,,,,,,, +62,BOWL,SUM,0,0,0,0,0,177,5,46.1337120533 +62,CUP,SUM,0,0,0,0,0,78,0,20.0502710342 +62,SPOON,SUM,1,0,1,0,8,1583,0,0 +62,,SUM,1,0,1,0,8,1838,5,66.1839830875 +62,,,,,,,,,, +63,, +63,BOWL,SUM,1,0,1,0,0,1730,8,0.0 +63,CUP,SUM,0,0,0,0,8,119,9,34.4296760559082 +63,SPOON,SUM,0,0,0,0,0,413,4,67.59644794464111 +63,,SUM,1,0,1,0,8,2262,21,102.02612400054932 +63,, +64,, +64,BOWL,SUM,0,0,0,0,2,30,3,23.23501992225647 +64,CUP,SUM,0,0,0,0,0,18,0,15.920490026473999 +64,SPOON,SUM,0,0,0,0,6,216,13,53.82513499259949 +64,,SUM,0,0,0,0,8,264,16,92.98064494132996 +64,, +65,, +65,BOWL,SUM,1,0,1,0,0,1478,9,0.0 +65,CUP,SUM,1,0,1,0,0,1171,56,0.0 +65,SPOON,SUM,1,0,1,0,2,1582,0,0.0 +65,,SUM,3,0,3,0,2,4231,65,0.0 +65,, +66,, +66,BOWL,SUM,0,0,0,0,8,52,3,29.776813983917236 +66,CUP,SUM,1,0,1,0,6,1663,0,0.0 +66,SPOON,SUM,0,0,0,0,0,11,3,24.143121004104614 +66,,SUM,1,0,1,0,14,1726,6,53.91993498802185 +66,, +67,, +67,BOWL,SUM,0,0,0,0,0,73,0,22.034204959869385 +67,CUP,SUM,0,0,0,0,10,553,42,96.85354089736938 +67,SPOON,SUM,0,0,0,0,0,30,1,23.199985027313232 +67,,SUM,0,0,0,0,10,656,43,142.087730884552 +67,, +68,, +68,BOWL,SUM,0,0,0,0,0,284,0,42.733784198760986 +68,CUP,SUM,1,0,1,0,8,469,101,0.0 +68,SPOON,SUM,0,0,0,0,0,3,0,19.87397289276123 +68,,SUM,1,0,1,0,8,756,101,62.60775709152222 +68,, +69,, +69,BOWL,SUM,0,0,0,0,6,977,4,111.95688104629517 +69,CUP,SUM,1,0,1,0,0,712,97,0.0 +69,SPOON,SUM,1,0,1,0,0,1651,0,0.0 +69,,SUM,2,0,2,0,6,3340,101,111.95688104629517 +69,, +70,, +70,BOWL,SUM,0,0,0,0,0,194,9,44.45542907714844 +70,CUP,SUM,0,0,0,0,0,114,1,25.792407989501953 +70,SPOON,SUM,1,0,1,0,18,1589,0,0.0 +70,,SUM,1,0,1,0,18,1897,10,70.24783706665039 +70,, +71,, +71,BOWL,SUM,1,0,1,0,2,1509,9,0.0 +71,CUP,SUM,0,0,0,0,2,108,0,23.342176914215088 +71,SPOON,SUM,0,0,0,0,2,577,12,90.44250106811523 +71,,SUM,1,0,1,0,6,2194,21,113.78467798233032 +71,, +72,, +72,BOWL,SUM,0,0,0,0,6,1275,45,176.48302698135376 +72,CUP,SUM,0,0,0,0,0,62,2,19.543957948684692 +72,SPOON,SUM,0,0,0,0,0,413,1,61.522621870040894 +72,,SUM,0,0,0,0,6,1750,48,257.54960680007935 +72,, +73,, +73,BOWL,SUM,1,0,1,0,0,1320,23,0.0 +73,CUP,SUM,0,0,0,0,0,98,6,23.72014284133911 +73,SPOON,SUM,1,0,1,0,8,1764,0,0.0 +73,,SUM,2,0,2,0,8,3182,29,23.72014284133911 +73,, +74,, +74,BOWL,SUM,0,0,0,0,0,78,9,39.122113943099976 +74,CUP,SUM,1,0,1,0,12,1440,27,0.0 +74,SPOON,SUM,1,0,1,0,0,2017,0,0.0 +74,,SUM,2,0,2,0,12,3535,36,39.122113943099976 +74,, +75,, +75,BOWL,SUM,0,0,0,0,0,255,1,42.70116901397705 +75,CUP,SUM,1,0,1,0,0,331,123,0.0 +75,SPOON,SUM,0,0,0,0,0,1,2,23.615293979644775 +75,,SUM,1,0,1,0,0,587,126,66.31646299362183 +75,, +76,, +76,BOWL,SUM,1,0,1,0,6,1581,0,0.0 +76,CUP,SUM,1,0,1,0,0,1060,66,0.0 +76,SPOON,SUM,0,0,0,0,0,8,0,22.588038206100464 +76,,SUM,2,0,2,0,6,2649,66,22.588038206100464 +76,, +77,, +77,BOWL,SUM,0,0,0,0,0,135,6,42.25461411476135 +77,CUP,SUM,0,0,0,0,0,114,4,24.788249015808105 diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_Boxy_orig_kitchen_offset_35_var_Data.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_Boxy_orig_kitchen_offset_35_var_Data.csv new file mode 100644 index 0000000000..e2139312bb --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_Boxy_orig_kitchen_offset_35_var_Data.csv @@ -0,0 +1,120 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,0,61,7,45.81942796707153 +0,CUP,SUM,1,0,1,0,6,667,99,0.0 +0,SPOON,SUM,1,0,1,0,2,1581,0,0.0 +0,,SUM,2,0,2,0,8,2309,106,45.81942796707153 +0,, +1,, +1,BOWL,SUM,0,0,0,0,6,186,3,36.1382942199707 +1,CUP,SUM,1,0,0,1,0,1590,19,0.0 +1,SPOON,SUM,1,0,1,0,2,2259,0,0.0 +1,,SUM,2,0,1,1,8,4035,22,36.1382942199707 +1,, +2,, +2,BOWL,SUM,1,0,1,0,0,1601,0,0.0 +2,CUP,SUM,1,0,1,0,2,1085,55,0.0 +2,SPOON,SUM,1,0,1,0,0,1857,0,0.0 +2,,SUM,3,0,3,0,2,4543,55,0.0 +2,, +3,, +3,BOWL,SUM,0,0,0,0,4,597,0,75.75787878036499 +3,CUP,SUM,0,0,0,0,0,338,4,46.398179054260254 +3,SPOON,SUM,1,0,1,0,0,1570,6,0.0 +3,,SUM,1,0,1,0,4,2505,10,122.15605783462524 +3,, +4,, +4,BOWL,SUM,0,0,0,0,0,57,6,30.878013849258423 +4,CUP,SUM,1,0,1,0,8,630,79,0.0 +4,SPOON,SUM,1,0,1,0,10,1567,3,0.0 +4,,SUM,2,0,2,0,18,2254,88,30.878013849258423 +4,, +5,, +5,BOWL,SUM,1,0,1,0,2,1595,0,0.0 +5,CUP,SUM,1,0,1,0,2,240,109,0.0 +5,SPOON,SUM,1,0,1,0,0,1697,0,0.0 +5,,SUM,3,0,3,0,4,3532,109,0.0 +5,, +6,, +6,BOWL,SUM,0,0,0,0,0,102,2,25.570691108703613 +6,CUP,SUM,1,0,1,0,2,2412,26,0.0 +6,SPOON,SUM,0,0,0,0,8,137,2,40.028680086135864 +6,,SUM,1,0,1,0,10,2651,30,65.59937119483948 +6,, +7,, +7,BOWL,SUM,1,0,1,0,0,1605,0,0.0 +7,CUP,SUM,0,0,0,0,6,871,2,97.5047128200531 +7,SPOON,SUM,1,0,1,0,0,1591,0,0.0 +7,,SUM,2,0,2,0,6,4067,2,97.5047128200531 +7,, +8,, +8,BOWL,SUM,1,0,1,0,0,1588,0,0.0 +8,CUP,SUM,1,0,0,1,2,1634,6,0.0 +8,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +8,,SUM,3,1,1,1,2,4741,6,0.0 +8,, +9,, +9,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +9,CUP,SUM,1,1,0,0,0,1519,0,0.0 +9,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +9,,SUM,3,2,1,0,0,4619,0,0.0 +9,, +10,, +10,BOWL,SUM,0,0,0,0,0,44,2,26.29835319519043 +10,CUP,SUM,1,0,1,0,0,651,99,0.0 +10,SPOON,SUM,1,0,1,0,0,1599,0,0.0 +10,,SUM,2,0,2,0,0,2294,101,26.29835319519043 +10,, +11,, +11,BOWL,SUM,1,0,1,0,10,1587,0,0.0 +11,CUP,SUM,1,0,0,1,0,1608,0,0.0 +11,SPOON,SUM,1,0,1,0,0,1664,0,0.0 +11,,SUM,3,0,2,1,10,4859,0,0.0 +11,, +12,, +12,BOWL,SUM,0,0,0,0,10,689,7,100.23853302001953 +12,CUP,SUM,0,0,0,0,0,189,7,33.26832699775696 +12,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +12,,SUM,1,0,1,0,10,2459,14,133.5068600177765 +12,, +13,, +13,BOWL,SUM,1,0,1,0,2,1622,0,0.0 +13,CUP,SUM,1,0,0,1,2,1555,15,0.0 +13,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +13,,SUM,3,0,2,1,4,4758,15,0.0 +13,, +14,, +14,BOWL,SUM,0,0,0,0,0,184,3,36.78994584083557 +14,CUP,SUM,1,0,1,0,2,1321,36,0.0 +14,SPOON,SUM,1,0,1,0,26,996,39,0.0 +14,,SUM,2,0,2,0,28,2501,78,36.78994584083557 +14,, +15,, +15,BOWL,SUM,1,0,1,0,0,1709,0,0.0 +15,CUP,SUM,1,0,1,0,0,1290,36,0.0 +15,SPOON,SUM,0,0,0,0,0,143,0,32.58703017234802 +15,,SUM,2,0,2,0,0,3142,36,32.58703017234802 +15,, +16,, +16,BOWL,SUM,1,0,1,0,0,1615,0,0.0 +16,CUP,SUM,1,0,1,0,0,1587,0,0.0 +16,SPOON,SUM,1,0,1,0,0,1582,0,0.0 +16,,SUM,3,0,3,0,0,4784,0,0.0 +16,, +17,, +17,BOWL,SUM,1,0,1,0,0,1621,0,0.0 +17,CUP,SUM,0,0,0,0,0,93,8,23.781898021697998 +17,SPOON,SUM,1,0,1,0,0,1584,0,0.0 +17,,SUM,2,0,2,0,0,3298,8,23.781898021697998 +17,, +18,, +18,BOWL,SUM,0,0,0,0,0,254,6,44.5993812084198 +18,CUP,SUM,0,0,0,0,0,799,0,87.45939779281616 +18,SPOON,SUM,1,0,1,0,2,1585,0,0.0 +18,,SUM,1,0,1,0,2,2638,6,132.05877900123596 +18,, +19,, +19,BOWL,SUM,1,0,1,0,0,1593,0,0.0 +19,CUP,SUM,1,0,0,1,10,1667,9,0.0 diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_new_kitchen_new_var_orig_data_offset_22.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_new_kitchen_new_var_orig_data_offset_22.csv new file mode 100644 index 0000000000..88a6833e77 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_new_kitchen_new_var_orig_data_offset_22.csv @@ -0,0 +1,603 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,0,9,3,40.568618059158325 +0,CUP,SUM,0,0,0,0,0,17,6,38.27983093261719 +0,SPOON,SUM,0,0,0,0,0,4,0,26.354867935180664 +0,,SUM,0,0,0,0,0,30,9,105.20331692695618 +0,, +1,, +1,BOWL,SUM,0,0,0,0,0,43,7,39.81366300582886 +1,CUP,SUM,0,0,0,0,14,13,2,29.419294118881226 +1,SPOON,SUM,0,0,0,0,4,30,0,28.404908180236816 +1,,SUM,0,0,0,0,18,86,9,97.6378653049469 +1,, +2,, +2,BOWL,SUM,0,0,0,0,2,3,4,30.776752948760986 +2,CUP,SUM,0,0,0,0,0,12,9,25.92041516304016 +2,SPOON,SUM,0,0,0,0,0,898,0,149.74242281913757 +2,,SUM,0,0,0,0,2,913,13,206.43959093093872 +2,, +3,, +3,BOWL,SUM,0,0,0,0,0,19,2,23.52532386779785 +3,CUP,SUM,0,0,0,0,0,13,0,21.999826192855835 +3,SPOON,SUM,1,0,1,0,26,1598,0,0.0 +3,,SUM,1,0,1,0,26,1630,2,45.52515006065369 +3,, +4,, +4,BOWL,SUM,0,0,0,0,2,10,3,35.20064306259155 +4,CUP,SUM,0,0,0,0,2,27,7,44.037792921066284 +4,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +4,,SUM,1,0,1,0,4,1618,10,79.23843598365784 +4,, +5,, +5,BOWL,SUM,1,0,1,0,2,1584,0,0.0 +5,CUP,SUM,0,0,0,0,0,49,30,139.7995240688324 +5,SPOON,SUM,0,0,0,0,2,13,5,36.017853021621704 +5,,SUM,1,0,1,0,4,1646,35,175.8173770904541 +5,, +6,, +6,BOWL,SUM,0,0,0,0,2,39,0,28.55128002166748 +6,CUP,SUM,0,0,0,0,0,11,6,26.346949815750122 +6,SPOON,SUM,1,0,1,0,82,791,0,0.0 +6,,SUM,1,0,1,0,84,841,6,54.8982298374176 +6,, +7,, +7,BOWL,SUM,0,0,0,0,0,129,6,41.425143003463745 +7,CUP,SUM,0,0,0,0,0,15,6,29.99735116958618 +7,SPOON,SUM,0,0,0,0,0,228,18,76.04751491546631 +7,,SUM,0,0,0,0,0,372,30,147.47000908851624 +7,, +8,, +8,BOWL,SUM,0,0,0,0,0,11,0,23.25432014465332 +8,CUP,SUM,0,0,0,0,0,36,16,68.9482409954071 +8,SPOON,SUM,0,0,0,0,2,220,10,71.21113395690918 +8,,SUM,0,0,0,0,2,267,26,163.4136950969696 +8,, +9,, +9,BOWL,SUM,0,0,0,0,0,14,2,22.725230932235718 +9,CUP,SUM,0,0,0,0,4,244,23,92.57111692428589 +9,SPOON,SUM,0,0,0,0,0,33,0,30.83648705482483 +9,,SUM,0,0,0,0,4,291,25,146.13283491134644 +9,, +10,, +10,BOWL,SUM,1,0,1,0,10,1565,0,0.0 +10,CUP,SUM,0,0,0,0,0,32,9,26.78466010093689 +10,SPOON,SUM,0,0,0,0,0,37,0,31.022310972213745 +10,,SUM,1,0,1,0,10,1634,9,57.806971073150635 +10,, +11,, +11,BOWL,SUM,1,0,1,0,0,1527,22,0.0 +11,CUP,SUM,1,0,0,1,0,118,57,0.0 +11,SPOON,SUM,0,0,0,0,0,91,2,35.87009906768799 +11,,SUM,2,0,1,1,0,1736,81,35.87009906768799 +11,, +12,, +12,BOWL,SUM,1,0,1,0,14,1458,0,0.0 +12,CUP,SUM,0,0,0,0,0,9,6,23.171905994415283 +12,SPOON,SUM,0,0,0,0,0,167,0,48.98919486999512 +12,,SUM,1,0,1,0,14,1634,6,72.1611008644104 +12,, +13,, +13,BOWL,SUM,0,0,0,0,0,44,7,40.20077610015869 +13,CUP,SUM,0,0,0,0,0,13,5,25.9790940284729 +13,SPOON,SUM,1,0,1,0,20,1546,0,0.0 +13,,SUM,1,0,1,0,20,1603,12,66.17987012863159 +13,, +14,, +14,BOWL,SUM,1,0,1,0,6,560,100,0.0 +14,CUP,SUM,0,0,0,0,0,7,1,22.20274591445923 +14,SPOON,SUM,0,0,0,0,6,546,2,112.99012994766235 +14,,SUM,1,0,1,0,12,1113,103,135.19287586212158 +14,, +15,, +15,BOWL,SUM,1,0,1,0,54,1070,0,0.0 +15,CUP,SUM,0,0,0,0,0,47,13,52.4889190196991 +15,SPOON,SUM,0,0,0,0,0,4,4,31.369938850402832 +15,,SUM,1,0,1,0,54,1121,17,83.85885787010193 +15,, +16,, +16,BOWL,SUM,0,0,0,0,0,94,3,44.847633838653564 +16,CUP,SUM,0,0,0,0,0,9,6,30.476758003234863 +16,SPOON,SUM,0,0,0,0,0,29,0,27.50522804260254 +16,,SUM,0,0,0,0,0,132,9,102.82961988449097 +16,, +17,, +17,BOWL,SUM,1,0,1,0,0,1506,10,0.0 +17,CUP,SUM,0,0,0,0,0,27,7,27.270864009857178 +17,SPOON,SUM,0,0,0,0,0,9,0,27.053350925445557 +17,,SUM,1,0,1,0,0,1542,17,54.324214935302734 +17,, +18,, +18,BOWL,SUM,0,0,0,0,0,868,73,248.74324297904968 +18,CUP,SUM,0,0,0,0,0,17,3,22.600005865097046 +18,SPOON,SUM,0,0,0,0,0,43,1,35.1483199596405 +18,,SUM,0,0,0,0,0,928,77,306.49156880378723 +18,, +19,, +19,BOWL,SUM,0,0,0,0,0,489,2,90.7292549610138 +19,CUP,SUM,0,0,0,0,0,4,0,22.602409839630127 +19,SPOON,SUM,0,0,0,0,0,150,3,49.04216289520264 +19,,SUM,0,0,0,0,0,643,5,162.37382769584656 +19,, +20,, +20,BOWL,SUM,0,0,0,0,0,160,0,41.82300782203674 +20,CUP,SUM,0,0,0,0,0,10,8,34.67860412597656 +20,SPOON,SUM,0,0,0,0,0,49,1,35.60278582572937 +20,,SUM,0,0,0,0,0,219,9,112.10439777374268 +20,, +21,, +21,BOWL,SUM,0,0,0,0,0,185,0,45.43321990966797 +21,CUP,SUM,0,0,0,0,0,51,7,51.16117882728577 +21,SPOON,SUM,0,0,0,0,0,27,0,27.473789930343628 +21,,SUM,0,0,0,0,0,263,7,124.06818866729736 +21,, +22,, +22,BOWL,SUM,0,0,0,0,0,215,5,55.24025797843933 +22,CUP,SUM,0,0,0,0,0,49,10,24.044200897216797 +22,SPOON,SUM,0,0,0,0,0,232,6,62.80417609214783 +22,,SUM,0,0,0,0,0,496,21,142.08863496780396 +22,, +23,, +23,BOWL,SUM,0,0,0,0,0,15,2,23.2233669757843 +23,CUP,SUM,0,0,0,0,0,96,9,48.470731019973755 +23,SPOON,SUM,0,0,0,0,4,16,1,32.244816064834595 +23,,SUM,0,0,0,0,4,127,12,103.93891406059265 +23,, +24,, +24,BOWL,SUM,0,0,0,0,0,5,2,31.191546201705933 +24,CUP,SUM,0,0,0,0,0,60,6,27.284516096115112 +24,SPOON,SUM,0,0,0,0,0,179,5,62.22820711135864 +24,,SUM,0,0,0,0,0,244,13,120.70426940917969 +24,, +25,, +25,BOWL,SUM,0,0,0,0,0,21,5,32.1847460269928 +25,CUP,SUM,0,0,0,0,0,36,9,26.631715059280396 +25,SPOON,SUM,0,0,0,0,0,15,5,35.036012172698975 +25,,SUM,0,0,0,0,0,72,19,93.85247325897217 +25,, +26,, +26,BOWL,SUM,0,0,0,0,0,34,2,27.588361024856567 +26,CUP,SUM,0,0,0,0,0,2,2,21.976444005966187 +26,SPOON,SUM,1,0,1,0,74,1033,0,0.0 +26,,SUM,1,0,1,0,74,1069,4,49.564805030822754 +26,, +27,, +27,BOWL,SUM,0,0,0,0,4,83,2,34.24053907394409 +27,CUP,SUM,0,0,0,0,0,12,9,43.28634691238403 +27,SPOON,SUM,0,0,0,0,0,71,0,35.62949085235596 +27,,SUM,0,0,0,0,4,166,11,113.15637683868408 +27,, +28,, +28,BOWL,SUM,0,0,0,0,0,30,0,23.840081214904785 +28,CUP,SUM,0,0,0,0,32,64,4,61.09874391555786 +28,SPOON,SUM,1,0,1,0,2,1514,10,0.0 +28,,SUM,1,0,1,0,34,1608,14,84.93882513046265 +28,, +29,, +29,BOWL,SUM,0,0,0,0,6,2,0,25.292222023010254 +29,CUP,SUM,0,0,0,0,0,31,6,31.07541799545288 +29,SPOON,SUM,0,0,0,0,2,256,0,63.32618308067322 +29,,SUM,0,0,0,0,8,289,6,119.69382309913635 +29,, +30,, +30,BOWL,SUM,1,0,1,0,2,1562,0,0.0 +30,CUP,SUM,0,0,0,0,0,26,12,55.83215880393982 +30,SPOON,SUM,0,0,0,0,14,482,6,104.25001788139343 +30,,SUM,1,0,1,0,16,2070,18,160.08217668533325 +30,, +31,, +31,BOWL,SUM,0,0,0,0,2,4,0,23.969604969024658 +31,CUP,SUM,0,0,0,0,0,41,14,68.56855010986328 +31,SPOON,SUM,0,0,0,0,0,162,0,48.54810309410095 +31,,SUM,0,0,0,0,2,207,14,141.0862581729889 +31,, +32,, +32,BOWL,SUM,0,0,0,0,2,13,7,40.22948098182678 +32,CUP,SUM,0,0,0,0,8,35,33,125.23903799057007 +32,SPOON,SUM,0,0,0,0,0,324,6,80.58758401870728 +32,,SUM,0,0,0,0,10,372,46,246.05610299110413 +32,, +33,, +33,BOWL,SUM,0,0,0,0,0,122,4,45.23867106437683 +33,CUP,SUM,0,0,0,0,0,77,4,44.27382016181946 +33,SPOON,SUM,0,0,0,0,2,131,0,41.43948817253113 +33,,SUM,0,0,0,0,2,330,8,130.95197939872742 +33,, +34,, +34,BOWL,SUM,0,0,0,0,2,10,4,28.520137071609497 +34,CUP,SUM,0,0,0,0,0,37,13,47.63567399978638 +34,SPOON,SUM,0,0,0,0,6,338,28,110.08585000038147 +34,,SUM,0,0,0,0,8,385,45,186.24166107177734 +34,, +35,, +35,BOWL,SUM,0,0,0,0,0,198,1,53.077402114868164 +35,CUP,SUM,1,0,1,0,0,247,109,0.0 +35,SPOON,SUM,0,0,0,0,0,36,1,35.80347394943237 +35,,SUM,1,0,1,0,0,481,111,88.88087606430054 +35,, +36,, +36,BOWL,SUM,0,0,0,0,0,47,2,35.38469910621643 +36,CUP,SUM,0,0,0,0,4,26,7,23.958658933639526 +36,SPOON,SUM,0,0,0,0,0,393,5,85.01555800437927 +36,,SUM,0,0,0,0,4,466,14,144.35891604423523 +36,, +37,, +37,BOWL,SUM,0,0,0,0,2,15,1,28.049306869506836 +37,CUP,SUM,0,0,0,0,0,122,19,102.66886281967163 +37,SPOON,SUM,0,0,0,0,2,118,5,49.55531287193298 +37,,SUM,0,0,0,0,4,255,25,180.27348256111145 +37,, +38,, +38,BOWL,SUM,0,0,0,0,0,48,4,40.60070085525513 +38,CUP,SUM,1,0,1,0,18,915,55,0.0 +38,SPOON,SUM,0,0,0,0,6,4,0,27.965167999267578 +38,,SUM,1,0,1,0,24,967,59,68.5658688545227 +38,, +39,, +39,BOWL,SUM,0,0,0,0,4,444,37,138.70536279678345 +39,CUP,SUM,0,0,0,0,0,17,0,21.77646517753601 +39,SPOON,SUM,0,0,0,0,32,41,0,53.294955015182495 +39,,SUM,0,0,0,0,36,502,37,213.77678298950195 +39,, +40,, +40,BOWL,SUM,1,0,1,0,6,1499,10,0.0 +40,CUP,SUM,1,0,1,0,0,342,112,0.0 +40,SPOON,SUM,0,0,0,0,0,0,1,31.21648597717285 +40,,SUM,2,0,2,0,6,1841,123,31.21648597717285 +40,, +41,, +41,BOWL,SUM,0,0,0,0,2,82,0,33.50880289077759 +41,CUP,SUM,1,0,0,1,4,342,58,0.0 +41,SPOON,SUM,0,0,0,0,2,7,2,27.523607969284058 +41,,SUM,1,0,0,1,8,431,60,61.032410860061646 +41,, +42,, +42,BOWL,SUM,0,0,0,0,0,10,3,29.03767991065979 +42,CUP,SUM,1,0,1,0,0,439,107,0.0 +42,SPOON,SUM,0,0,0,0,0,4,0,26.922838926315308 +42,,SUM,1,0,1,0,0,453,110,55.9605188369751 +42,, +43,, +43,BOWL,SUM,1,0,1,0,2,1394,20,0.0 +43,CUP,SUM,0,0,0,0,4,30,8,31.88415002822876 +43,SPOON,SUM,0,0,0,0,0,316,14,86.6039080619812 +43,,SUM,1,0,1,0,6,1740,42,118.48805809020996 +43,, +44,, +44,BOWL,SUM,1,0,1,0,0,1587,0,0.0 +44,CUP,SUM,0,0,0,0,112,249,13,146.7496931552887 +44,SPOON,SUM,0,0,0,0,0,392,2,89.63404822349548 +44,,SUM,1,0,1,0,112,2228,15,236.38374137878418 +44,, +45,, +45,BOWL,SUM,0,0,0,0,0,79,7,48.9057080745697 +45,CUP,SUM,0,0,0,0,0,34,20,88.87102794647217 +45,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +45,,SUM,1,0,1,0,0,1694,27,137.77673602104187 +45,, +46,, +46,BOWL,SUM,1,0,1,0,10,1466,0,0.0 +46,CUP,SUM,0,0,0,0,0,9,4,30.53198504447937 +46,SPOON,SUM,0,0,0,0,0,14,19,69.0707471370697 +46,,SUM,1,0,1,0,10,1489,23,99.60273218154907 +46,, +47,, +47,BOWL,SUM,0,0,0,0,0,22,4,27.93070697784424 +47,CUP,SUM,1,0,1,0,16,618,77,0.0 +47,SPOON,SUM,0,0,0,0,0,102,0,40.57600402832031 +47,,SUM,1,0,1,0,16,742,81,68.50671100616455 +47,, +48,, +48,BOWL,SUM,0,0,0,0,0,3,0,23.98958706855774 +48,CUP,SUM,0,0,0,0,0,15,4,30.195101976394653 +48,SPOON,SUM,0,0,0,0,0,23,1,31.532824993133545 +48,,SUM,0,0,0,0,0,41,5,85.71751403808594 +48,, +49,, +49,BOWL,SUM,0,0,0,0,2,6,0,23.754812002182007 +49,CUP,SUM,0,0,0,0,0,11,14,38.90619492530823 +49,SPOON,SUM,0,0,0,0,0,185,2,50.37425398826599 +49,,SUM,0,0,0,0,2,202,16,113.03526091575623 +49,, +50,, +50,BOWL,SUM,0,0,0,0,0,62,7,57.091618061065674 +50,CUP,SUM,0,0,0,0,0,0,3,22.91811180114746 +50,SPOON,SUM,0,0,0,0,0,5,1,31.16352915763855 +50,,SUM,0,0,0,0,0,67,11,111.17325901985168 +50,, +51,, +51,BOWL,SUM,0,0,0,0,0,65,8,38.065502882003784 +51,CUP,SUM,0,0,0,0,0,100,5,41.1985068321228 +51,SPOON,SUM,0,0,0,0,10,107,3,53.44827103614807 +51,,SUM,0,0,0,0,10,272,16,132.71228075027466 +51,, +52,, +52,BOWL,SUM,0,0,0,0,12,43,13,56.83330011367798 +52,CUP,SUM,0,0,0,0,0,29,9,56.77674698829651 +52,SPOON,SUM,0,0,0,0,2,326,3,76.78422093391418 +52,,SUM,0,0,0,0,14,398,25,190.39426803588867 +52,, +53,, +53,BOWL,SUM,0,0,0,0,0,152,4,46.23827004432678 +53,CUP,SUM,0,0,0,0,0,12,5,22.953441858291626 +53,SPOON,SUM,0,0,0,0,0,19,2,35.26072096824646 +53,,SUM,0,0,0,0,0,183,11,104.45243287086487 +53,, +54,, +54,BOWL,SUM,0,0,0,0,10,23,0,31.164716005325317 +54,CUP,SUM,0,0,0,0,0,82,8,52.81958508491516 +54,SPOON,SUM,1,0,1,0,44,1195,6,0.0 +54,,SUM,1,0,1,0,54,1300,14,83.98430109024048 +54,, +55,, +55,BOWL,SUM,0,0,0,0,0,23,11,56.92866396903992 +55,CUP,SUM,0,0,0,0,8,14,8,37.789658069610596 +55,SPOON,SUM,0,0,0,0,0,294,16,85.72477078437805 +55,,SUM,0,0,0,0,8,331,35,180.44309282302856 +55,, +56,, +56,BOWL,SUM,0,0,0,0,0,162,9,51.7566819190979 +56,CUP,SUM,0,0,0,0,0,6,8,39.26250195503235 +56,SPOON,SUM,0,0,0,0,0,39,6,36.752464056015015 +56,,SUM,0,0,0,0,0,207,23,127.77164793014526 +56,, +57,, +57,BOWL,SUM,0,0,0,0,0,11,2,31.902503967285156 +57,CUP,SUM,0,0,0,0,0,10,2,30.358453035354614 +57,SPOON,SUM,0,0,0,0,0,147,1,45.34092092514038 +57,,SUM,0,0,0,0,0,168,5,107.60187792778015 +57,, +58,, +58,BOWL,SUM,1,0,1,0,0,1309,38,0.0 +58,CUP,SUM,0,0,0,0,0,29,0,23.59206795692444 +58,SPOON,SUM,0,0,0,0,2,3,0,28.24557113647461 +58,,SUM,1,0,1,0,2,1341,38,51.83763909339905 +58,, +59,, +59,BOWL,SUM,1,0,1,0,0,1526,14,0.0 +59,CUP,SUM,0,0,0,0,2,14,5,27.47615098953247 +59,SPOON,SUM,0,0,0,0,4,207,3,59.687674045562744 +59,,SUM,1,0,1,0,6,1747,22,87.16382503509521 +59,, +60,, +60,BOWL,SUM,1,0,1,0,0,1566,4,0.0 +60,CUP,SUM,0,0,0,0,0,36,9,52.65007281303406 +60,SPOON,SUM,0,0,0,0,0,109,0,40.99325203895569 +60,,SUM,1,0,1,0,0,1711,13,93.64332485198975 +60,, +61,, +61,BOWL,SUM,0,0,0,0,2,57,0,28.921761989593506 +61,CUP,SUM,0,0,0,0,0,27,11,35.73714900016785 +61,SPOON,SUM,1,0,1,0,2,1757,0,0.0 +61,,SUM,1,0,1,0,4,1841,11,64.65891098976135 +61,, +62,, +62,BOWL,SUM,0,0,0,0,0,96,3,37.174643993377686 +62,CUP,SUM,0,0,0,0,4,88,13,63.65860390663147 +62,SPOON,SUM,0,0,0,0,0,14,1,31.518420934677124 +62,,SUM,0,0,0,0,4,198,17,132.35166883468628 +62,, +63,, +63,BOWL,SUM,1,0,1,0,12,1470,0,0.0 +63,CUP,SUM,0,0,0,0,0,40,6,40.793859004974365 +63,SPOON,SUM,0,0,0,0,0,50,4,40.79669809341431 +63,,SUM,1,0,1,0,12,1560,10,81.59055709838867 +63,, +64,, +64,BOWL,SUM,1,0,1,0,0,1499,10,0.0 +64,CUP,SUM,0,0,0,0,0,23,16,81.21617388725281 +64,SPOON,SUM,0,0,0,0,0,121,4,48.98526906967163 +64,,SUM,1,0,1,0,0,1643,30,130.20144295692444 +64,, +65,, +65,BOWL,SUM,1,0,1,0,12,1363,10,0.0 +65,CUP,SUM,0,0,0,0,0,41,16,41.37100791931152 +65,SPOON,SUM,0,0,0,0,2,641,0,117.87409400939941 +65,,SUM,1,0,1,0,14,2045,26,159.24510192871094 +65,, +66,, +66,BOWL,SUM,1,0,1,0,0,1414,22,0.0 +66,CUP,SUM,0,0,0,0,0,32,14,78.03624510765076 +66,SPOON,SUM,0,0,0,0,2,293,0,69.14987778663635 +66,,SUM,1,0,1,0,2,1739,36,147.1861228942871 +66,, +67,, +67,BOWL,SUM,0,0,0,0,0,17,0,24.166640996932983 +67,CUP,SUM,0,0,0,0,0,45,16,49.03142285346985 +67,SPOON,SUM,0,0,0,0,0,1406,1,233.97831797599792 +67,,SUM,0,0,0,0,0,1468,17,307.17638182640076 +67,, +68,, +68,BOWL,SUM,0,0,0,0,0,68,3,33.51487708091736 +68,CUP,SUM,0,0,0,0,8,29,4,29.13077998161316 +68,SPOON,SUM,1,0,1,0,10,1430,22,0.0 +68,,SUM,1,0,1,0,18,1527,29,62.64565706253052 +68,, +69,, +69,BOWL,SUM,1,0,1,0,0,957,64,0.0 +69,CUP,SUM,1,0,1,0,0,256,111,0.0 +69,SPOON,SUM,0,0,0,0,0,1,5,35.89097881317139 +69,,SUM,2,0,2,0,0,1214,180,35.89097881317139 +69,, +70,, +70,BOWL,SUM,0,0,0,0,2,66,4,49.32493495941162 +70,CUP,SUM,0,0,0,0,10,213,10,70.7052948474884 +70,SPOON,SUM,0,0,0,0,0,124,1,48.27025008201599 +70,,SUM,0,0,0,0,12,403,15,168.30047988891602 +70,, +71,, +71,BOWL,SUM,0,0,0,0,2,36,1,29.766983032226563 +71,CUP,SUM,0,0,0,0,0,16,6,30.965780019760132 +71,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +71,,SUM,1,0,1,0,2,1633,7,60.732763051986694 +71,, +72,, +72,BOWL,SUM,0,0,0,0,0,57,1,32.14797902107239 +72,CUP,SUM,0,0,0,0,8,40,9,54.931636095047 +72,SPOON,SUM,0,0,0,0,4,25,0,29.54176115989685 +72,,SUM,0,0,0,0,12,122,10,116.62137627601624 +72,, +73,, +73,BOWL,SUM,0,0,0,0,0,39,1,29.006680965423584 +73,CUP,SUM,0,0,0,0,0,15,2,31.05378007888794 +73,SPOON,SUM,0,0,0,0,0,704,1,128.59890294075012 +73,,SUM,0,0,0,0,0,758,4,188.65936398506165 +73,, +74,, +74,BOWL,SUM,0,0,0,0,0,30,2,32.5689799785614 +74,CUP,SUM,0,0,0,0,2,4,5,27.832656145095825 +74,SPOON,SUM,0,0,0,0,10,220,0,62.53009295463562 +74,,SUM,0,0,0,0,12,254,7,122.93172907829285 +74,, +75,, +75,BOWL,SUM,0,0,0,0,0,700,34,164.24085402488708 +75,CUP,SUM,0,0,0,0,0,16,4,22.236627101898193 +75,SPOON,SUM,0,0,0,0,0,128,1,49.449849128723145 +75,,SUM,0,0,0,0,0,844,39,235.92733025550842 +75,, +76,, +76,BOWL,SUM,0,0,0,0,0,215,5,63.36816596984863 +76,CUP,SUM,0,0,0,0,0,17,10,23.787545919418335 +76,SPOON,SUM,0,0,0,0,0,366,42,144.6799499988556 +76,,SUM,0,0,0,0,0,598,57,231.83566188812256 +76,, +77,, +77,BOWL,SUM,0,0,0,0,20,87,2,54.136420011520386 +77,CUP,SUM,0,0,0,0,0,68,35,76.35101509094238 +77,SPOON,SUM,0,0,0,0,0,10,1,32.30602717399597 +77,,SUM,0,0,0,0,20,165,38,162.79346227645874 +77,, +78,, +78,BOWL,SUM,0,0,0,0,0,145,7,56.624794006347656 +78,CUP,SUM,0,0,0,0,0,12,15,40.25344491004944 +78,SPOON,SUM,0,0,0,0,2,272,6,69.82343006134033 +78,,SUM,0,0,0,0,2,429,28,166.70166897773743 +78,, +79,, +79,BOWL,SUM,0,0,0,0,0,37,1,28.69696879386902 +79,CUP,SUM,0,0,0,0,8,31,2,29.506616830825806 +79,SPOON,SUM,0,0,0,0,0,410,18,116.57186007499695 +79,,SUM,0,0,0,0,8,478,21,174.77544569969177 +79,, +80,, +80,BOWL,SUM,0,0,0,0,46,36,0,58.52913808822632 +80,CUP,SUM,0,0,0,0,0,26,9,48.61521506309509 +80,SPOON,SUM,0,0,0,0,6,1019,26,202.5460250377655 +80,,SUM,0,0,0,0,52,1081,35,309.6903781890869 +80,, +81,, +81,BOWL,SUM,1,1,0,0,160,1228,0,0.0 +81,CUP,SUM,0,0,0,0,0,90,5,33.04944896697998 +81,SPOON,SUM,0,0,0,0,2,50,1,37.84121918678284 +81,,SUM,1,1,0,0,162,1368,6,70.89066815376282 +81,, +82,, +82,BOWL,SUM,0,0,0,0,58,74,7,82.6392149925232 +82,CUP,SUM,0,0,0,0,0,71,16,54.12295579910278 +82,SPOON,SUM,0,0,0,0,0,157,2,57.48927283287048 +82,,SUM,0,0,0,0,58,302,25,194.25144362449646 +82,, +83,, +83,BOWL,SUM,0,0,0,0,0,7,1,28.368406057357788 +83,CUP,SUM,0,0,0,0,0,29,17,61.51063299179077 +83,SPOON,SUM,1,0,1,0,0,1567,10,0.0 +83,,SUM,1,0,1,0,0,1603,28,89.87903904914856 +83,, +84,, +84,BOWL,SUM,0,0,0,0,0,32,2,24.495734930038452 +84,CUP,SUM,1,0,0,1,0,170,51,0.0 +84,SPOON,SUM,0,0,0,0,2,483,7,124.3767819404602 +84,,SUM,1,0,0,1,2,685,60,148.87251687049866 +84,, +85,, +85,BOWL,SUM,0,0,0,0,0,170,0,46.99120116233826 +85,CUP,SUM,1,0,1,0,0,143,112,0.0 +85,SPOON,SUM,0,0,0,0,0,250,0,59.767083168029785 +85,,SUM,1,0,1,0,0,563,112,106.75828433036804 +85,, +86,, +86,BOWL,SUM,0,0,0,0,0,89,3,46.43712306022644 +86,CUP,SUM,1,0,1,0,0,156,112,0.0 +86,SPOON,SUM,0,0,0,0,0,13,8,40.36497497558594 +86,,SUM,1,0,1,0,0,258,123,86.80209803581238 +86,, +87,, +87,BOWL,SUM,0,0,0,0,0,554,41,154.76834392547607 +87,CUP,SUM,0,0,0,0,0,19,10,44.20832800865173 +87,SPOON,SUM,0,0,0,0,0,41,2,40.231353998184204 +87,,SUM,0,0,0,0,0,614,53,239.208025932312 +87,, +88,, +88,BOWL,SUM,0,0,0,0,0,20,1,28.48821711540222 +88,CUP,SUM,0,0,0,0,0,35,17,77.32331490516663 +88,SPOON,SUM,0,0,0,0,2,5,6,36.21146607398987 +88,,SUM,0,0,0,0,2,60,24,142.02299809455872 +88,, +89,, +89,BOWL,SUM,0,0,0,0,0,5,0,23.904149055480957 +89,CUP,SUM,1,0,1,0,0,183,111,0.0 +89,SPOON,SUM,0,0,0,0,0,1024,9,189.91921401023865 +89,,SUM,1,0,1,0,0,1212,120,213.8233630657196 +89,, +90,, +90,BOWL,SUM,1,0,1,0,0,1595,0,0.0 +90,CUP,SUM,0,0,0,0,2,66,13,79.37936401367188 +90,SPOON,SUM,0,0,0,0,0,35,1,36.80947518348694 +90,,SUM,1,0,1,0,2,1696,14,116.18883919715881 +90,, +91,, +91,BOWL,SUM,1,0,1,0,2,1533,8,0.0 +91,CUP,SUM,0,0,0,0,0,48,17,69.31875705718994 +91,SPOON,SUM,0,0,0,0,0,388,7,90.95109796524048 +91,,SUM,1,0,1,0,2,1969,32,160.26985502243042 +91,, +92,, +92,BOWL,SUM,0,0,0,0,0,161,1,47.02493190765381 +92,CUP,SUM,0,0,0,0,0,26,3,22.702583074569702 +92,SPOON,SUM,0,0,0,0,0,224,0,58.13044285774231 +92,,SUM,0,0,0,0,0,411,4,127.85795783996582 +92,, +93,, +93,BOWL,SUM,0,0,0,0,0,8,4,39.392411947250366 +93,CUP,SUM,0,0,0,0,0,7,7,30.934212923049927 +93,SPOON,SUM,0,0,0,0,0,117,2,48.98847794532776 +93,,SUM,0,0,0,0,0,132,13,119.31510281562805 +93,, +94,, +94,BOWL,SUM,0,0,0,0,0,51,3,32.50670003890991 +94,CUP,SUM,0,0,0,0,0,15,3,26.182156801223755 +94,SPOON,SUM,1,0,1,0,2,1578,0,0.0 +94,,SUM,1,0,1,0,2,1644,6,58.68885684013367 +94,, +95,, +95,BOWL,SUM,0,0,0,0,2,154,0,42.309804916381836 +95,CUP,SUM,0,0,0,0,0,4,6,22.6527578830719 +95,SPOON,SUM,0,0,0,0,0,23,0,28.17968201637268 +95,,SUM,0,0,0,0,2,181,6,93.14224481582642 +95,, +96,, +96,BOWL,SUM,0,0,0,0,0,65,7,37.92928409576416 +96,CUP,SUM,1,0,1,0,0,390,109,0.0 +96,SPOON,SUM,0,0,0,0,0,29,2,27.827924966812134 +96,,SUM,1,0,1,0,0,484,118,65.7572090625763 +96,, +97,, +97,BOWL,SUM,0,0,0,0,2,104,27,80.11770987510681 +97,CUP,SUM,0,0,0,0,0,28,21,69.51396298408508 +97,SPOON,SUM,0,0,0,0,8,1057,0,182.29799890518188 +97,,SUM,0,0,0,0,10,1189,48,331.9296717643738 +97,, +98,, +98,BOWL,SUM,0,0,0,0,0,109,18,66.83558297157288 +98,CUP,SUM,0,0,0,0,0,23,4,22.239507913589478 +98,SPOON,SUM,0,0,0,0,0,139,6,54.55437684059143 +98,,SUM,0,0,0,0,0,271,28,143.62946772575378 +98,, +99,, +99,BOWL,SUM,0,0,0,0,0,16,4,40.38495492935181 +99,CUP,SUM,0,0,0,0,0,9,10,38.77251982688904 +99,SPOON,SUM,0,0,0,0,0,75,3,42.021337032318115 +99,,SUM,0,0,0,0,0,100,17,121.17881178855896 +99,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_new_var_data_offset_20.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_new_var_data_offset_20.csv new file mode 100644 index 0000000000..d4305442c6 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_new_var_data_offset_20.csv @@ -0,0 +1,543 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,42,8,20.9493629932 +0,CUP,SUM,1,0,0,1,0,355,61,0 +0,SPOON,SUM,0,0,0,0,0,68,5,22.3206379414 +0,,SUM,1,0,0,1,0,465,74,43.2700009346 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,0,21,6,15.3941979408 +1,CUP,SUM,0,0,0,0,0,7,6,10.1462330818 +1,SPOON,SUM,1,0,1,0,2,1583,0,0 +1,,SUM,1,0,1,0,2,1611,12,25.5404310226 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,10,243,14,38.5037341118 +2,CUP,SUM,0,0,0,0,0,17,8,10.8666069508 +2,SPOON,SUM,0,0,0,0,6,33,0,17.6080420017 +2,,SUM,0,0,0,0,16,293,22,66.9783830643 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,0,4,0,11.4423480034 +3,CUP,SUM,0,0,0,0,0,193,22,49.5121378899 +3,SPOON,SUM,0,0,0,0,2,152,2,27.3079140186 +3,,SUM,0,0,0,0,2,349,24,88.2623999119 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,82,4,17.5296838284 +4,CUP,SUM,1,0,1,0,0,157,112,0 +4,SPOON,SUM,0,0,0,0,0,226,1,29.5569648743 +4,,SUM,1,0,1,0,0,465,117,47.0866487026 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,0,23,0,12.1671879292 +5,CUP,SUM,0,0,0,0,2,31,3,11.9213690758 +5,SPOON,SUM,0,0,0,0,0,21,1,16.8182640076 +5,,SUM,0,0,0,0,2,75,4,40.9068210125 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,0,17,1,13.5321700573 +6,CUP,SUM,0,0,0,0,0,288,42,67.5762770176 +6,SPOON,SUM,0,0,0,0,0,113,2,24.0821909904 +6,,SUM,0,0,0,0,0,418,45,105.1906380653 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,0,48,20,27.3744280338 +7,CUP,SUM,1,0,0,1,0,388,69,0 +7,SPOON,SUM,0,0,0,0,0,56,1,17.6448638439 +7,,SUM,1,0,0,1,0,492,90,45.0192918777 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,0,62,0,14.2441129684 +8,CUP,SUM,0,0,0,0,0,11,2,9.964910984 +8,SPOON,SUM,0,0,0,0,0,106,1,20.1443870068 +8,,SUM,0,0,0,0,0,179,3,44.3534109592 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,42,8,20.9187588692 +9,CUP,SUM,1,0,0,1,0,355,61,0 +9,SPOON,SUM,0,0,0,0,0,68,5,22.2073619366 +9,,SUM,1,0,0,1,0,465,74,43.1261208057 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,21,6,15.1833670139 +10,CUP,SUM,0,0,0,0,0,7,6,10.139605999 +10,SPOON,SUM,1,0,1,0,2,1583,0,0 +10,,SUM,1,0,1,0,2,1611,12,25.3229730129 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,10,243,14,38.2106609344 +11,CUP,SUM,0,0,0,0,0,17,8,10.9128890038 +11,SPOON,SUM,0,0,0,0,6,33,0,17.7877409458 +11,,SUM,0,0,0,0,16,293,22,66.911290884 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,0,4,0,11.4186069965 +12,CUP,SUM,0,0,0,0,0,193,22,48.7314639091 +12,SPOON,SUM,0,0,0,0,2,152,2,27.0904459953 +12,,SUM,0,0,0,0,2,349,24,87.240516901 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,0,82,4,17.4711661339 +13,CUP,SUM,1,0,1,0,0,157,112,0 +13,SPOON,SUM,0,0,0,0,0,226,1,28.9131419659 +13,,SUM,1,0,1,0,0,465,117,46.3843080997 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,0,23,0,12.2122030258 +14,CUP,SUM,0,0,0,0,2,31,3,11.5156087875 +14,SPOON,SUM,0,0,0,0,0,21,1,16.5796940327 +14,,SUM,0,0,0,0,2,75,4,40.307505846 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,0,17,1,13.4523880482 +15,CUP,SUM,0,0,0,0,0,288,42,66.5650660992 +15,SPOON,SUM,0,0,0,0,0,113,2,24.1531200409 +15,,SUM,0,0,0,0,0,418,45,104.1705741882 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,48,20,27.3086180687 +16,CUP,SUM,1,0,0,1,0,388,69,0 +16,SPOON,SUM,0,0,0,0,0,56,1,17.6314709187 +16,,SUM,1,0,0,1,0,492,90,44.9400889874 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,0,62,0,13.8872559071 +17,CUP,SUM,0,0,0,0,0,11,2,10.0720000267 +17,SPOON,SUM,0,0,0,0,0,106,1,19.9248149395 +17,,SUM,0,0,0,0,0,179,3,43.8840708733 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,0,18,1,13.1620719433 +18,CUP,SUM,1,0,1,0,0,136,111,0 +18,SPOON,SUM,0,0,0,0,0,14,0,14.9089770317 +18,,SUM,1,0,1,0,0,168,112,28.071048975 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,2,7,0,12.213891983 +19,CUP,SUM,0,0,0,0,2,14,1,12.2621200085 +19,SPOON,SUM,0,0,0,0,0,58,0,17.2409610748 +19,,SUM,0,0,0,0,4,79,1,41.7169730663 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,0,16,0,11.3114171028 +20,CUP,SUM,1,0,1,0,0,131,111,0 +20,SPOON,SUM,0,0,0,0,0,68,5,21.0632219315 +20,,SUM,1,0,1,0,0,215,116,32.3746390343 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,56,0,12.7108790874 +21,CUP,SUM,0,0,0,0,0,118,15,33.6792700291 +21,SPOON,SUM,0,0,0,0,0,20,4,16.9341180325 +21,,SUM,0,0,0,0,0,194,19,63.324267149 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,2,60,4,14.8934350014 +22,CUP,SUM,0,0,0,0,0,20,4,10.2234230042 +22,SPOON,SUM,0,0,0,0,0,7,6,18.164345026 +22,,SUM,0,0,0,0,2,87,14,43.2812030315 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,13,2,11.7976169586 +23,CUP,SUM,0,0,0,0,0,88,20,29.7222030163 +23,SPOON,SUM,1,0,1,0,0,1582,0,0 +23,,SUM,1,0,1,0,0,1683,22,41.5198199749 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,0,44,2,14.0925149918 +24,CUP,SUM,1,0,0,1,0,438,56,0 +24,SPOON,SUM,0,0,0,0,0,15,11,23.3071870804 +24,,SUM,1,0,0,1,0,497,69,37.3997020721 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,0,22,0,11.9444010258 +25,CUP,SUM,0,0,0,0,0,3,3,11.3979489803 +25,SPOON,SUM,0,0,0,0,0,12,0,14.4704930782 +25,,SUM,0,0,0,0,0,37,3,37.8128430843 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,0,83,4,17.5161268711 +26,CUP,SUM,1,0,0,1,0,364,65,0 +26,SPOON,SUM,0,0,0,0,0,2,0,14.9750351906 +26,,SUM,1,0,0,1,0,449,69,32.4911620617 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,0,41,2,13.7409229279 +27,CUP,SUM,0,0,0,0,2,4,2,10.0259981155 +27,SPOON,SUM,0,0,0,0,2,84,2,20.3406088352 +27,,SUM,0,0,0,0,4,129,6,44.1075298786 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,0,45,0,13.6519749165 +28,CUP,SUM,1,0,1,0,0,186,109,0 +28,SPOON,SUM,0,0,0,0,2,99,0,21.8176138401 +28,,SUM,1,0,1,0,2,330,109,35.4695887566 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,0,16,0,11.6585929394 +29,CUP,SUM,0,0,0,0,6,19,1,12.2400660515 +29,SPOON,SUM,0,0,0,0,0,17,2,15.5552079678 +29,,SUM,0,0,0,0,6,52,3,39.4538669586 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,6,5,1,15.0175828934 +30,CUP,SUM,0,0,0,0,0,105,11,26.2494578362 +30,SPOON,SUM,0,0,0,0,0,98,0,21.0753798485 +30,,SUM,0,0,0,0,6,208,12,62.342420578 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,0,260,28,41.9228610992 +31,CUP,SUM,1,0,1,0,2,239,106,0 +31,SPOON,SUM,0,0,0,0,0,421,0,41.1969311237 +31,,SUM,1,0,1,0,2,920,134,83.119792223 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,0,12,5,15.2638380527 +32,CUP,SUM,0,0,0,0,0,13,2,9.8579931259 +32,SPOON,SUM,0,0,0,0,0,44,1,17.1209998131 +32,,SUM,0,0,0,0,0,69,8,42.2428309917 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,43,0,12.7417690754 +33,CUP,SUM,0,0,0,0,0,40,4,12.2944779396 +33,SPOON,SUM,0,0,0,0,0,59,0,17.7586131096 +33,,SUM,0,0,0,0,0,142,4,42.7948601246 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,0,9,0,11.3618121147 +34,CUP,SUM,1,0,0,1,0,346,51,0 +34,SPOON,SUM,0,0,0,0,0,51,1,18.7836351395 +34,,SUM,1,0,0,1,0,406,52,30.1454472542 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,0,87,5,17.7306699753 +35,CUP,SUM,0,0,0,0,0,23,2,10.2647149563 +35,SPOON,SUM,0,0,0,0,0,57,3,22.0693531036 +35,,SUM,0,0,0,0,0,167,10,50.0647380352 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,6,36,0,14.6340799332 +36,CUP,SUM,0,0,0,0,0,2,7,10.6965048313 +36,SPOON,SUM,1,0,1,0,0,1601,0,0 +36,,SUM,1,0,1,0,6,1639,7,25.3305847645 +36,,,,,,,,,, +37,,,,,,,,,, +37,BOWL,SUM,1,0,1,0,6,634,96,0 +37,CUP,SUM,0,0,0,0,0,99,15,22.932653904 +37,SPOON,SUM,0,0,0,0,0,82,2,23.0572681427 +37,,SUM,1,0,1,0,6,815,113,45.9899220467 +37,,,,,,,,,, +38,,,,,,,,,, +38,BOWL,SUM,0,0,0,0,6,13,0,14.6833031178 +38,CUP,SUM,0,0,0,0,0,175,41,65.293241024 +38,SPOON,SUM,0,0,0,0,0,160,1,25.3268690109 +38,,SUM,0,0,0,0,6,348,42,105.3034131527 +38,,,,,,,,,, +39,,,,,,,,,, +39,BOWL,SUM,0,0,0,0,6,9,0,13.8533279896 +39,CUP,SUM,0,0,0,0,0,73,13,22.9247658253 +39,SPOON,SUM,0,0,0,0,0,476,1,44.7347400188 +39,,SUM,0,0,0,0,6,558,14,81.5128338337 +39,,,,,,,,,, +40,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,0,13,4,13.5359368324 +40,CUP,SUM,0,0,0,0,0,15,5,11.6847980022 +40,SPOON,SUM,0,0,0,0,0,23,0,15.3073678017 +40,,SUM,0,0,0,0,0,51,9,40.5281026363 +40,,,,,,,,,, +41,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,2,34,1,14.2770318985 +41,CUP,SUM,1,0,1,0,0,103,112,0 +41,SPOON,SUM,0,0,0,0,0,3,2,17.4144580364 +41,,SUM,1,0,1,0,2,140,115,31.6914899349 +41,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,18,129,2,26.3447508812 +42,CUP,SUM,1,0,0,1,0,286,60,0 +42,SPOON,SUM,0,0,0,0,0,53,0,17.5928368568 +42,,SUM,1,0,0,1,18,468,62,43.937587738 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,2,22,0,12.4556410313 +43,CUP,SUM,1,0,1,0,2,194,109,0 +43,SPOON,SUM,0,0,0,0,0,21,0,15.1262118816 +43,,SUM,1,0,1,0,4,237,109,27.5818529129 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,8,13,4,16.9012548923 +44,CUP,SUM,0,0,0,0,0,15,4,10.0680859089 +44,SPOON,SUM,0,0,0,0,0,25,14,25.5012910366 +44,,SUM,0,0,0,0,8,53,22,52.4706318378 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,6,81,0,17.8628180027 +45,CUP,SUM,0,0,0,0,0,6,5,10.1154952049 +45,SPOON,SUM,1,0,1,0,52,1140,0,0 +45,,SUM,1,0,1,0,58,1227,5,27.9783132076 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,0,107,16,25.3941428661 +46,CUP,SUM,0,0,0,0,0,6,5,9.8772630692 +46,SPOON,SUM,0,0,0,0,0,153,1,24.7701358795 +46,,SUM,0,0,0,0,0,266,22,60.0415418148 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,0,0,0,0,0,25,6,15.2226731777 +47,CUP,SUM,0,0,0,0,2,333,34,62.6258468628 +47,SPOON,SUM,0,0,0,0,0,275,1,32.1676549911 +47,,SUM,0,0,0,0,2,633,41,110.0161750317 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,30,24,0,24.6128849983 +48,CUP,SUM,0,0,0,0,0,21,5,11.5203619003 +48,SPOON,SUM,0,0,0,0,0,5,0,14.8386938572 +48,,SUM,0,0,0,0,30,50,5,50.9719407558 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,0,14,0,11.4757549763 +49,CUP,SUM,0,0,0,0,2,8,2,9.9621369839 +49,SPOON,SUM,0,0,0,0,2,6,0,15.681016922 +49,,SUM,0,0,0,0,4,28,2,37.1189088821 +49,,,,,,,,,, +50,,,,,,,,,, +50,BOWL,SUM,0,0,0,0,6,20,4,16.6787540913 +50,CUP,SUM,0,0,0,0,0,33,2,10.3158888817 +50,SPOON,SUM,0,0,0,0,0,33,0,16.6401209831 +50,,SUM,0,0,0,0,6,86,6,43.6347639561 +50,,,,,,,,,, +51,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,0,17,0,11.4624547958 +51,CUP,SUM,0,0,0,0,0,5,5,9.8253378868 +51,SPOON,SUM,0,0,0,0,2,141,2,26.7788300514 +51,,SUM,0,0,0,0,2,163,7,48.0666227341 +51,,,,,,,,,, +52,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,4,17,10,19.6124329567 +52,CUP,SUM,0,0,0,0,2,17,7,12.1674859524 +52,SPOON,SUM,0,0,0,0,0,72,0,17.7818479538 +52,,SUM,0,0,0,0,6,106,17,49.5617668629 +52,,,,,,,,,, +53,,,,,,,,,, +53,BOWL,SUM,0,0,0,0,0,19,6,15.2627630234 +53,CUP,SUM,1,0,1,0,6,199,104,0 +53,SPOON,SUM,0,0,0,0,0,208,10,31.6069200039 +53,,SUM,1,0,1,0,6,426,120,46.8696830273 +53,,,,,,,,,, +54,,,,,,,,,, +54,BOWL,SUM,0,0,0,0,0,21,0,11.7477319241 +54,CUP,SUM,0,0,0,0,6,195,32,55.5835371017 +54,SPOON,SUM,0,0,0,0,6,108,12,29.8663971424 +54,,SUM,0,0,0,0,12,324,44,97.1976661682 +54,,,,,,,,,, +55,,,,,,,,,, +55,BOWL,SUM,0,0,0,0,0,60,19,27.4066798687 +55,CUP,SUM,1,0,0,1,0,319,58,0 +55,SPOON,SUM,0,0,0,0,0,18,0,15.0259020329 +55,,SUM,1,0,0,1,0,397,77,42.4325819016 +55,,,,,,,,,, +56,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,0,17,0,11.8760249615 +56,CUP,SUM,0,0,0,0,2,85,15,19.217124939 +56,SPOON,SUM,0,0,0,0,0,66,3,19.6054639816 +56,,SUM,0,0,0,0,2,168,18,50.6986138821 +56,,,,,,,,,, +57,,,,,,,,,, +57,BOWL,SUM,0,0,0,0,6,29,0,13.976913929 +57,CUP,SUM,0,0,0,0,2,20,4,12.1034538746 +57,SPOON,SUM,0,0,0,0,4,41,1,19.6349139214 +57,,SUM,0,0,0,0,12,90,5,45.7152817249 +57,,,,,,,,,, +58,,,,,,,,,, +58,BOWL,SUM,0,0,0,0,2,25,0,13.8126661777 +58,CUP,SUM,1,0,0,1,0,320,62,0 +58,SPOON,SUM,0,0,0,0,0,18,0,15.2128551006 +58,,SUM,1,0,0,1,2,363,62,29.0255212784 +58,,,,,,,,,, +59,,,,,,,,,, +59,BOWL,SUM,0,0,0,0,0,32,6,15.493751049 +59,CUP,SUM,0,0,0,0,0,25,0,10.2737579346 +59,SPOON,SUM,0,0,0,0,0,33,0,15.8074879646 +59,,SUM,0,0,0,0,0,90,6,41.5749969482 +59,,,,,,,,,, +60,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,0,21,0,12.5722980499 +60,CUP,SUM,0,0,0,0,0,24,5,11.0685560703 +60,SPOON,SUM,0,0,0,0,6,72,0,20.7574629784 +60,,SUM,0,0,0,0,6,117,5,44.3983170986 +60,,,,,,,,,, +61,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,0,32,0,12.4640779495 +61,CUP,SUM,1,0,1,0,0,181,112,0 +61,SPOON,SUM,0,0,0,0,0,81,1,19.8327889442 +61,,SUM,1,0,1,0,0,294,113,32.2968668938 +61,,,,,,,,,, +62,,,,,,,,,, +62,BOWL,SUM,0,0,0,0,2,233,30,43.389621973 +62,CUP,SUM,0,0,0,0,0,26,2,10.5806219578 +62,SPOON,SUM,0,0,0,0,0,2,0,14.9261550903 +62,,SUM,0,0,0,0,2,261,32,68.8963990211 +62,,,,,,,,,, +63,,,,,,,,,, +63,BOWL,SUM,0,0,0,0,2,9,3,14.2586128712 +63,CUP,SUM,0,0,0,0,0,3,10,10.2181649208 +63,SPOON,SUM,0,0,0,0,0,66,0,19.4133820534 +63,,SUM,0,0,0,0,2,78,13,43.8901598454 +63,,,,,,,,,, +64,,,,,,,,,, +64,BOWL,SUM,0,0,0,0,0,21,0,12.5398478508 +64,CUP,SUM,0,0,0,0,0,49,12,16.5131249428 +64,SPOON,SUM,0,0,0,0,0,21,4,18.027356863 +64,,SUM,0,0,0,0,0,91,16,47.0803296566 +64,,,,,,,,,, +65,,,,,,,,,, +65,BOWL,SUM,0,0,0,0,0,37,0,12.8490729332 +65,CUP,SUM,1,0,0,1,2,333,61,0 +65,SPOON,SUM,0,0,0,0,2,634,1,56.7427000999 +65,,SUM,1,0,0,1,4,1004,62,69.5917730331 +65,,,,,,,,,, +66,,,,,,,,,, +66,BOWL,SUM,0,0,0,0,0,34,0,13.5691900253 +66,CUP,SUM,0,0,0,0,0,9,4,10.2711019516 +66,SPOON,SUM,0,0,0,0,0,88,6,23.9981119633 +66,,SUM,0,0,0,0,0,131,10,47.8384039402 +66,,,,,,,,,, +67,,,,,,,,,, +67,BOWL,SUM,0,0,0,0,0,31,3,14.3004081249 +67,CUP,SUM,0,0,0,0,8,23,3,14.6106510162 +67,SPOON,SUM,0,0,0,0,0,2,1,16.9380710125 +67,,SUM,0,0,0,0,8,56,7,45.8491301537 +67,,,,,,,,,, +68,,,,,,,,,, +68,BOWL,SUM,0,0,0,0,0,42,8,21.3125829697 +68,CUP,SUM,1,0,0,1,0,355,61,0 +68,SPOON,SUM,0,0,0,0,0,68,5,22.3043379784 +68,,SUM,1,0,0,1,0,465,74,43.616920948 +68,,,,,,,,,, +69,,,,,,,,,, +69,BOWL,SUM,0,0,0,0,0,21,6,15.4916050434 +69,CUP,SUM,0,0,0,0,0,7,6,10.0316388607 +69,SPOON,SUM,1,0,1,0,2,1583,0,0 +69,,SUM,1,0,1,0,2,1611,12,25.5232439041 +69,,,,,,,,,, +70,,,,,,,,,, +70,BOWL,SUM,0,0,0,0,10,243,14,38.9354498386 +70,CUP,SUM,0,0,0,0,0,17,8,10.9507467747 +70,SPOON,SUM,0,0,0,0,6,33,0,18.2367269993 +70,,SUM,0,0,0,0,16,293,22,68.1229236126 +70,,,,,,,,,, +71,,,,,,,,,, +71,BOWL,SUM,0,0,0,0,0,4,0,11.6490969658 +71,CUP,SUM,0,0,0,0,0,193,22,49.7068490982 +71,SPOON,SUM,0,0,0,0,2,152,2,27.6307349205 +71,,SUM,0,0,0,0,2,349,24,88.9866809845 +71,,,,,,,,,, +72,,,,,,,,,, +72,BOWL,SUM,0,0,0,0,0,82,4,17.6313910484 +72,CUP,SUM,1,0,1,0,0,157,112,0 +72,SPOON,SUM,0,0,0,0,0,226,1,29.522217989 +72,,SUM,1,0,1,0,0,465,117,47.1536090374 +72,,,,,,,,,, +73,,,,,,,,,, +73,BOWL,SUM,0,0,0,0,0,23,0,12.1889638901 +73,CUP,SUM,0,0,0,0,2,31,3,11.8147530556 +73,SPOON,SUM,0,0,0,0,0,21,1,16.4688360691 +73,,SUM,0,0,0,0,2,75,4,40.4725530148 +73,,,,,,,,,, +74,,,,,,,,,, +74,BOWL,SUM,0,0,0,0,0,17,1,13.4738790989 +74,CUP,SUM,0,0,0,0,0,288,42,67.6285910606 +74,SPOON,SUM,0,0,0,0,0,113,2,24.2143371105 +74,,SUM,0,0,0,0,0,418,45,105.3168072701 +74,,,,,,,,,, +75,,,,,,,,,, +75,BOWL,SUM,0,0,0,0,0,48,20,28.1556959152 +75,CUP,SUM,1,0,0,1,0,388,69,0 +75,SPOON,SUM,0,0,0,0,0,56,1,18.0190589428 +75,,SUM,1,0,0,1,0,492,90,46.174754858 +75,,,,,,,,,, +76,,,,,,,,,, +76,BOWL,SUM,0,0,0,0,0,62,0,14.264537096 +76,CUP,SUM,0,0,0,0,0,11,2,10.2933490276 +76,SPOON,SUM,0,0,0,0,0,106,1,20.3612420559 +76,,SUM,0,0,0,0,0,179,3,44.9191281796 +76,,,,,,,,,, +77,,,,,,,,,, +77,BOWL,SUM,0,0,0,0,0,18,1,13.6470901966 +77,CUP,SUM,1,0,1,0,0,136,111,0 +77,SPOON,SUM,0,0,0,0,0,14,0,15.7179689407 +77,,SUM,1,0,1,0,0,168,112,29.3650591373 +77,,,,,,,,,, +78,,,,,,,,,, +78,BOWL,SUM,0,0,0,0,2,7,0,12.7372021675 +78,CUP,SUM,0,0,0,0,2,14,1,12.5339989662 +78,SPOON,SUM,0,0,0,0,0,58,0,17.9642100334 +78,,SUM,0,0,0,0,4,79,1,43.2354111671 +78,,,,,,,,,, +79,,,,,,,,,, +79,BOWL,SUM,0,0,0,0,0,16,0,12.0167291164 +79,CUP,SUM,1,0,1,0,0,131,111,0 +79,SPOON,SUM,0,0,0,0,0,68,5,21.6875998974 +79,,SUM,1,0,1,0,0,215,116,33.7043290138 +79,,,,,,,,,, +80,,,,,,,,,, +80,BOWL,SUM,0,0,0,0,0,56,0,13.0971069336 +80,CUP,SUM,0,0,0,0,0,118,15,34.4157931805 +80,SPOON,SUM,0,0,0,0,0,20,4,17.4665520191 +80,,SUM,0,0,0,0,0,194,19,64.9794521332 +80,,,,,,,,,, +81,,,,,,,,,, +81,BOWL,SUM,0,0,0,0,2,60,4,15.6050858498 +81,CUP,SUM,0,0,0,0,0,20,4,10.3088450432 +81,SPOON,SUM,0,0,0,0,0,7,6,18.8448569775 +81,,SUM,0,0,0,0,2,87,14,44.7587878704 +81,,,,,,,,,, +82,,,,,,,,,, +82,BOWL,SUM,0,0,0,0,0,13,2,12.0580599308 +82,CUP,SUM,0,0,0,0,0,88,20,30.6145670414 +82,SPOON,SUM,1,0,1,0,0,1582,0,0 +82,,SUM,1,0,1,0,0,1683,22,42.6726269722 +82,,,,,,,,,, +83,,,,,,,,,, +83,BOWL,SUM,0,0,0,0,0,44,2,14.059196949 +83,CUP,SUM,1,0,0,1,0,438,56,0 +83,SPOON,SUM,0,0,0,0,0,15,11,24.3525559902 +83,,SUM,1,0,0,1,0,497,69,38.4117529392 +83,,,,,,,,,, +84,,,,,,,,,, +84,BOWL,SUM,0,0,0,0,0,22,0,12.4436907768 +84,CUP,SUM,0,0,0,0,0,3,3,11.3881800175 +84,SPOON,SUM,0,0,0,0,0,12,0,15.217274189 +84,,SUM,0,0,0,0,0,37,3,39.0491449833 +84,,,,,,,,,, +85,,,,,,,,,, +85,BOWL,SUM,0,0,0,0,0,83,4,18.0657999516 +85,CUP,SUM,1,0,0,1,0,364,65,0 +85,SPOON,SUM,0,0,0,0,0,2,0,15.2963519096 +85,,SUM,1,0,0,1,0,449,69,33.3621518612 +85,,,,,,,,,, +86,,,,,,,,,, +86,BOWL,SUM,0,0,0,0,0,41,2,14.0361468792 +86,CUP,SUM,0,0,0,0,2,4,2,10.637565136 +86,SPOON,SUM,0,0,0,0,2,84,2,20.6093869209 +86,,SUM,0,0,0,0,4,129,6,45.2830989361 +86,,,,,,,,,, +87,,,,,,,,,, +87,BOWL,SUM,0,0,0,0,0,45,0,13.357336998 +87,CUP,SUM,1,0,1,0,0,186,109,0 +87,SPOON,SUM,0,0,0,0,2,99,0,21.230232954 +87,,SUM,1,0,1,0,2,330,109,34.587569952 +87,,,,,,,,,, +88,,,,,,,,,, +88,BOWL,SUM,0,0,0,0,0,16,0,11.6562170982 +88,CUP,SUM,0,0,0,0,6,19,1,12.2668280602 +88,SPOON,SUM,0,0,0,0,0,17,2,15.5789480209 +88,,SUM,0,0,0,0,6,52,3,39.5019931793 +88,,,,,,,,,, +89,,,,,,,,,, +89,BOWL,SUM,0,0,0,0,6,5,1,14.9227979183 +89,CUP,SUM,0,0,0,0,0,105,11,26.9618151188 +89,SPOON,SUM,0,0,0,0,0,98,0,21.6780650616 +89,,SUM,0,0,0,0,6,208,12,63.5626780987 +89,,,,,,,,,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_new_var_data_offset_22.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_new_var_data_offset_22.csv new file mode 100644 index 0000000000..2914cf73f2 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_new_var_data_offset_22.csv @@ -0,0 +1,603 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,0,109,28,52.486818075180054 +0,CUP,SUM,0,0,0,0,2,19,8,22.171729803085327 +0,SPOON,SUM,0,0,0,0,0,41,0,21.725011825561523 +0,,SUM,0,0,0,0,2,169,36,96.3835597038269 +0,, +1,, +1,BOWL,SUM,0,0,0,0,6,11,0,16.941517114639282 +1,CUP,SUM,0,0,0,0,0,12,4,13.60329794883728 +1,SPOON,SUM,0,0,0,0,0,15,2,18.692469120025635 +1,,SUM,0,0,0,0,6,38,6,49.2372841835022 +1,, +2,, +2,BOWL,SUM,0,0,0,0,0,40,11,28.254573106765747 +2,CUP,SUM,0,0,0,0,0,24,3,14.155251026153564 +2,SPOON,SUM,0,0,0,0,0,215,0,35.04850912094116 +2,,SUM,0,0,0,0,0,279,14,77.45833325386047 +2,, +3,, +3,BOWL,SUM,0,0,0,0,0,90,2,21.631932020187378 +3,CUP,SUM,0,0,0,0,10,29,3,19.73883891105652 +3,SPOON,SUM,0,0,0,0,0,77,5,24.607303142547607 +3,,SUM,0,0,0,0,10,196,10,65.9780740737915 +3,, +4,, +4,BOWL,SUM,0,0,0,0,0,51,4,18.21917486190796 +4,CUP,SUM,0,0,0,0,0,31,0,14.394853830337524 +4,SPOON,SUM,0,0,0,0,0,133,0,29.793560028076172 +4,,SUM,0,0,0,0,0,215,4,62.407588720321655 +4,, +5,, +5,BOWL,SUM,0,0,0,0,0,14,2,16.130915880203247 +5,CUP,SUM,1,0,1,0,0,367,109,0.0 +5,SPOON,SUM,0,0,0,0,0,412,10,56.09112811088562 +5,,SUM,1,0,1,0,0,793,121,72.22204399108887 +5,, +6,, +6,BOWL,SUM,0,0,0,0,0,6,4,18.408365964889526 +6,CUP,SUM,0,0,0,0,0,4,6,14.653532981872559 +6,SPOON,SUM,0,0,0,0,0,51,6,24.308040142059326 +6,,SUM,0,0,0,0,0,61,16,57.36993908882141 +6,, +7,, +7,BOWL,SUM,0,0,0,0,0,17,1,15.398491859436035 +7,CUP,SUM,1,0,0,1,0,298,56,0.0 +7,SPOON,SUM,0,0,0,0,0,242,12,47.578397035598755 +7,,SUM,1,0,0,1,0,557,69,62.97688889503479 +7,, +8,, +8,BOWL,SUM,1,0,1,0,22,591,42,0.0 +8,CUP,SUM,0,0,0,0,0,17,7,14.505453109741211 +8,SPOON,SUM,0,0,0,0,0,901,0,100.50949597358704 +8,,SUM,1,0,1,0,22,1509,49,115.01494908332825 +8,, +9,, +9,BOWL,SUM,0,0,0,0,0,20,2,15.878023862838745 +9,CUP,SUM,0,0,0,0,0,108,32,73.44102692604065 +9,SPOON,SUM,0,0,0,0,0,93,1,27.167680025100708 +9,,SUM,0,0,0,0,0,221,35,116.4867308139801 +9,, +10,, +10,BOWL,SUM,0,0,0,0,0,93,7,26.56380009651184 +10,CUP,SUM,0,0,0,0,0,269,49,125.51342606544495 +10,SPOON,SUM,0,0,0,0,0,37,1,23.693401098251343 +10,,SUM,0,0,0,0,0,399,57,175.77062726020813 +10,, +11,, +11,BOWL,SUM,1,0,1,0,18,931,33,0.0 +11,CUP,SUM,0,0,0,0,0,8,2,14.352502822875977 +11,SPOON,SUM,0,0,0,0,0,1,2,19.209541082382202 +11,,SUM,1,0,1,0,18,940,37,33.56204390525818 +11,, +12,, +12,BOWL,SUM,0,0,0,0,0,11,0,15.983727931976318 +12,CUP,SUM,0,0,0,0,0,10,10,16.952161073684692 +12,SPOON,SUM,0,0,0,0,0,156,0,30.182708024978638 +12,,SUM,0,0,0,0,0,177,10,63.11859703063965 +12,, +13,, +13,BOWL,SUM,0,0,0,0,0,20,0,15.429208040237427 +13,CUP,SUM,0,0,0,0,0,16,6,14.081845998764038 +13,SPOON,SUM,0,0,0,0,2,0,0,19.040462017059326 +13,,SUM,0,0,0,0,2,36,6,48.55151605606079 +13,, +14,, +14,BOWL,SUM,0,0,0,0,0,6,0,15.609040975570679 +14,CUP,SUM,0,0,0,0,0,25,4,14.344360113143921 +14,SPOON,SUM,0,0,0,0,4,131,0,30.634783029556274 +14,,SUM,0,0,0,0,4,162,4,60.588184118270874 +14,, +15,, +15,BOWL,SUM,0,0,0,0,0,2,0,15.391731977462769 +15,CUP,SUM,0,0,0,0,8,21,6,18.704097986221313 +15,SPOON,SUM,0,0,0,0,18,11,3,30.771164894104004 +15,,SUM,0,0,0,0,26,34,9,64.86699485778809 +15,, +16,, +16,BOWL,SUM,1,0,1,0,0,1028,64,0.0 +16,CUP,SUM,1,0,0,1,0,258,53,0.0 +16,SPOON,SUM,0,0,0,0,0,3,0,19.328458070755005 +16,,SUM,2,0,1,1,0,1289,117,19.328458070755005 +16,, +17,, +17,BOWL,SUM,0,0,0,0,2,41,8,24.630095958709717 +17,CUP,SUM,0,0,0,0,4,3,3,14.89388394355774 +17,SPOON,SUM,0,0,0,0,0,101,0,26.76632785797119 +17,,SUM,0,0,0,0,6,145,11,66.29030776023865 +17,, +18,, +18,BOWL,SUM,0,0,0,0,0,39,4,19.226969957351685 +18,CUP,SUM,0,0,0,0,0,9,11,16.517150163650513 +18,SPOON,SUM,0,0,0,0,0,103,0,27.429744958877563 +18,,SUM,0,0,0,0,0,151,15,63.17386507987976 +18,, +19,, +19,BOWL,SUM,1,0,1,0,0,927,68,0.0 +19,CUP,SUM,0,0,0,0,0,14,14,19.9396550655365 +19,SPOON,SUM,0,0,0,0,0,122,0,28.26430606842041 +19,,SUM,1,0,1,0,0,1063,82,48.20396113395691 +19,, +20,, +20,BOWL,SUM,0,0,0,0,0,13,0,15.695977926254272 +20,CUP,SUM,0,0,0,0,0,11,3,14.267510890960693 +20,SPOON,SUM,0,0,0,0,0,9,2,18.775553941726685 +20,,SUM,0,0,0,0,0,33,5,48.73904275894165 +20,, +21,, +21,BOWL,SUM,0,0,0,0,0,38,4,18.292211055755615 +21,CUP,SUM,0,0,0,0,0,21,4,14.123204946517944 +21,SPOON,SUM,0,0,0,0,2,77,0,25.232969999313354 +21,,SUM,0,0,0,0,2,136,8,57.648386001586914 +21,, +22,, +22,BOWL,SUM,1,0,1,0,2,793,44,0.0 +22,CUP,SUM,0,0,0,0,0,36,12,19.97657012939453 +22,SPOON,SUM,0,0,0,0,0,218,4,43.29161190986633 +22,,SUM,1,0,1,0,2,1047,60,63.268182039260864 +22,, +23,, +23,BOWL,SUM,0,0,0,0,0,16,1,18.387435913085938 +23,CUP,SUM,1,0,1,0,30,117,71,0.0 +23,SPOON,SUM,0,0,0,0,0,216,0,36.375290870666504 +23,,SUM,1,0,1,0,30,349,72,54.76272678375244 +23,, +24,, +24,BOWL,SUM,0,0,0,0,0,11,1,18.66631317138672 +24,CUP,SUM,0,0,0,0,0,19,0,13.978842973709106 +24,SPOON,SUM,1,0,1,0,86,1162,17,0.0 +24,,SUM,1,0,1,0,86,1192,18,32.645156145095825 +24,, +25,, +25,BOWL,SUM,1,0,1,0,2,1017,68,0.0 +25,CUP,SUM,0,0,0,0,0,14,6,16.651676893234253 +25,SPOON,SUM,0,0,0,0,2,46,0,22.466025829315186 +25,,SUM,1,0,1,0,4,1077,74,39.11770272254944 +25,, +26,, +26,BOWL,SUM,0,0,0,0,10,6,4,23.221213817596436 +26,CUP,SUM,0,0,0,0,0,1,3,14.096740961074829 +26,SPOON,SUM,0,0,0,0,0,179,10,44.728090047836304 +26,,SUM,0,0,0,0,10,186,17,82.04604482650757 +26,, +27,, +27,BOWL,SUM,0,0,0,0,0,85,10,31.36985492706299 +27,CUP,SUM,0,0,0,0,0,20,4,13.98627495765686 +27,SPOON,SUM,0,0,0,0,0,339,0,47.69632816314697 +27,,SUM,0,0,0,0,0,444,14,93.05245804786682 +27,, +28,, +28,BOWL,SUM,0,0,0,0,0,22,0,16.234941959381104 +28,CUP,SUM,0,0,0,0,0,26,6,14.529561996459961 +28,SPOON,SUM,0,0,0,0,0,3,0,18.856673002243042 +28,,SUM,0,0,0,0,0,51,6,49.621176958084106 +28,, +29,, +29,BOWL,SUM,0,0,0,0,0,29,0,16.44386601448059 +29,CUP,SUM,1,0,1,0,64,320,42,0.0 +29,SPOON,SUM,0,0,0,0,4,3,0,20.66736102104187 +29,,SUM,1,0,1,0,68,352,42,37.11122703552246 +29,, +30,, +30,BOWL,SUM,0,0,0,0,0,4,0,15.788322925567627 +30,CUP,SUM,0,0,0,0,2,16,1,14.920753955841064 +30,SPOON,SUM,0,0,0,0,0,243,6,42.98085808753967 +30,,SUM,0,0,0,0,2,263,7,73.68993496894836 +30,, +31,, +31,BOWL,SUM,0,0,0,0,0,18,0,16.106919050216675 +31,CUP,SUM,0,0,0,0,0,21,0,14.581114053726196 +31,SPOON,SUM,0,0,0,0,0,48,9,32.82497191429138 +31,,SUM,0,0,0,0,0,87,9,63.51300501823425 +31,, +32,, +32,BOWL,SUM,0,0,0,0,0,10,2,16.684552907943726 +32,CUP,SUM,0,0,0,0,0,17,2,14.571861028671265 +32,SPOON,SUM,0,0,0,0,0,66,0,26.120721101760864 +32,,SUM,0,0,0,0,0,93,4,57.377135038375854 +32,, +33,, +33,BOWL,SUM,0,0,0,0,0,20,0,16.166576147079468 +33,CUP,SUM,0,0,0,0,0,11,4,13.983847856521606 +33,SPOON,SUM,0,0,0,0,0,6,0,19.32071614265442 +33,,SUM,0,0,0,0,0,37,4,49.47114014625549 +33,, +34,, +34,BOWL,SUM,0,0,0,0,0,12,4,18.262027978897095 +34,CUP,SUM,0,0,0,0,0,8,2,14.019604921340942 +34,SPOON,SUM,0,0,0,0,0,113,3,31.389580965042114 +34,,SUM,0,0,0,0,0,133,9,63.67121386528015 +34,, +35,, +35,BOWL,SUM,0,0,0,0,0,14,0,16.506500005722046 +35,CUP,SUM,1,0,0,1,2,293,56,0.0 +35,SPOON,SUM,0,0,0,0,0,104,5,35.46126914024353 +35,,SUM,1,0,0,1,2,411,61,51.967769145965576 +35,, +36,, +36,BOWL,SUM,0,0,0,0,0,6,0,15.989482879638672 +36,CUP,SUM,0,0,0,0,0,19,6,14.415939092636108 +36,SPOON,SUM,0,0,0,0,0,3,0,19.132812023162842 +36,,SUM,0,0,0,0,0,28,6,49.53823399543762 +36,, +37,, +37,BOWL,SUM,0,0,0,0,0,53,6,21.837743997573853 +37,CUP,SUM,1,0,0,1,0,297,57,0.0 +37,SPOON,SUM,0,0,0,0,0,23,0,19.736276865005493 +37,,SUM,1,0,0,1,0,373,63,41.574020862579346 +37,, +38,, +38,BOWL,SUM,0,0,0,0,0,4,0,15.958670854568481 +38,CUP,SUM,0,0,0,0,0,23,0,14.291414022445679 +38,SPOON,SUM,0,0,0,0,2,22,0,20.138164043426514 +38,,SUM,0,0,0,0,2,49,0,50.388248920440674 +38,, +39,, +39,BOWL,SUM,0,0,0,0,16,24,0,26.00541591644287 +39,CUP,SUM,1,0,0,1,0,226,54,0.0 +39,SPOON,SUM,0,0,0,0,0,59,1,22.39854907989502 +39,,SUM,1,0,0,1,16,309,55,48.40396499633789 +39,, +40,, +40,BOWL,SUM,0,0,0,0,0,30,4,18.974448919296265 +40,CUP,SUM,0,0,0,0,2,23,0,15.093027830123901 +40,SPOON,SUM,0,0,0,0,0,2,4,21.724355220794678 +40,,SUM,0,0,0,0,2,55,8,55.791831970214844 +40,, +41,, +41,BOWL,SUM,0,0,0,0,0,25,6,21.948555946350098 +41,CUP,SUM,1,0,1,0,0,231,63,0.0 +41,SPOON,SUM,0,0,0,0,0,91,1,27.86512303352356 +41,,SUM,1,0,1,0,0,347,70,49.81367897987366 +41,, +42,, +42,BOWL,SUM,0,0,0,0,0,60,0,19.216033935546875 +42,CUP,SUM,0,0,0,0,0,6,0,14.170873880386353 +42,SPOON,SUM,0,0,0,0,26,14,6,39.49774384498596 +42,,SUM,0,0,0,0,26,80,6,72.88465166091919 +42,, +43,, +43,BOWL,SUM,0,0,0,0,0,4,4,15.395750999450684 +43,CUP,SUM,0,0,0,0,0,14,2,14.362100839614868 +43,SPOON,SUM,0,0,0,0,0,23,4,22.11896300315857 +43,,SUM,0,0,0,0,0,41,10,51.87681484222412 +43,, +44,, +44,BOWL,SUM,0,0,0,0,16,26,0,25.37061905860901 +44,CUP,SUM,1,0,1,0,42,345,71,0.0 +44,SPOON,SUM,0,0,0,0,0,23,2,24.30099892616272 +44,,SUM,1,0,1,0,58,394,73,49.67161798477173 +44,, +45,, +45,BOWL,SUM,0,0,0,0,0,11,0,16.11494493484497 +45,CUP,SUM,0,0,0,0,0,6,0,14.075972080230713 +45,SPOON,SUM,0,0,0,0,0,27,3,26.742008209228516 +45,,SUM,0,0,0,0,0,44,3,56.9329252243042 +45,, +46,, +46,BOWL,SUM,0,0,0,0,0,245,0,35.4712278842926 +46,CUP,SUM,0,0,0,0,0,46,26,38.58484601974487 +46,SPOON,SUM,0,0,0,0,0,10,0,19.550442934036255 +46,,SUM,0,0,0,0,0,301,26,93.60651683807373 +46,, +47,, +47,BOWL,SUM,0,0,0,0,0,33,4,19.123208045959473 +47,CUP,SUM,0,0,0,0,6,8,4,16.26827907562256 +47,SPOON,SUM,0,0,0,0,0,409,0,55.72277498245239 +47,,SUM,0,0,0,0,6,450,8,91.11426210403442 +47,, +48,, +48,BOWL,SUM,0,0,0,0,0,10,2,15.82349419593811 +48,CUP,SUM,0,0,0,0,0,74,20,44.36065101623535 +48,SPOON,SUM,0,0,0,0,0,109,3,30.60328197479248 +48,,SUM,0,0,0,0,0,193,25,90.78742718696594 +48,, +49,, +49,BOWL,SUM,0,0,0,0,0,28,0,16.492263078689575 +49,CUP,SUM,0,0,0,0,0,32,0,14.45160698890686 +49,SPOON,SUM,0,0,0,0,0,16,2,19.638160943984985 +49,,SUM,0,0,0,0,0,76,2,50.58203101158142 +49,, +50,, +50,BOWL,SUM,0,0,0,0,0,34,1,16.52361798286438 +50,CUP,SUM,0,0,0,0,0,29,0,14.481092929840088 +50,SPOON,SUM,0,0,0,0,0,260,1,45.539462089538574 +50,,SUM,0,0,0,0,0,323,2,76.54417300224304 +50,, +51,, +51,BOWL,SUM,0,0,0,0,2,19,10,28.788906812667847 +51,CUP,SUM,0,0,0,0,0,64,10,31.035130977630615 +51,SPOON,SUM,0,0,0,0,2,9,4,24.437768936157227 +51,,SUM,0,0,0,0,4,92,24,84.26180672645569 +51,, +52,, +52,BOWL,SUM,0,0,0,0,0,156,12,35.78059506416321 +52,CUP,SUM,0,0,0,0,2,21,2,15.336907148361206 +52,SPOON,SUM,0,0,0,0,0,173,2,34.05827212333679 +52,,SUM,0,0,0,0,2,350,16,85.1757743358612 +52,, +53,, +53,BOWL,SUM,0,0,0,0,0,161,36,62.13547086715698 +53,CUP,SUM,0,0,0,0,2,6,0,14.651559114456177 +53,SPOON,SUM,0,0,0,0,0,3,14,33.815579891204834 +53,,SUM,0,0,0,0,2,170,50,110.602609872818 +53,, +54,, +54,BOWL,SUM,0,0,0,0,0,8,4,18.776711225509644 +54,CUP,SUM,0,0,0,0,6,32,3,17.102649927139282 +54,SPOON,SUM,0,0,0,0,2,24,5,27.19490098953247 +54,,SUM,0,0,0,0,8,64,12,63.0742621421814 +54,, +55,, +55,BOWL,SUM,0,0,0,0,0,11,0,15.929614067077637 +55,CUP,SUM,1,0,1,0,0,178,111,0.0 +55,SPOON,SUM,0,0,0,0,0,256,1,44.131994009017944 +55,,SUM,1,0,1,0,0,445,112,60.06160807609558 +55,, +56,, +56,BOWL,SUM,0,0,0,0,0,111,2,24.40019989013672 +56,CUP,SUM,0,0,0,0,2,30,12,18.194887161254883 +56,SPOON,SUM,0,0,0,0,0,0,2,18.92205786705017 +56,,SUM,0,0,0,0,2,141,16,61.51714491844177 +56,, +57,, +57,BOWL,SUM,0,0,0,0,0,274,34,68.42764592170715 +57,CUP,SUM,1,0,1,0,0,343,111,0.0 +57,SPOON,SUM,0,0,0,0,0,19,0,19.355314016342163 +57,,SUM,1,0,1,0,0,636,145,87.78295993804932 +57,, +58,, +58,BOWL,SUM,0,0,0,0,0,3,0,16.05822992324829 +58,CUP,SUM,1,0,0,1,0,375,50,0.0 +58,SPOON,SUM,0,0,0,0,0,9,5,24.376566171646118 +58,,SUM,1,0,0,1,0,387,55,40.43479609489441 +58,, +59,, +59,BOWL,SUM,0,0,0,0,2,14,0,16.92810320854187 +59,CUP,SUM,0,0,0,0,0,4,6,14.337889194488525 +59,SPOON,SUM,0,0,0,0,0,0,0,19.180461168289185 +59,,SUM,0,0,0,0,2,18,6,50.44645357131958 +59,, +60,, +60,BOWL,SUM,0,0,0,0,6,74,0,23.473021030426025 +60,CUP,SUM,0,0,0,0,0,41,2,14.934363842010498 +60,SPOON,SUM,0,0,0,0,0,30,0,19.808743953704834 +60,,SUM,0,0,0,0,6,145,2,58.21612882614136 +60,, +61,, +61,BOWL,SUM,1,0,1,0,0,398,94,0.0 +61,CUP,SUM,0,0,0,0,0,12,6,14.278021097183228 +61,SPOON,SUM,0,0,0,0,0,166,0,34.30565285682678 +61,,SUM,1,0,1,0,0,576,100,48.58367395401001 +61,, +62,, +62,BOWL,SUM,0,0,0,0,0,112,0,23.489410877227783 +62,CUP,SUM,0,0,0,0,0,15,2,14.75286316871643 +62,SPOON,SUM,0,0,0,0,0,1,2,19.38479208946228 +62,,SUM,0,0,0,0,0,128,4,57.627066135406494 +62,, +63,, +63,BOWL,SUM,0,0,0,0,38,34,6,42.11837410926819 +63,CUP,SUM,0,0,0,0,0,30,4,14.386262893676758 +63,SPOON,SUM,0,0,0,0,0,1,2,19.266098976135254 +63,,SUM,0,0,0,0,38,65,12,75.7707359790802 +63,, +64,, +64,BOWL,SUM,0,0,0,0,6,72,8,27.157310962677002 +64,CUP,SUM,0,0,0,0,0,7,4,15.043967008590698 +64,SPOON,SUM,0,0,0,0,2,84,2,26.23178005218506 +64,,SUM,0,0,0,0,8,163,14,68.43305802345276 +64,, +65,, +65,BOWL,SUM,0,0,0,0,0,20,0,16.313842058181763 +65,CUP,SUM,0,0,0,0,0,82,18,39.137619972229004 +65,SPOON,SUM,0,0,0,0,22,121,4,39.56066393852234 +65,,SUM,0,0,0,0,22,223,22,95.0121259689331 +65,, +66,, +66,BOWL,SUM,0,0,0,0,0,12,1,16.42764186859131 +66,CUP,SUM,0,0,0,0,0,28,5,15.388418912887573 +66,SPOON,SUM,0,0,0,0,0,0,4,22.020838022232056 +66,,SUM,0,0,0,0,0,40,10,53.83689880371094 +66,, +67,, +67,BOWL,SUM,0,0,0,0,0,13,3,18.582561016082764 +67,CUP,SUM,0,0,0,0,0,86,17,42.89488911628723 +67,SPOON,SUM,0,0,0,0,0,23,0,19.97221302986145 +67,,SUM,0,0,0,0,0,122,20,81.44966316223145 +67,, +68,, +68,BOWL,SUM,0,0,0,0,0,82,14,37.62451505661011 +68,CUP,SUM,0,0,0,0,0,5,10,15.059646129608154 +68,SPOON,SUM,0,0,0,0,0,87,0,25.649967908859253 +68,,SUM,0,0,0,0,0,174,24,78.33412909507751 +68,, +69,, +69,BOWL,SUM,0,0,0,0,0,18,0,16.172343969345093 +69,CUP,SUM,0,0,0,0,14,8,0,20.658265113830566 +69,SPOON,SUM,0,0,0,0,0,3,2,19.65733504295349 +69,,SUM,0,0,0,0,14,29,2,56.48794412612915 +69,, +70,, +70,BOWL,SUM,0,0,0,0,0,24,0,16.278909921646118 +70,CUP,SUM,0,0,0,0,0,27,0,14.532886028289795 +70,SPOON,SUM,0,0,0,0,0,9,4,29.155813932418823 +70,,SUM,0,0,0,0,0,60,4,59.967609882354736 +70,, +71,, +71,BOWL,SUM,0,0,0,0,0,199,37,67.6838231086731 +71,CUP,SUM,0,0,0,0,0,86,15,43.057748794555664 +71,SPOON,SUM,0,0,0,0,0,14,6,24.857505083084106 +71,,SUM,0,0,0,0,0,299,58,135.59907698631287 +71,, +72,, +72,BOWL,SUM,0,0,0,0,62,53,8,58.0739381313324 +72,CUP,SUM,1,0,1,0,8,297,98,0.0 +72,SPOON,SUM,0,0,0,0,0,71,0,25.524240970611572 +72,,SUM,1,0,1,0,70,421,106,83.59817910194397 +72,, +73,, +73,BOWL,SUM,0,0,0,0,38,29,0,36.33325695991516 +73,CUP,SUM,0,0,0,0,0,10,1,14.794120073318481 +73,SPOON,SUM,0,0,0,0,8,986,24,146.29588198661804 +73,,SUM,0,0,0,0,46,1025,25,197.42325901985168 +73,, +74,, +74,BOWL,SUM,0,0,0,0,0,324,26,62.1631121635437 +74,CUP,SUM,0,0,0,0,0,52,4,20.451355934143066 +74,SPOON,SUM,0,0,0,0,0,22,2,22.022214889526367 +74,,SUM,0,0,0,0,0,398,32,104.63668298721313 +74,, +75,, +75,BOWL,SUM,0,0,0,0,0,26,0,16.717582941055298 +75,CUP,SUM,0,0,0,0,2,16,0,15.87225890159607 +75,SPOON,SUM,0,0,0,0,0,12,0,19.462552070617676 +75,,SUM,0,0,0,0,2,54,0,52.05239391326904 +75,, +76,, +76,BOWL,SUM,0,0,0,0,0,13,1,18.323678016662598 +76,CUP,SUM,0,0,0,0,0,10,6,18.999197006225586 +76,SPOON,SUM,0,0,0,0,0,200,0,36.935462951660156 +76,,SUM,0,0,0,0,0,223,7,74.25833797454834 +76,, +77,, +77,BOWL,SUM,0,0,0,0,0,15,0,16.049345016479492 +77,CUP,SUM,0,0,0,0,2,102,19,44.497583866119385 +77,SPOON,SUM,0,0,0,0,10,48,2,27.5536949634552 +77,,SUM,0,0,0,0,12,165,21,88.10062384605408 +77,, +78,, +78,BOWL,SUM,0,0,0,0,0,31,0,16.553629875183105 +78,CUP,SUM,0,0,0,0,2,103,26,66.67249512672424 +78,SPOON,SUM,1,0,1,0,100,102,4,0.0 +78,,SUM,1,0,1,0,102,236,30,83.22612500190735 +78,, +79,, +79,BOWL,SUM,0,0,0,0,0,25,0,16.34018087387085 +79,CUP,SUM,0,0,0,0,0,16,8,19.30251908302307 +79,SPOON,SUM,0,0,0,0,0,58,4,25.60953712463379 +79,,SUM,0,0,0,0,0,99,12,61.25223708152771 +79,, +80,, +80,BOWL,SUM,0,0,0,0,0,10,0,17.847615003585815 +80,CUP,SUM,0,0,0,0,2,311,58,144.24904417991638 +80,SPOON,SUM,0,0,0,0,0,61,7,32.28881597518921 +80,,SUM,0,0,0,0,2,382,65,194.3854751586914 +80,, +81,, +81,BOWL,SUM,0,0,0,0,0,15,0,16.43019390106201 +81,CUP,SUM,1,0,1,0,28,291,51,0.0 +81,SPOON,SUM,0,0,0,0,0,70,4,25.800169944763184 +81,,SUM,1,0,1,0,28,376,55,42.230363845825195 +81,, +82,, +82,BOWL,SUM,0,0,0,0,0,3,0,15.8111891746521 +82,CUP,SUM,0,0,0,0,0,40,9,26.967457056045532 +82,SPOON,SUM,0,0,0,0,0,227,4,41.08515405654907 +82,,SUM,0,0,0,0,0,270,13,83.8638002872467 +82,, +83,, +83,BOWL,SUM,0,0,0,0,0,9,0,16.3885600566864 +83,CUP,SUM,0,0,0,0,0,265,52,131.22012186050415 +83,SPOON,SUM,0,0,0,0,2,491,7,67.4131760597229 +83,,SUM,0,0,0,0,2,765,59,215.02185797691345 +83,, +84,, +84,BOWL,SUM,0,0,0,0,0,76,0,19.17508292198181 +84,CUP,SUM,0,0,0,0,0,7,0,14.108931064605713 +84,SPOON,SUM,0,0,0,0,0,101,0,27.47046399116516 +84,,SUM,0,0,0,0,0,184,0,60.754477977752686 +84,, +85,, +85,BOWL,SUM,0,0,0,0,0,63,8,26.866947174072266 +85,CUP,SUM,1,0,1,0,38,303,67,0.0 +85,SPOON,SUM,0,0,0,0,0,141,0,31.223710775375366 +85,,SUM,1,0,1,0,38,507,75,58.09065794944763 +85,, +86,, +86,BOWL,SUM,0,0,0,0,0,50,14,31.76046109199524 +86,CUP,SUM,0,0,0,0,10,97,20,61.72415494918823 +86,SPOON,SUM,0,0,0,0,6,388,1,53.97766613960266 +86,,SUM,0,0,0,0,16,535,35,147.46228218078613 +86,, +87,, +87,BOWL,SUM,0,0,0,0,2,40,0,19.304542064666748 +87,CUP,SUM,0,0,0,0,0,5,2,14.349059104919434 +87,SPOON,SUM,0,0,0,0,0,11,0,19.803586959838867 +87,,SUM,0,0,0,0,2,56,2,53.45718812942505 +87,, +88,, +88,BOWL,SUM,0,0,0,0,0,213,22,52.44572591781616 +88,CUP,SUM,1,0,1,0,32,297,45,0.0 +88,SPOON,SUM,0,0,0,0,0,33,0,22.422634840011597 +88,,SUM,1,0,1,0,32,543,67,74.86836075782776 +88,, +89,, +89,BOWL,SUM,0,0,0,0,24,130,0,37.2064368724823 +89,CUP,SUM,0,0,0,0,0,15,4,16.51333713531494 +89,SPOON,SUM,0,0,0,0,0,142,21,54.691617012023926 +89,,SUM,0,0,0,0,24,287,25,108.41139101982117 +89,, +90,, +90,BOWL,SUM,0,0,0,0,0,36,0,16.813822984695435 +90,CUP,SUM,0,0,0,0,0,159,23,63.896848917007446 +90,SPOON,SUM,0,0,0,0,0,57,2,23.067354917526245 +90,,SUM,0,0,0,0,0,252,25,103.77802681922913 +90,, +91,, +91,BOWL,SUM,0,0,0,0,0,19,1,18.86653709411621 +91,CUP,SUM,0,0,0,0,0,9,3,14.314893960952759 +91,SPOON,SUM,1,0,1,0,0,1554,5,0.0 +91,,SUM,1,0,1,0,0,1582,9,33.18143105506897 +91,, +92,, +92,BOWL,SUM,0,0,0,0,0,42,0,18.459964990615845 +92,CUP,SUM,0,0,0,0,0,6,10,24.31263303756714 +92,SPOON,SUM,0,0,0,0,2,11,0,20.33564305305481 +92,,SUM,0,0,0,0,2,59,10,63.10824108123779 +92,, +93,, +93,BOWL,SUM,0,0,0,0,0,17,5,21.191028833389282 +93,CUP,SUM,0,0,0,0,0,112,32,70.01473188400269 +93,SPOON,SUM,0,0,0,0,0,167,0,33.75807809829712 +93,,SUM,0,0,0,0,0,296,37,124.96383881568909 +93,, +94,, +94,BOWL,SUM,0,0,0,0,0,3,2,16.264782905578613 +94,CUP,SUM,0,0,0,0,0,19,9,17.4996280670166 +94,SPOON,SUM,1,0,1,0,0,1258,34,0.0 +94,,SUM,1,0,1,0,0,1280,45,33.764410972595215 +94,, +95,, +95,BOWL,SUM,0,0,0,0,0,16,0,16.508628845214844 +95,CUP,SUM,0,0,0,0,6,80,14,46.64802694320679 +95,SPOON,SUM,0,0,0,0,6,292,3,48.398041009902954 +95,,SUM,0,0,0,0,12,388,17,111.55469679832458 +95,, +96,, +96,BOWL,SUM,0,0,0,0,2,26,0,17.43870711326599 +96,CUP,SUM,1,0,1,0,30,129,87,0.0 +96,SPOON,SUM,0,0,0,0,0,618,3,82.76519298553467 +96,,SUM,1,0,1,0,32,773,90,100.20390009880066 +96,, +97,, +97,BOWL,SUM,1,0,1,0,0,1339,26,0.0 +97,CUP,SUM,1,0,1,0,42,309,50,0.0 +97,SPOON,SUM,0,0,0,0,0,69,0,24.968276023864746 +97,,SUM,2,0,2,0,42,1717,76,24.968276023864746 +97,, +98,, +98,BOWL,SUM,0,0,0,0,0,7,4,18.58943510055542 +98,CUP,SUM,1,0,1,0,0,84,99,0.0 +98,SPOON,SUM,0,0,0,0,0,105,1,28.20468306541443 +98,,SUM,1,0,1,0,0,196,104,46.79411816596985 +98,, +99,, +99,BOWL,SUM,0,0,0,0,0,6,0,15.922672033309937 +99,CUP,SUM,1,0,1,0,84,222,60,0.0 +99,SPOON,SUM,0,0,0,0,2,17,1,22.87428593635559 +99,,SUM,1,0,1,0,86,245,61,38.79695796966553 +99,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_and_vr_data.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_and_vr_data.csv new file mode 100644 index 0000000000..29e2c34153 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_and_vr_data.csv @@ -0,0 +1,603 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,0,12,0,22.435499906539917 +0,CUP,SUM,1,0,1,0,0,202,111,0.0 +0,SPOON,SUM,0,0,0,0,10,87,4,38.804344177246094 +0,,SUM,1,0,1,0,10,301,115,61.23984408378601 +0,, +1,, +1,BOWL,SUM,0,0,0,0,0,19,3,21.905822038650513 +1,CUP,SUM,0,0,0,0,0,1,2,16.61355686187744 +1,SPOON,SUM,0,0,0,0,0,11,0,22.019892930984497 +1,,SUM,0,0,0,0,0,31,5,60.53927183151245 +1,, +2,, +2,BOWL,SUM,0,0,0,0,0,14,1,22.26213002204895 +2,CUP,SUM,0,0,0,0,0,30,2,18.933631896972656 +2,SPOON,SUM,0,0,0,0,8,2,0,27.311751127243042 +2,,SUM,0,0,0,0,8,46,3,68.50751304626465 +2,, +3,, +3,BOWL,SUM,0,0,0,0,6,11,0,20.77181911468506 +3,CUP,SUM,0,0,0,0,0,25,12,24.724472045898438 +3,SPOON,SUM,0,0,0,0,0,11,0,21.458389043807983 +3,,SUM,0,0,0,0,6,47,12,66.95468020439148 +3,, +4,, +4,BOWL,SUM,0,0,0,0,0,3,0,18.70069694519043 +4,CUP,SUM,0,0,0,0,0,144,39,119.08636808395386 +4,SPOON,SUM,0,0,0,0,0,170,0,38.55480909347534 +4,,SUM,0,0,0,0,0,317,39,176.34187412261963 +4,, +5,, +5,BOWL,SUM,1,0,1,0,0,1062,62,0.0 +5,CUP,SUM,0,0,0,0,0,13,7,21.33560585975647 +5,SPOON,SUM,0,0,0,0,2,62,3,38.2179069519043 +5,,SUM,1,0,1,0,2,1137,72,59.55351281166077 +5,, +6,, +6,BOWL,SUM,0,0,0,0,0,5,0,18.444429874420166 +6,CUP,SUM,0,0,0,0,0,12,9,18.055535078048706 +6,SPOON,SUM,0,0,0,0,0,2,2,23.005977153778076 +6,,SUM,0,0,0,0,0,19,11,59.50594210624695 +6,, +7,, +7,BOWL,SUM,0,0,0,0,0,13,0,18.87836980819702 +7,CUP,SUM,0,0,0,0,0,25,5,21.01284098625183 +7,SPOON,SUM,0,0,0,0,0,27,5,28.19861888885498 +7,,SUM,0,0,0,0,0,65,10,68.08982968330383 +7,, +8,, +8,BOWL,SUM,0,0,0,0,0,121,2,29.619507789611816 +8,CUP,SUM,0,0,0,0,0,252,52,163.18537712097168 +8,SPOON,SUM,0,0,0,0,0,735,1,105.14465999603271 +8,,SUM,0,0,0,0,0,1108,55,297.9495449066162 +8,, +9,, +9,BOWL,SUM,0,0,0,0,0,12,0,18.687638998031616 +9,CUP,SUM,0,0,0,0,0,1,2,16.64359998703003 +9,SPOON,SUM,0,0,0,0,0,73,0,25.957507133483887 +9,,SUM,0,0,0,0,0,86,2,61.28874611854553 +9,, +10,, +10,BOWL,SUM,0,0,0,0,0,7,0,19.309290885925293 +10,CUP,SUM,0,0,0,0,0,74,23,72.76339411735535 +10,SPOON,SUM,0,0,0,0,16,391,0,68.92888593673706 +10,,SUM,0,0,0,0,16,472,23,161.0015709400177 +10,, +11,, +11,BOWL,SUM,0,0,0,0,2,51,3,26.586284160614014 +11,CUP,SUM,0,0,0,0,0,7,2,17.521960973739624 +11,SPOON,SUM,0,0,0,0,2,202,1,45.60162305831909 +11,,SUM,0,0,0,0,4,260,6,89.70986819267273 +11,, +12,, +12,BOWL,SUM,1,0,1,0,10,1154,46,0.0 +12,CUP,SUM,0,0,0,0,0,156,30,102.14925694465637 +12,SPOON,SUM,0,0,0,0,0,345,0,60.42038297653198 +12,,SUM,1,0,1,0,10,1655,76,162.56963992118835 +12,, +13,, +13,BOWL,SUM,0,0,0,0,26,54,4,38.84583592414856 +13,CUP,SUM,0,0,0,0,0,33,2,17.731026887893677 +13,SPOON,SUM,0,0,0,0,0,142,0,35.7439820766449 +13,,SUM,0,0,0,0,26,229,6,92.32084488868713 +13,, +14,, +14,BOWL,SUM,0,0,0,0,0,26,0,18.845278024673462 +14,CUP,SUM,0,0,0,0,8,22,6,29.11820912361145 +14,SPOON,SUM,0,0,0,0,0,3,1,24.924628019332886 +14,,SUM,0,0,0,0,8,51,7,72.8881151676178 +14,, +15,, +15,BOWL,SUM,0,0,0,0,8,17,0,24.45731782913208 +15,CUP,SUM,0,0,0,0,0,16,3,20.792423963546753 +15,SPOON,SUM,0,0,0,0,0,1,4,27.22773504257202 +15,,SUM,0,0,0,0,8,34,7,72.47747683525085 +15,, +16,, +16,BOWL,SUM,0,0,0,0,0,13,2,18.803242921829224 +16,CUP,SUM,0,0,0,0,0,10,2,17.744520902633667 +16,SPOON,SUM,0,0,0,0,0,66,0,28.302107095718384 +16,,SUM,0,0,0,0,0,89,4,64.84987092018127 +16,, +17,, +17,BOWL,SUM,0,0,0,0,0,22,10,31.582371950149536 +17,CUP,SUM,0,0,0,0,0,16,2,17.696873903274536 +17,SPOON,SUM,0,0,0,0,2,220,10,50.79183006286621 +17,,SUM,0,0,0,0,2,258,22,100.07107591629028 +17,, +18,, +18,BOWL,SUM,0,0,0,0,58,67,16,79.53500199317932 +18,CUP,SUM,0,0,0,0,2,18,2,17.859699010849 +18,SPOON,SUM,0,0,0,0,0,327,7,63.863024950027466 +18,,SUM,0,0,0,0,60,412,25,161.2577259540558 +18,, +19,, +19,BOWL,SUM,0,0,0,0,0,20,0,19.114986896514893 +19,CUP,SUM,0,0,0,0,0,11,7,24.146512985229492 +19,SPOON,SUM,0,0,0,0,2,82,2,29.937071800231934 +19,,SUM,0,0,0,0,2,113,9,73.19857168197632 +19,, +20,, +20,BOWL,SUM,0,0,0,0,0,37,1,22.0706729888916 +20,CUP,SUM,1,0,0,1,4,189,60,0.0 +20,SPOON,SUM,0,0,0,0,0,3,0,21.837428092956543 +20,,SUM,1,0,0,1,4,229,61,43.908101081848145 +20,, +21,, +21,BOWL,SUM,0,0,0,0,0,24,2,18.909071922302246 +21,CUP,SUM,0,0,0,0,2,15,4,18.313820123672485 +21,SPOON,SUM,0,0,0,0,0,46,3,34.15669798851013 +21,,SUM,0,0,0,0,2,85,9,71.37959003448486 +21,, +22,, +22,BOWL,SUM,0,0,0,0,0,124,16,48.69266700744629 +22,CUP,SUM,0,0,0,0,2,27,6,24.010165214538574 +22,SPOON,SUM,0,0,0,0,0,68,0,29.354995012283325 +22,,SUM,0,0,0,0,2,219,22,102.05782723426819 +22,, +23,, +23,BOWL,SUM,0,0,0,0,0,91,6,30.190060138702393 +23,CUP,SUM,0,0,0,0,0,12,2,17.498318910598755 +23,SPOON,SUM,0,0,0,0,2,138,2,39.89482498168945 +23,,SUM,0,0,0,0,2,241,10,87.5832040309906 +23,, +24,, +24,BOWL,SUM,0,0,0,0,0,9,0,19.156457901000977 +24,CUP,SUM,1,0,0,1,0,232,53,0.0 +24,SPOON,SUM,0,0,0,0,0,51,1,28.73483896255493 +24,,SUM,1,0,0,1,0,292,54,47.89129686355591 +24,, +25,, +25,BOWL,SUM,0,0,0,0,0,6,0,19.20889401435852 +25,CUP,SUM,1,0,1,0,0,216,76,0.0 +25,SPOON,SUM,0,0,0,0,0,1,1,24.99394917488098 +25,,SUM,1,0,1,0,0,223,77,44.2028431892395 +25,, +26,, +26,BOWL,SUM,1,0,1,0,6,207,82,0.0 +26,CUP,SUM,0,0,0,0,0,49,11,28.78442883491516 +26,SPOON,SUM,0,0,0,0,0,25,10,35.003562211990356 +26,,SUM,1,0,1,0,6,281,103,63.78799104690552 +26,, +27,, +27,BOWL,SUM,0,0,0,0,0,20,1,22.506314992904663 +27,CUP,SUM,0,0,0,0,2,183,37,130.76372003555298 +27,SPOON,SUM,0,0,0,0,2,23,0,23.283139944076538 +27,,SUM,0,0,0,0,4,226,38,176.55317497253418 +27,, +28,, +28,BOWL,SUM,1,0,1,0,48,943,84,0.0 +28,CUP,SUM,0,0,0,0,10,26,6,30.910704851150513 +28,SPOON,SUM,0,0,0,0,2,101,0,31.757068157196045 +28,,SUM,1,0,1,0,60,1070,90,62.66777300834656 +28,, +29,, +29,BOWL,SUM,0,0,0,0,0,10,0,18.94951105117798 +29,CUP,SUM,0,0,0,0,2,7,0,17.737725973129272 +29,SPOON,SUM,0,0,0,0,0,45,0,25.909798860549927 +29,,SUM,0,0,0,0,2,62,0,62.59703588485718 +29,, +30,, +30,BOWL,SUM,0,0,0,0,54,72,2,55.845324993133545 +30,CUP,SUM,0,0,0,0,0,25,9,27.81955599784851 +30,SPOON,SUM,0,0,0,0,2,385,5,74.45629501342773 +30,,SUM,0,0,0,0,56,482,16,158.1211760044098 +30,, +31,, +31,BOWL,SUM,0,0,0,0,2,6,0,19.19854187965393 +31,CUP,SUM,0,0,0,0,0,11,10,23.788560152053833 +31,SPOON,SUM,0,0,0,0,0,178,12,50.0530788898468 +31,,SUM,0,0,0,0,2,195,22,93.04018092155457 +31,, +32,, +32,BOWL,SUM,0,0,0,0,0,4,4,22.59727907180786 +32,CUP,SUM,0,0,0,0,0,89,25,58.68431091308594 +32,SPOON,SUM,0,0,0,0,0,4,0,21.986918926239014 +32,,SUM,0,0,0,0,0,97,29,103.26850891113281 +32,, +33,, +33,BOWL,SUM,1,0,1,0,90,1211,50,0.0 +33,CUP,SUM,1,0,0,1,0,245,51,0.0 +33,SPOON,SUM,0,0,0,0,0,0,0,22.290395975112915 +33,,SUM,2,0,1,1,90,1456,101,22.290395975112915 +33,, +34,, +34,BOWL,SUM,0,0,0,0,0,141,0,33.41660404205322 +34,CUP,SUM,1,0,1,0,4,408,107,0.0 +34,SPOON,SUM,0,0,0,0,0,56,0,25.782868146896362 +34,,SUM,1,0,1,0,4,605,107,59.199472188949585 +34,, +35,, +35,BOWL,SUM,0,0,0,0,58,35,4,60.197449922561646 +35,CUP,SUM,1,0,0,1,0,280,54,0.0 +35,SPOON,SUM,0,0,0,0,0,130,0,36.13205909729004 +35,,SUM,1,0,0,1,58,445,58,96.32950901985168 +35,, +36,, +36,BOWL,SUM,0,0,0,0,2,32,0,20.127700090408325 +36,CUP,SUM,1,0,0,1,0,259,54,0.0 +36,SPOON,SUM,0,0,0,0,0,25,1,25.048901081085205 +36,,SUM,1,0,0,1,2,316,55,45.17660117149353 +36,, +37,, +37,BOWL,SUM,0,0,0,0,0,19,0,19.323707818984985 +37,CUP,SUM,0,0,0,0,2,16,4,18.214046955108643 +37,SPOON,SUM,0,0,0,0,0,2,4,34.1451370716095 +37,,SUM,0,0,0,0,2,37,8,71.68289184570313 +37,, +38,, +38,BOWL,SUM,0,0,0,0,56,14,0,58.3118109703064 +38,CUP,SUM,0,0,0,0,0,22,0,18.449044942855835 +38,SPOON,SUM,0,0,0,0,0,18,0,22.244516134262085 +38,,SUM,0,0,0,0,56,54,0,99.00537204742432 +38,, +39,, +39,BOWL,SUM,0,0,0,0,0,5,0,18.87735915184021 +39,CUP,SUM,0,0,0,0,0,14,3,20.911189794540405 +39,SPOON,SUM,0,0,0,0,0,2,2,27.35778307914734 +39,,SUM,0,0,0,0,0,21,5,67.14633202552795 +39,, +40,, +40,BOWL,SUM,0,0,0,0,62,68,0,63.22163701057434 +40,CUP,SUM,0,0,0,0,0,1,2,17.565698862075806 +40,SPOON,SUM,0,0,0,0,0,55,3,36.01981496810913 +40,,SUM,0,0,0,0,62,124,5,116.80715084075928 +40,, +41,, +41,BOWL,SUM,0,0,0,0,0,39,8,32.68684005737305 +41,CUP,SUM,0,0,0,0,0,44,9,34.19619798660278 +41,SPOON,SUM,0,0,0,0,0,83,1,32.889358043670654 +41,,SUM,0,0,0,0,0,166,18,99.77239608764648 +41,, +42,, +42,BOWL,SUM,1,0,1,0,0,703,88,0.0 +42,CUP,SUM,1,0,1,0,0,340,111,0.0 +42,SPOON,SUM,0,0,0,0,0,189,1,46.1691529750824 +42,,SUM,2,0,2,0,0,1232,200,46.1691529750824 +42,, +43,, +43,BOWL,SUM,0,0,0,0,10,20,4,29.02703595161438 +43,CUP,SUM,0,0,0,0,0,92,22,77.63082504272461 +43,SPOON,SUM,0,0,0,0,0,482,16,92.81454706192017 +43,,SUM,0,0,0,0,10,594,42,199.47240805625916 +43,, +44,, +44,BOWL,SUM,0,0,0,0,2,60,22,53.227752923965454 +44,CUP,SUM,0,0,0,0,0,136,40,114.57932209968567 +44,SPOON,SUM,0,0,0,0,6,509,0,81.22823095321655 +44,,SUM,0,0,0,0,8,705,62,249.03530597686768 +44,, +45,, +45,BOWL,SUM,0,0,0,0,0,108,13,43.254343032836914 +45,CUP,SUM,0,0,0,0,0,19,4,17.909723043441772 +45,SPOON,SUM,0,0,0,0,2,130,8,40.950870990753174 +45,,SUM,0,0,0,0,2,257,25,102.11493706703186 +45,, +46,, +46,BOWL,SUM,0,0,0,0,0,14,0,19.38771080970764 +46,CUP,SUM,0,0,0,0,0,3,0,16.995043992996216 +46,SPOON,SUM,0,0,0,0,0,10,0,22.247792959213257 +46,,SUM,0,0,0,0,0,27,0,58.630547761917114 +46,, +47,, +47,BOWL,SUM,0,0,0,0,2,12,0,20.257734060287476 +47,CUP,SUM,0,0,0,0,0,11,1,21.606925010681152 +47,SPOON,SUM,0,0,0,0,2,61,1,30.746212005615234 +47,,SUM,0,0,0,0,4,84,2,72.61087107658386 +47,, +48,, +48,BOWL,SUM,0,0,0,0,0,12,6,25.63832998275757 +48,CUP,SUM,0,0,0,0,0,21,6,24.94859790802002 +48,SPOON,SUM,1,0,1,0,2,1582,0,0.0 +48,,SUM,1,0,1,0,2,1615,12,50.58692789077759 +48,, +49,, +49,BOWL,SUM,0,0,0,0,4,5,0,20.50578784942627 +49,CUP,SUM,0,0,0,0,0,14,0,18.155215978622437 +49,SPOON,SUM,0,0,0,0,0,0,0,22.19048309326172 +49,,SUM,0,0,0,0,4,19,0,60.851486921310425 +49,, +50,, +50,BOWL,SUM,0,0,0,0,0,7,0,21.616790056228638 +50,CUP,SUM,0,0,0,0,0,17,10,28.825676918029785 +50,SPOON,SUM,0,0,0,0,0,3,6,27.697877168655396 +50,,SUM,0,0,0,0,0,27,16,78.14034414291382 +50,, +51,, +51,BOWL,SUM,0,0,0,0,0,33,0,19.267395973205566 +51,CUP,SUM,0,0,0,0,2,231,57,175.2841091156006 +51,SPOON,SUM,0,0,0,0,12,333,1,73.26650190353394 +51,,SUM,0,0,0,0,14,597,58,267.8180069923401 +51,, +52,, +52,BOWL,SUM,0,0,0,0,0,25,0,18.59504199028015 +52,CUP,SUM,0,0,0,0,0,44,7,33.34682106971741 +52,SPOON,SUM,0,0,0,0,0,3,3,30.3904550075531 +52,,SUM,0,0,0,0,0,72,10,82.33231806755066 +52,, +53,, +53,BOWL,SUM,0,0,0,0,0,9,0,18.201112031936646 +53,CUP,SUM,0,0,0,0,2,12,10,21.703232049942017 +53,SPOON,SUM,0,0,0,0,0,4,6,28.269838094711304 +53,,SUM,0,0,0,0,2,25,16,68.17418217658997 +53,, +54,, +54,BOWL,SUM,0,0,0,0,0,810,42,143.06880903244019 +54,CUP,SUM,0,0,0,0,0,21,7,18.33565402030945 +54,SPOON,SUM,0,0,0,0,0,353,4,72.17308115959167 +54,,SUM,0,0,0,0,0,1184,53,233.5775442123413 +54,, +55,, +55,BOWL,SUM,0,0,0,0,22,94,8,42.56216287612915 +55,CUP,SUM,0,0,0,0,0,17,2,17.261083841323853 +55,SPOON,SUM,0,0,0,0,0,123,2,33.02058792114258 +55,,SUM,0,0,0,0,22,234,12,92.84383463859558 +55,, +56,, +56,BOWL,SUM,0,0,0,0,0,6,2,18.391302824020386 +56,CUP,SUM,0,0,0,0,0,16,3,23.689970016479492 +56,SPOON,SUM,0,0,0,0,0,36,1,27.69976806640625 +56,,SUM,0,0,0,0,0,58,6,69.78104090690613 +56,, +57,, +57,BOWL,SUM,0,0,0,0,2,18,0,19.263399839401245 +57,CUP,SUM,0,0,0,0,0,9,9,20.581286907196045 +57,SPOON,SUM,0,0,0,0,0,56,0,25.263183116912842 +57,,SUM,0,0,0,0,2,83,9,65.10786986351013 +57,, +58,, +58,BOWL,SUM,0,0,0,0,0,3,0,18.202200174331665 +58,CUP,SUM,0,0,0,0,0,6,0,16.952749013900757 +58,SPOON,SUM,0,0,0,0,0,29,2,22.43878197669983 +58,,SUM,0,0,0,0,0,38,2,57.59373116493225 +58,, +59,, +59,BOWL,SUM,1,0,1,0,6,800,80,0.0 +59,CUP,SUM,0,0,0,0,2,3,2,18.297735929489136 +59,SPOON,SUM,0,0,0,0,2,595,14,98.69569301605225 +59,,SUM,1,0,1,0,10,1398,96,116.99342894554138 +59,, +60,, +60,BOWL,SUM,0,0,0,0,0,432,14,71.34977293014526 +60,CUP,SUM,0,0,0,0,0,7,13,17.916653156280518 +60,SPOON,SUM,0,0,0,0,0,19,2,27.829638957977295 +60,,SUM,0,0,0,0,0,458,29,117.09606504440308 +60,, +61,, +61,BOWL,SUM,0,0,0,0,0,87,8,35.12587094306946 +61,CUP,SUM,0,0,0,0,0,34,0,17.228487014770508 +61,SPOON,SUM,0,0,0,0,0,0,0,21.51559615135193 +61,,SUM,0,0,0,0,0,121,8,73.8699541091919 +61,, +62,, +62,BOWL,SUM,0,0,0,0,0,17,4,21.695384979248047 +62,CUP,SUM,0,0,0,0,2,54,22,81.99774098396301 +62,SPOON,SUM,0,0,0,0,0,238,3,46.86587619781494 +62,,SUM,0,0,0,0,2,309,29,150.559002161026 +62,, +63,, +63,BOWL,SUM,0,0,0,0,0,1,0,18.543131113052368 +63,CUP,SUM,0,0,0,0,2,41,4,25.06510901451111 +63,SPOON,SUM,0,0,0,0,0,37,0,25.1600558757782 +63,,SUM,0,0,0,0,2,79,4,68.76829600334167 +63,, +64,, +64,BOWL,SUM,0,0,0,0,2,285,21,82.48004198074341 +64,CUP,SUM,0,0,0,0,0,19,8,20.899073839187622 +64,SPOON,SUM,0,0,0,0,0,500,0,77.11585998535156 +64,,SUM,0,0,0,0,2,804,29,180.4949758052826 +64,, +65,, +65,BOWL,SUM,0,0,0,0,4,301,24,74.97861790657043 +65,CUP,SUM,1,0,0,1,0,204,56,0.0 +65,SPOON,SUM,0,0,0,0,0,86,2,34.92611598968506 +65,,SUM,1,0,0,1,4,591,82,109.9047338962555 +65,, +66,, +66,BOWL,SUM,0,0,0,0,0,13,8,27.951735019683838 +66,CUP,SUM,1,0,1,0,0,226,112,0.0 +66,SPOON,SUM,0,0,0,0,0,94,2,29.71432614326477 +66,,SUM,1,0,1,0,0,333,122,57.66606116294861 +66,, +67,, +67,BOWL,SUM,0,0,0,0,0,8,0,19.07176899909973 +67,CUP,SUM,0,0,0,0,0,9,11,24.49334216117859 +67,SPOON,SUM,0,0,0,0,0,30,2,22.580965042114258 +67,,SUM,0,0,0,0,0,47,13,66.14607620239258 +67,, +68,, +68,BOWL,SUM,0,0,0,0,0,16,0,18.874002933502197 +68,CUP,SUM,0,0,0,0,4,10,0,18.37745499610901 +68,SPOON,SUM,0,0,0,0,0,2,0,21.10495686531067 +68,,SUM,0,0,0,0,4,28,0,58.356414794921875 +68,, +69,, +69,BOWL,SUM,1,0,1,0,2,655,88,0.0 +69,CUP,SUM,0,0,0,0,0,28,2,18.013226985931396 +69,SPOON,SUM,0,0,0,0,0,339,12,69.93874287605286 +69,,SUM,1,0,1,0,2,1022,102,87.95196986198425 +69,, +70,, +70,BOWL,SUM,0,0,0,0,0,172,11,46.67681694030762 +70,CUP,SUM,0,0,0,0,0,21,13,24.476346969604492 +70,SPOON,SUM,0,0,0,0,8,188,0,45.54172706604004 +70,,SUM,0,0,0,0,8,381,24,116.69489097595215 +70,, +71,, +71,BOWL,SUM,0,0,0,0,0,3,1,18.680123805999756 +71,CUP,SUM,0,0,0,0,0,6,2,17.088145971298218 +71,SPOON,SUM,0,0,0,0,0,79,0,29.07139015197754 +71,,SUM,0,0,0,0,0,88,3,64.83965992927551 +71,, +72,, +72,BOWL,SUM,0,0,0,0,6,15,0,20.870500802993774 +72,CUP,SUM,1,0,0,1,2,262,54,0.0 +72,SPOON,SUM,0,0,0,0,0,24,0,22.048234939575195 +72,,SUM,1,0,0,1,8,301,54,42.91873574256897 +72,, +73,, +73,BOWL,SUM,0,0,0,0,6,65,6,30.543373107910156 +73,CUP,SUM,0,0,0,0,0,22,4,23.957480907440186 +73,SPOON,SUM,0,0,0,0,0,31,0,25.025123119354248 +73,,SUM,0,0,0,0,6,118,10,79.52597713470459 +73,, +74,, +74,BOWL,SUM,0,0,0,0,0,41,0,21.73931312561035 +74,CUP,SUM,0,0,0,0,0,37,0,20.7624089717865 +74,SPOON,SUM,0,0,0,0,0,58,4,37.35265612602234 +74,,SUM,0,0,0,0,0,136,4,79.85437822341919 +74,, +75,, +75,BOWL,SUM,0,0,0,0,6,6,1,20.431413173675537 +75,CUP,SUM,0,0,0,0,0,3,6,17.490051984786987 +75,SPOON,SUM,0,0,0,0,2,92,2,29.677780151367188 +75,,SUM,0,0,0,0,8,101,9,67.59924530982971 +75,, +76,, +76,BOWL,SUM,0,0,0,0,0,22,0,18.899384021759033 +76,CUP,SUM,0,0,0,0,0,31,8,24.192622900009155 +76,SPOON,SUM,0,0,0,0,0,396,2,63.193575859069824 +76,,SUM,0,0,0,0,0,449,10,106.28558278083801 +76,, +77,, +77,BOWL,SUM,0,0,0,0,0,20,6,28.13282299041748 +77,CUP,SUM,0,0,0,0,0,193,42,126.77784490585327 +77,SPOON,SUM,0,0,0,0,4,5,0,23.286622047424316 +77,,SUM,0,0,0,0,4,218,48,178.19728994369507 +77,, +78,, +78,BOWL,SUM,0,0,0,0,0,14,0,18.745550870895386 +78,CUP,SUM,0,0,0,0,0,38,19,56.59209704399109 +78,SPOON,SUM,0,0,0,0,2,5,11,41.12331700325012 +78,,SUM,0,0,0,0,2,57,30,116.4609649181366 +78,, +79,, +79,BOWL,SUM,0,0,0,0,0,4,0,19.053426027297974 +79,CUP,SUM,0,0,0,0,0,22,6,18.179468870162964 +79,SPOON,SUM,0,0,0,0,86,89,1,83.00892400741577 +79,,SUM,0,0,0,0,86,115,7,120.24181890487671 +79,, +80,, +80,BOWL,SUM,0,0,0,0,2,13,0,20.074678897857666 +80,CUP,SUM,0,0,0,0,4,35,0,19.437592029571533 +80,SPOON,SUM,0,0,0,0,0,135,2,41.76032590866089 +80,,SUM,0,0,0,0,6,183,2,81.27259683609009 +80,, +81,, +81,BOWL,SUM,0,0,0,0,2,116,10,37.328553199768066 +81,CUP,SUM,0,0,0,0,0,36,4,21.389453887939453 +81,SPOON,SUM,0,0,0,0,32,107,0,53.54376196861267 +81,,SUM,0,0,0,0,34,259,14,112.26176905632019 +81,, +82,, +82,BOWL,SUM,0,0,0,0,74,40,0,66.02729797363281 +82,CUP,SUM,0,0,0,0,14,139,34,112.91299200057983 +82,SPOON,SUM,0,0,0,0,0,3,1,24.364217042922974 +82,,SUM,0,0,0,0,88,182,35,203.30450701713562 +82,, +83,, +83,BOWL,SUM,0,0,0,0,0,1,1,20.802573919296265 +83,CUP,SUM,1,0,1,0,0,203,112,0.0 +83,SPOON,SUM,0,0,0,0,0,12,0,22.104159116744995 +83,,SUM,1,0,1,0,0,216,113,42.90673303604126 +83,, +84,, +84,BOWL,SUM,0,0,0,0,0,43,1,24.68225884437561 +84,CUP,SUM,0,0,0,0,4,6,0,17.911784172058105 +84,SPOON,SUM,0,0,0,0,2,3,0,22.8821439743042 +84,,SUM,0,0,0,0,6,52,1,65.47618699073792 +84,, +85,, +85,BOWL,SUM,0,0,0,0,0,52,6,28.824821949005127 +85,CUP,SUM,0,0,0,0,0,32,10,27.87113094329834 +85,SPOON,SUM,0,0,0,0,0,107,0,32.52445602416992 +85,,SUM,0,0,0,0,0,191,16,89.22040891647339 +85,, +86,, +86,BOWL,SUM,0,0,0,0,0,6,0,18.89967703819275 +86,CUP,SUM,0,0,0,0,0,3,4,17.317458868026733 +86,SPOON,SUM,0,0,0,0,48,316,0,80.1266131401062 +86,,SUM,0,0,0,0,48,325,4,116.34374904632568 +86,, +87,, +87,BOWL,SUM,0,0,0,0,0,22,0,18.903094053268433 +87,CUP,SUM,1,0,0,1,0,291,54,0.0 +87,SPOON,SUM,0,0,0,0,0,22,0,22.19415807723999 +87,,SUM,1,0,0,1,0,335,54,41.09725213050842 +87,, +88,, +88,BOWL,SUM,0,0,0,0,6,9,1,23.303356170654297 +88,CUP,SUM,0,0,0,0,0,27,9,27.034379959106445 +88,SPOON,SUM,0,0,0,0,2,0,5,28.717829942703247 +88,,SUM,0,0,0,0,8,36,15,79.05556607246399 +88,, +89,, +89,BOWL,SUM,1,0,1,0,2,915,84,0.0 +89,CUP,SUM,0,0,0,0,0,40,3,21.278531074523926 +89,SPOON,SUM,0,0,0,0,0,56,8,35.22840714454651 +89,,SUM,1,0,1,0,2,1011,95,56.506938219070435 +89,, +90,, +90,BOWL,SUM,0,0,0,0,0,23,1,19.32046389579773 +90,CUP,SUM,0,0,0,0,0,6,10,20.942237854003906 +90,SPOON,SUM,0,0,0,0,0,57,1,28.738697052001953 +90,,SUM,0,0,0,0,0,86,12,69.00139880180359 +90,, +91,, +91,BOWL,SUM,0,0,0,0,0,16,4,22.04365110397339 +91,CUP,SUM,0,0,0,0,0,19,0,17.575266122817993 +91,SPOON,SUM,0,0,0,0,2,24,2,28.109542846679688 +91,,SUM,0,0,0,0,2,59,6,67.72846007347107 +91,, +92,, +92,BOWL,SUM,0,0,0,0,34,25,4,43.284982204437256 +92,CUP,SUM,0,0,0,0,0,15,10,24.284455060958862 +92,SPOON,SUM,0,0,0,0,0,151,1,36.39458107948303 +92,,SUM,0,0,0,0,34,191,15,103.96401834487915 +92,, +93,, +93,BOWL,SUM,0,0,0,0,0,386,40,97.30277299880981 +93,CUP,SUM,0,0,0,0,0,17,2,17.47747802734375 +93,SPOON,SUM,0,0,0,0,0,222,2,43.46848797798157 +93,,SUM,0,0,0,0,0,625,44,158.24873900413513 +93,, +94,, +94,BOWL,SUM,0,0,0,0,0,20,2,24.340241193771362 +94,CUP,SUM,0,0,0,0,0,184,46,133.4968090057373 +94,SPOON,SUM,0,0,0,0,8,91,1,37.37036418914795 +94,,SUM,0,0,0,0,8,295,49,195.20741438865662 +94,, +95,, +95,BOWL,SUM,0,0,0,0,10,33,0,24.895408153533936 +95,CUP,SUM,0,0,0,0,0,6,2,17.247371912002563 +95,SPOON,SUM,0,0,0,0,0,1250,1,162.2361330986023 +95,,SUM,0,0,0,0,10,1289,3,204.3789131641388 +95,, +96,, +96,BOWL,SUM,0,0,0,0,0,40,1,22.02469491958618 +96,CUP,SUM,0,0,0,0,0,8,4,17.410694122314453 +96,SPOON,SUM,0,0,0,0,2,273,0,53.193723917007446 +96,,SUM,0,0,0,0,2,321,5,92.62911295890808 +96,, +97,, +97,BOWL,SUM,0,0,0,0,0,16,2,18.943340063095093 +97,CUP,SUM,0,0,0,0,0,23,5,18.07484197616577 +97,SPOON,SUM,0,0,0,0,0,8,0,22.040590047836304 +97,,SUM,0,0,0,0,0,47,7,59.05877208709717 +97,, +98,, +98,BOWL,SUM,0,0,0,0,0,52,2,22.945404052734375 +98,CUP,SUM,0,0,0,0,0,32,10,43.64822793006897 +98,SPOON,SUM,0,0,0,0,0,88,4,32.0605890750885 +98,,SUM,0,0,0,0,0,172,16,98.65422105789185 +98,, +99,, +99,BOWL,SUM,0,0,0,0,6,24,0,20.66563391685486 +99,CUP,SUM,0,0,0,0,0,8,1,17.010490894317627 +99,SPOON,SUM,0,0,0,0,0,9,4,25.173081874847412 +99,,SUM,0,0,0,0,6,41,5,62.8492066860199 +99,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_10.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_10.csv new file mode 100644 index 0000000000..04b23ccc09 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_10.csv @@ -0,0 +1,303 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,0,7,2,13.6941978931427 +0,CUP,SUM,0,0,0,0,0,16,3,9.333943843841553 +0,SPOON,SUM,0,0,0,0,0,16,0,13.62615180015564 +0,,SUM,0,0,0,0,0,39,5,36.65429353713989 +0,, +1,, +1,BOWL,SUM,0,0,0,0,8,33,0,13.70945119857788 +1,CUP,SUM,0,0,0,0,0,24,2,8.480520009994507 +1,SPOON,SUM,1,0,1,0,0,1650,0,0.0 +1,,SUM,1,0,1,0,8,1707,2,22.189971208572388 +1,, +2,, +2,BOWL,SUM,0,0,0,0,6,8,0,11.835462808609009 +2,CUP,SUM,0,0,0,0,8,15,0,12.106986999511719 +2,SPOON,SUM,0,0,0,0,0,521,0,40.613906145095825 +2,,SUM,0,0,0,0,14,544,0,64.55635595321655 +2,, +3,, +3,BOWL,SUM,0,0,0,0,0,134,3,17.867616891860962 +3,CUP,SUM,0,0,0,0,0,2,4,8.302978038787842 +3,SPOON,SUM,0,0,0,0,0,26,0,13.729882001876831 +3,,SUM,0,0,0,0,0,162,7,39.900476932525635 +3,, +4,, +4,BOWL,SUM,0,0,0,0,0,59,0,12.143081903457642 +4,CUP,SUM,0,0,0,0,2,10,5,12.041576147079468 +4,SPOON,SUM,0,0,0,0,2,39,0,14.365671873092651 +4,,SUM,0,0,0,0,4,108,5,38.55032992362976 +4,, +5,, +5,BOWL,SUM,0,0,0,0,0,5,0,9.987602949142456 +5,CUP,SUM,0,0,0,0,0,7,6,8.707391023635864 +5,SPOON,SUM,0,0,0,0,0,5,0,13.368759870529175 +5,,SUM,0,0,0,0,0,17,6,32.063753843307495 +5,, +6,, +6,BOWL,SUM,0,0,0,0,2,82,0,14.364289045333862 +6,CUP,SUM,0,0,0,0,2,44,5,10.363455057144165 +6,SPOON,SUM,0,0,0,0,0,179,0,22.39747905731201 +6,,SUM,0,0,0,0,4,305,5,47.12522315979004 +6,, +7,, +7,BOWL,SUM,0,0,0,0,4,50,0,13.785452127456665 +7,CUP,SUM,0,0,0,0,0,7,2,8.658258199691772 +7,SPOON,SUM,1,0,1,0,10,1581,0,0.0 +7,,SUM,1,0,1,0,14,1638,2,22.443710327148438 +7,, +8,, +8,BOWL,SUM,0,0,0,0,0,22,0,10.416828155517578 +8,CUP,SUM,0,0,0,0,0,7,0,8.44684910774231 +8,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +8,,SUM,1,0,1,0,0,1610,0,18.863677263259888 +8,, +9,, +9,BOWL,SUM,0,0,0,0,0,145,1,18.40223503112793 +9,CUP,SUM,0,0,0,0,0,5,0,8.263492107391357 +9,SPOON,SUM,0,0,0,0,10,15,0,18.083956956863403 +9,,SUM,0,0,0,0,10,165,1,44.74968409538269 +9,, +10,, +10,BOWL,SUM,0,0,0,0,16,103,2,21.628081798553467 +10,CUP,SUM,0,0,0,0,0,14,0,8.613420009613037 +10,SPOON,SUM,1,0,1,0,0,1609,0,0.0 +10,,SUM,1,0,1,0,16,1726,2,30.241501808166504 +10,, +11,, +11,BOWL,SUM,0,0,0,0,0,28,0,10.458186864852905 +11,CUP,SUM,1,0,1,0,0,435,109,0.0 +11,SPOON,SUM,0,0,0,0,0,108,0,18.824039936065674 +11,,SUM,1,0,1,0,0,571,109,29.28222680091858 +11,, +12,, +12,BOWL,SUM,0,0,0,0,218,230,0,118.48518490791321 +12,CUP,SUM,1,0,0,1,0,253,51,0.0 +12,SPOON,SUM,0,0,0,0,0,110,0,18.59145212173462 +12,,SUM,1,0,0,1,218,593,51,137.07663702964783 +12,, +13,, +13,BOWL,SUM,0,0,0,0,0,19,1,11.798259019851685 +13,CUP,SUM,0,0,0,0,4,48,26,31.42843794822693 +13,SPOON,SUM,0,0,0,0,0,187,0,23.71431612968445 +13,,SUM,0,0,0,0,4,254,27,66.94101309776306 +13,, +14,, +14,BOWL,SUM,0,0,0,0,0,22,0,10.439287900924683 +14,CUP,SUM,0,0,0,0,2,10,6,9.435528993606567 +14,SPOON,SUM,0,0,0,0,0,189,0,22.70912504196167 +14,,SUM,0,0,0,0,2,221,6,42.58394193649292 +14,, +15,, +15,BOWL,SUM,0,0,0,0,0,24,0,10.57682204246521 +15,CUP,SUM,0,0,0,0,0,15,1,8.648187160491943 +15,SPOON,SUM,0,0,0,0,0,88,0,16.928336143493652 +15,,SUM,0,0,0,0,0,127,1,36.153345346450806 +15,, +16,, +16,BOWL,SUM,1,0,1,0,38,1659,0,0.0 +16,CUP,SUM,1,0,0,1,0,184,59,0.0 +16,SPOON,SUM,0,0,0,0,2,142,0,21.005160093307495 +16,,SUM,2,0,1,1,40,1985,59,21.005160093307495 +16,, +17,, +17,BOWL,SUM,1,0,1,0,2,1584,0,0.0 +17,CUP,SUM,0,0,0,0,2,48,0,10.105937004089355 +17,SPOON,SUM,0,0,0,0,0,4,0,13.461970090866089 +17,,SUM,1,0,1,0,4,1636,0,23.567907094955444 +17,, +18,, +18,BOWL,SUM,0,0,0,0,0,18,0,10.290047883987427 +18,CUP,SUM,0,0,0,0,2,15,5,9.651917934417725 +18,SPOON,SUM,0,0,0,0,0,111,0,19.064453125 +18,,SUM,0,0,0,0,2,144,5,39.00641894340515 +18,, +19,, +19,BOWL,SUM,0,0,0,0,60,59,0,38.55989599227905 +19,CUP,SUM,1,0,0,1,0,274,51,0.0 +19,SPOON,SUM,0,0,0,0,0,41,0,14.975733995437622 +19,,SUM,1,0,0,1,60,374,51,53.535629987716675 +19,, +20,, +20,BOWL,SUM,0,0,0,0,0,203,2,22.810291051864624 +20,CUP,SUM,0,0,0,0,0,16,2,9.135678052902222 +20,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +20,,SUM,1,0,1,0,0,1800,4,31.945969104766846 +20,, +21,, +21,BOWL,SUM,0,0,0,0,0,145,0,17.655418872833252 +21,CUP,SUM,0,0,0,0,0,3,9,8.81913685798645 +21,SPOON,SUM,0,0,0,0,0,603,0,46.362354040145874 +21,,SUM,0,0,0,0,0,751,9,72.83690977096558 +21,, +22,, +22,BOWL,SUM,0,0,0,0,2,16,1,12.430530071258545 +22,CUP,SUM,0,0,0,0,2,19,3,9.692581176757813 +22,SPOON,SUM,0,0,0,0,2,3,0,14.1003999710083 +22,,SUM,0,0,0,0,6,38,4,36.22351121902466 +22,, +23,, +23,BOWL,SUM,0,0,0,0,6,2,1,13.386927843093872 +23,CUP,SUM,0,0,0,0,0,0,2,8.298884153366089 +23,SPOON,SUM,0,0,0,0,2,2,0,13.550420045852661 +23,,SUM,0,0,0,0,8,4,3,35.23623204231262 +23,, +24,, +24,BOWL,SUM,0,0,0,0,0,22,0,10.591440916061401 +24,CUP,SUM,0,0,0,0,0,18,0,8.672574996948242 +24,SPOON,SUM,0,0,0,0,0,27,2,14.019765138626099 +24,,SUM,0,0,0,0,0,67,2,33.28378105163574 +24,, +25,, +25,BOWL,SUM,0,0,0,0,0,106,0,15.669369220733643 +25,CUP,SUM,0,0,0,0,16,47,2,16.952935934066772 +25,SPOON,SUM,0,0,0,0,0,184,1,22.614933013916016 +25,,SUM,0,0,0,0,16,337,3,55.23723816871643 +25,, +26,, +26,BOWL,SUM,0,0,0,0,0,21,0,10.61534595489502 +26,CUP,SUM,0,0,0,0,0,8,4,8.656656980514526 +26,SPOON,SUM,0,0,0,0,58,110,2,43.91802406311035 +26,,SUM,0,0,0,0,58,139,6,63.1900269985199 +26,, +27,, +27,BOWL,SUM,0,0,0,0,2,136,0,18.231177806854248 +27,CUP,SUM,0,0,0,0,2,18,3,9.307600021362305 +27,SPOON,SUM,0,0,0,0,2,200,2,24.996088981628418 +27,,SUM,0,0,0,0,6,354,5,52.53486680984497 +27,, +28,, +28,BOWL,SUM,0,0,0,0,0,239,0,22.768765926361084 +28,CUP,SUM,1,0,0,1,2,204,63,0.0 +28,SPOON,SUM,0,0,0,0,0,10,0,13.245285987854004 +28,,SUM,1,0,0,1,2,453,63,36.01405191421509 +28,, +29,, +29,BOWL,SUM,0,0,0,0,0,104,0,15.855569124221802 +29,CUP,SUM,0,0,0,0,0,25,2,8.855814933776855 +29,SPOON,SUM,0,0,0,0,0,265,0,28.328122854232788 +29,,SUM,0,0,0,0,0,394,2,53.039506912231445 +29,, +30,, +30,BOWL,SUM,0,0,0,0,4,198,3,23.35259199142456 +30,CUP,SUM,0,0,0,0,0,8,6,9.053953170776367 +30,SPOON,SUM,1,0,1,0,0,1583,0,0.0 +30,,SUM,1,0,1,0,4,1789,9,32.40654516220093 +30,, +31,, +31,BOWL,SUM,0,0,0,0,0,27,0,10.59089708328247 +31,CUP,SUM,0,0,0,0,0,13,0,8.432713031768799 +31,SPOON,SUM,0,0,0,0,10,165,0,25.710708141326904 +31,,SUM,0,0,0,0,10,205,0,44.734318256378174 +31,, +32,, +32,BOWL,SUM,0,0,0,0,2,40,0,12.97121810913086 +32,CUP,SUM,0,0,0,0,2,9,3,9.616924047470093 +32,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +32,,SUM,1,0,1,0,4,1630,3,22.588142156600952 +32,, +33,, +33,BOWL,SUM,0,0,0,0,24,124,0,27.575093984603882 +33,CUP,SUM,0,0,0,0,0,19,4,9.288878917694092 +33,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +33,,SUM,1,0,1,0,24,1724,4,36.863972902297974 +33,, +34,, +34,BOWL,SUM,0,0,0,0,0,32,0,11.326689004898071 +34,CUP,SUM,0,0,0,0,0,25,0,8.987281084060669 +34,SPOON,SUM,0,0,0,0,0,338,0,32.1712441444397 +34,,SUM,0,0,0,0,0,395,0,52.48521423339844 +34,, +35,, +35,BOWL,SUM,0,0,0,0,2,26,1,11.593909978866577 +35,CUP,SUM,0,0,0,0,8,14,10,14.586183786392212 +35,SPOON,SUM,1,0,1,0,0,1582,0,0.0 +35,,SUM,1,0,1,0,10,1622,11,26.18009376525879 +35,, +36,, +36,BOWL,SUM,0,0,0,0,0,18,0,10.800052165985107 +36,CUP,SUM,0,0,0,0,2,13,2,9.548226118087769 +36,SPOON,SUM,0,0,0,0,0,54,0,16.030384063720703 +36,,SUM,0,0,0,0,2,85,2,36.37866234779358 +36,, +37,, +37,BOWL,SUM,0,0,0,0,0,76,0,14.654183149337769 +37,CUP,SUM,0,0,0,0,2,11,0,9.722316980361938 +37,SPOON,SUM,0,0,0,0,0,1,1,14.917771100997925 +37,,SUM,0,0,0,0,2,88,1,39.29427123069763 +37,, +38,, +38,BOWL,SUM,0,0,0,0,56,80,0,38.50930690765381 +38,CUP,SUM,1,0,0,1,2,199,51,0.0 +38,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +38,,SUM,2,0,1,1,58,1860,51,38.50930690765381 +38,, +39,, +39,BOWL,SUM,0,0,0,0,2,94,1,16.51201605796814 +39,CUP,SUM,0,0,0,0,0,30,14,20.667243003845215 +39,SPOON,SUM,0,0,0,0,0,182,0,22.782708883285522 +39,,SUM,0,0,0,0,2,306,15,59.96196794509888 +39,, +40,, +40,BOWL,SUM,0,0,0,0,2,15,1,12.705702066421509 +40,CUP,SUM,0,0,0,0,0,9,3,8.801445007324219 +40,SPOON,SUM,0,0,0,0,0,21,0,14.21362590789795 +40,,SUM,0,0,0,0,2,45,4,35.72077298164368 +40,, +41,, +41,BOWL,SUM,0,0,0,0,2,33,0,11.951415061950684 +41,CUP,SUM,0,0,0,0,0,7,6,9.382122993469238 +41,SPOON,SUM,0,0,0,0,8,21,0,17.624253034591675 +41,,SUM,0,0,0,0,10,61,6,38.9577910900116 +41,, +42,, +42,BOWL,SUM,0,0,0,0,10,129,0,21.329383850097656 +42,CUP,SUM,0,0,0,0,0,9,0,8.865937948226929 +42,SPOON,SUM,0,0,0,0,0,67,0,16.15058207511902 +42,,SUM,0,0,0,0,10,205,0,46.3459038734436 +42,, +43,, +43,BOWL,SUM,0,0,0,0,2,58,0,13.266754150390625 +43,CUP,SUM,1,0,0,1,0,242,51,0.0 +43,SPOON,SUM,0,0,0,0,0,2,0,13.267374038696289 +43,,SUM,1,0,0,1,2,302,51,26.534128189086914 +43,, +44,, +44,BOWL,SUM,1,0,1,0,6,1421,24,0.0 +44,CUP,SUM,1,0,0,1,0,201,56,0.0 +44,SPOON,SUM,0,0,0,0,12,163,0,28.571397066116333 +44,,SUM,2,0,1,1,18,1785,80,28.571397066116333 +44,, +45,, +45,BOWL,SUM,0,0,0,0,0,18,2,10.886497974395752 +45,CUP,SUM,0,0,0,0,0,53,16,27.291529893875122 +45,SPOON,SUM,0,0,0,0,0,9,0,13.514336109161377 +45,,SUM,0,0,0,0,0,80,18,51.69236397743225 +45,, +46,, +46,BOWL,SUM,0,0,0,0,0,34,0,11.153945922851563 +46,CUP,SUM,0,0,0,0,0,5,0,8.38342022895813 +46,SPOON,SUM,0,0,0,0,0,14,1,13.87653398513794 +46,,SUM,0,0,0,0,0,53,1,33.41390013694763 +46,, +47,, +47,BOWL,SUM,0,0,0,0,0,13,0,10.507174015045166 +47,CUP,SUM,0,0,0,0,4,21,4,10.982290983200073 +47,SPOON,SUM,0,0,0,0,0,33,0,14.597734928131104 +47,,SUM,0,0,0,0,4,67,4,36.08719992637634 +47,, +48,, +48,BOWL,SUM,0,0,0,0,0,94,0,14.392702102661133 +48,CUP,SUM,0,0,0,0,6,83,5,15.40494704246521 +48,SPOON,SUM,1,0,1,0,2,1701,0,0.0 +48,,SUM,1,0,1,0,8,1878,5,29.797649145126343 +48,, +49,, +49,BOWL,SUM,0,0,0,0,0,13,2,10.99905800819397 +49,CUP,SUM,0,0,0,0,0,4,0,8.912223100662231 +49,SPOON,SUM,0,0,0,0,0,20,0,14.387133121490479 +49,,SUM,0,0,0,0,0,37,2,34.29841423034668 +49,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_12.5.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_12.5.csv new file mode 100644 index 0000000000..9276f51175 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_12.5.csv @@ -0,0 +1,303 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +50,, +50,BOWL,SUM,0,0,0,0,0,7,0,10.434447050094604 +50,CUP,SUM,0,0,0,0,16,14,1,16.3244731426239 +50,SPOON,SUM,0,0,0,0,0,218,0,25.249832153320313 +50,,SUM,0,0,0,0,16,239,1,52.00875234603882 +50,, +51,, +51,BOWL,SUM,0,0,0,0,2,21,0,11.471933841705322 +51,CUP,SUM,1,0,0,1,2,222,69,0.0 +51,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +51,,SUM,2,0,1,1,4,1824,69,11.471933841705322 +51,, +52,, +52,BOWL,SUM,0,0,0,0,0,1,0,10.088486909866333 +52,CUP,SUM,0,0,0,0,0,22,14,17.36380410194397 +52,SPOON,SUM,0,0,0,0,2,13,0,14.04788088798523 +52,,SUM,0,0,0,0,2,36,14,41.50017189979553 +52,, +53,, +53,BOWL,SUM,0,0,0,0,0,37,0,12.183252811431885 +53,CUP,SUM,1,0,0,1,0,251,60,0.0 +53,SPOON,SUM,0,0,0,0,0,70,0,16.63511085510254 +53,,SUM,1,0,0,1,0,358,60,28.818363666534424 +53,, +54,, +54,BOWL,SUM,0,0,0,0,0,12,0,10.514291048049927 +54,CUP,SUM,1,0,0,1,0,197,63,0.0 +54,SPOON,SUM,0,0,0,0,0,63,2,15.690797090530396 +54,,SUM,1,0,0,1,0,272,65,26.205088138580322 +54,, +55,, +55,BOWL,SUM,0,0,0,0,0,3,1,10.25860595703125 +55,CUP,SUM,0,0,0,0,10,29,3,14.890743017196655 +55,SPOON,SUM,0,0,0,0,0,92,0,17.543906927108765 +55,,SUM,0,0,0,0,10,124,4,42.69325590133667 +55,, +56,, +56,BOWL,SUM,0,0,0,0,0,154,10,23.02497386932373 +56,CUP,SUM,1,0,0,1,0,220,57,0.0 +56,SPOON,SUM,0,0,0,0,10,76,0,20.262401819229126 +56,,SUM,1,0,0,1,10,450,67,43.287375688552856 +56,, +57,, +57,BOWL,SUM,0,0,0,0,2,4,0,11.009602069854736 +57,CUP,SUM,0,0,0,0,0,28,2,9.392124891281128 +57,SPOON,SUM,0,0,0,0,0,29,0,13.951495170593262 +57,,SUM,0,0,0,0,2,61,2,34.353222131729126 +57,, +58,, +58,BOWL,SUM,1,0,1,0,6,1320,34,0.0 +58,CUP,SUM,0,0,0,0,0,7,2,8.625355005264282 +58,SPOON,SUM,0,0,0,0,0,375,0,32.74223613739014 +58,,SUM,1,0,1,0,6,1702,36,41.36759114265442 +58,, +59,, +59,BOWL,SUM,0,0,0,0,0,33,2,11.487753868103027 +59,CUP,SUM,0,0,0,0,4,20,2,10.49406099319458 +59,SPOON,SUM,0,0,0,0,0,24,0,13.959550857543945 +59,,SUM,0,0,0,0,4,77,4,35.94136571884155 +59,, +60,, +60,BOWL,SUM,0,0,0,0,2,59,0,13.188676118850708 +60,CUP,SUM,0,0,0,0,0,11,0,8.658782005310059 +60,SPOON,SUM,0,0,0,0,2,6,0,14.637680053710938 +60,,SUM,0,0,0,0,4,76,0,36.485138177871704 +60,, +61,, +61,BOWL,SUM,0,0,0,0,4,20,0,12.246095895767212 +61,CUP,SUM,0,0,0,0,0,4,3,9.090544939041138 +61,SPOON,SUM,0,0,0,0,0,53,0,15.547513008117676 +61,,SUM,0,0,0,0,4,77,3,36.884153842926025 +61,, +62,, +62,BOWL,SUM,0,0,0,0,0,11,0,10.280903100967407 +62,CUP,SUM,0,0,0,0,10,42,2,14.611223936080933 +62,SPOON,SUM,0,0,0,0,2,91,0,18.183454990386963 +62,,SUM,0,0,0,0,12,144,2,43.0755820274353 +62,, +63,, +63,BOWL,SUM,0,0,0,0,0,9,0,10.36107611656189 +63,CUP,SUM,0,0,0,0,0,5,1,8.653022050857544 +63,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +63,,SUM,1,0,1,0,0,1595,1,19.014098167419434 +63,, +64,, +64,BOWL,SUM,0,0,0,0,0,11,4,12.222034215927124 +64,CUP,SUM,0,0,0,0,0,5,0,8.572192907333374 +64,SPOON,SUM,0,0,0,0,0,25,0,13.872895002365112 +64,,SUM,0,0,0,0,0,41,4,34.66712212562561 +64,, +65,, +65,BOWL,SUM,1,0,1,0,0,1387,24,0.0 +65,CUP,SUM,1,0,0,1,0,199,63,0.0 +65,SPOON,SUM,0,0,0,0,0,83,0,18.466357946395874 +65,,SUM,2,0,1,1,0,1669,87,18.466357946395874 +65,, +66,, +66,BOWL,SUM,0,0,0,0,0,28,0,11.366482973098755 +66,CUP,SUM,1,0,0,1,0,196,53,0.0 +66,SPOON,SUM,0,0,0,0,0,905,0,63.54792904853821 +66,,SUM,1,0,0,1,0,1129,53,74.91441202163696 +66,, +67,, +67,BOWL,SUM,0,0,0,0,0,8,0,10.102499008178711 +67,CUP,SUM,1,0,0,1,56,255,59,0.0 +67,SPOON,SUM,0,0,0,0,0,172,2,22.92682385444641 +67,,SUM,1,0,0,1,56,435,61,33.02932286262512 +67,, +68,, +68,BOWL,SUM,0,0,0,0,4,1,0,11.77514100074768 +68,CUP,SUM,1,0,0,1,0,202,55,0.0 +68,SPOON,SUM,0,0,0,0,0,9,0,13.560734987258911 +68,,SUM,1,0,0,1,4,212,55,25.335875988006592 +68,, +69,, +69,BOWL,SUM,0,0,0,0,2,69,0,14.64009690284729 +69,CUP,SUM,0,0,0,0,0,73,33,45.77504205703735 +69,SPOON,SUM,0,0,0,0,4,1,0,14.60863184928894 +69,,SUM,0,0,0,0,6,143,33,75.02377080917358 +69,, +70,, +70,BOWL,SUM,0,0,0,0,0,8,0,10.452875852584839 +70,CUP,SUM,0,0,0,0,16,84,41,61.3756890296936 +70,SPOON,SUM,0,0,0,0,0,52,0,14.634735822677612 +70,,SUM,0,0,0,0,16,144,41,86.46330070495605 +70,, +71,, +71,BOWL,SUM,0,0,0,0,0,6,0,10.263589859008789 +71,CUP,SUM,0,0,0,0,2,9,0,9.509284973144531 +71,SPOON,SUM,1,0,1,0,2,1581,0,0.0 +71,,SUM,1,0,1,0,4,1596,0,19.77287483215332 +71,, +72,, +72,BOWL,SUM,0,0,0,0,0,4,0,10.793458938598633 +72,CUP,SUM,0,0,0,0,0,10,0,9.276982069015503 +72,SPOON,SUM,0,0,0,0,6,11,2,16.037880897521973 +72,,SUM,0,0,0,0,6,25,2,36.10832190513611 +72,, +73,, +73,BOWL,SUM,0,0,0,0,0,27,0,10.94678020477295 +73,CUP,SUM,0,0,0,0,0,15,0,8.828031063079834 +73,SPOON,SUM,0,0,0,0,0,33,2,15.887587070465088 +73,,SUM,0,0,0,0,0,75,2,35.66239833831787 +73,, +74,, +74,BOWL,SUM,0,0,0,0,2,25,0,11.772248029708862 +74,CUP,SUM,0,0,0,0,0,13,3,8.985986948013306 +74,SPOON,SUM,0,0,0,0,4,4,0,15.02386212348938 +74,,SUM,0,0,0,0,6,42,3,35.78209710121155 +74,, +75,, +75,BOWL,SUM,1,0,1,0,0,1438,19,0.0 +75,CUP,SUM,0,0,0,0,6,4,4,10.873118877410889 +75,SPOON,SUM,0,0,0,0,0,56,0,15.754966020584106 +75,,SUM,1,0,1,0,6,1498,23,26.628084897994995 +75,, +76,, +76,BOWL,SUM,0,0,0,0,0,15,0,10.652849912643433 +76,CUP,SUM,0,0,0,0,0,15,7,10.943670988082886 +76,SPOON,SUM,0,0,0,0,0,460,0,37.883376121520996 +76,,SUM,0,0,0,0,0,490,7,59.479897022247314 +76,, +77,, +77,BOWL,SUM,0,0,0,0,0,10,0,10.367499113082886 +77,CUP,SUM,0,0,0,0,0,1,0,8.131698846817017 +77,SPOON,SUM,0,0,0,0,2,49,0,16.472914934158325 +77,,SUM,0,0,0,0,2,60,0,34.97211289405823 +77,, +78,, +78,BOWL,SUM,0,0,0,0,0,13,0,10.319906949996948 +78,CUP,SUM,0,0,0,0,0,33,2,12.335423946380615 +78,SPOON,SUM,0,0,0,0,0,3,0,13.729816913604736 +78,,SUM,0,0,0,0,0,49,2,36.3851478099823 +78,, +79,, +79,BOWL,SUM,0,0,0,0,2,53,0,13.750405073165894 +79,CUP,SUM,0,0,0,0,0,33,0,9.700596809387207 +79,SPOON,SUM,0,0,0,0,0,4,0,13.503041982650757 +79,,SUM,0,0,0,0,2,90,0,36.95404386520386 +79,, +80,, +80,BOWL,SUM,0,0,0,0,114,703,1,96.12811493873596 +80,CUP,SUM,1,0,0,1,0,199,56,0.0 +80,SPOON,SUM,0,0,0,0,0,0,0,13.554277896881104 +80,,SUM,1,0,0,1,114,902,57,109.68239283561707 +80,, +81,, +81,BOWL,SUM,0,0,0,0,56,21,0,37.797455072402954 +81,CUP,SUM,0,0,0,0,0,10,4,9.214473962783813 +81,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +81,,SUM,1,0,1,0,56,1612,4,47.01192903518677 +81,, +82,, +82,BOWL,SUM,0,0,0,0,0,57,2,13.260775089263916 +82,CUP,SUM,0,0,0,0,0,34,6,10.14723014831543 +82,SPOON,SUM,0,0,0,0,0,27,0,14.331840991973877 +82,,SUM,0,0,0,0,0,118,8,37.73984622955322 +82,, +83,, +83,BOWL,SUM,0,0,0,0,62,61,0,40.6342670917511 +83,CUP,SUM,0,0,0,0,0,39,0,9.699576139450073 +83,SPOON,SUM,0,0,0,0,0,25,0,14.159082889556885 +83,,SUM,0,0,0,0,62,125,0,64.49292612075806 +83,, +84,, +84,BOWL,SUM,0,0,0,0,0,172,0,18.919885873794556 +84,CUP,SUM,0,0,0,0,0,21,0,9.06815218925476 +84,SPOON,SUM,1,0,1,0,0,1582,0,0.0 +84,,SUM,1,0,1,0,0,1775,0,27.988038063049316 +84,, +85,, +85,BOWL,SUM,0,0,0,0,0,22,0,10.9498450756073 +85,CUP,SUM,0,0,0,0,0,14,5,8.810625076293945 +85,SPOON,SUM,0,0,0,0,0,84,0,17.684432983398438 +85,,SUM,0,0,0,0,0,120,5,37.44490313529968 +85,, +86,, +86,BOWL,SUM,0,0,0,0,18,42,1,20.991352081298828 +86,CUP,SUM,1,0,0,1,0,211,59,0.0 +86,SPOON,SUM,0,0,0,0,0,5,0,13.468976974487305 +86,,SUM,1,0,0,1,18,258,60,34.46032905578613 +86,, +87,, +87,BOWL,SUM,0,0,0,0,56,71,2,43.03990387916565 +87,CUP,SUM,0,0,0,0,0,21,2,10.762330055236816 +87,SPOON,SUM,0,0,0,0,0,1,0,13.51143503189087 +87,,SUM,0,0,0,0,56,93,4,67.31366896629333 +87,, +88,, +88,BOWL,SUM,0,0,0,0,0,114,12,21.80426597595215 +88,CUP,SUM,0,0,0,0,2,19,2,10.084789991378784 +88,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +88,,SUM,1,0,1,0,2,1714,14,31.889055967330933 +88,, +89,, +89,BOWL,SUM,0,0,0,0,2,21,0,11.616353034973145 +89,CUP,SUM,0,0,0,0,0,19,3,9.496047019958496 +89,SPOON,SUM,0,0,0,0,0,19,2,14.64622187614441 +89,,SUM,0,0,0,0,2,59,5,35.75862193107605 +89,, +90,, +90,BOWL,SUM,0,0,0,0,2,43,1,14.181122064590454 +90,CUP,SUM,0,0,0,0,0,7,1,8.824935913085938 +90,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +90,,SUM,1,0,1,0,2,1631,2,23.00605797767639 +90,, +91,, +91,BOWL,SUM,0,0,0,0,0,13,0,10.653243064880371 +91,CUP,SUM,0,0,0,0,2,7,10,11.417168855667114 +91,SPOON,SUM,0,0,0,0,2,24,0,14.932386875152588 +91,,SUM,0,0,0,0,4,44,10,37.00279879570007 +91,, +92,, +92,BOWL,SUM,0,0,0,0,0,18,0,10.543165922164917 +92,CUP,SUM,0,0,0,0,10,18,2,13.387519836425781 +92,SPOON,SUM,0,0,0,0,0,34,0,15.347402095794678 +92,,SUM,0,0,0,0,10,70,2,39.278087854385376 +92,, +93,, +93,BOWL,SUM,0,0,0,0,56,985,2,89.4375867843628 +93,CUP,SUM,1,0,0,1,0,215,52,0.0 +93,SPOON,SUM,0,0,0,0,0,119,0,20.691253900527954 +93,,SUM,1,0,0,1,56,1319,54,110.12884068489075 +93,, +94,, +94,BOWL,SUM,0,0,0,0,60,25,1,39.65346312522888 +94,CUP,SUM,0,0,0,0,0,13,4,9.163373231887817 +94,SPOON,SUM,1,0,1,0,0,1591,0,0.0 +94,,SUM,1,0,1,0,60,1629,5,48.8168363571167 +94,, +95,, +95,BOWL,SUM,0,0,0,0,0,52,0,12.651877164840698 +95,CUP,SUM,0,0,0,0,0,24,14,13.351801872253418 +95,SPOON,SUM,0,0,0,0,0,7,0,13.48208498954773 +95,,SUM,0,0,0,0,0,83,14,39.485764026641846 +95,, +96,, +96,BOWL,SUM,0,0,0,0,4,1,0,11.504374027252197 +96,CUP,SUM,0,0,0,0,0,22,4,9.091797828674316 +96,SPOON,SUM,0,0,0,0,0,76,0,16.966641902923584 +96,,SUM,0,0,0,0,4,99,4,37.5628137588501 +96,, +97,, +97,BOWL,SUM,0,0,0,0,6,29,0,12.77753496170044 +97,CUP,SUM,0,0,0,0,2,43,2,11.147116899490356 +97,SPOON,SUM,1,0,1,0,0,1587,0,0.0 +97,,SUM,1,0,1,0,8,1659,2,23.924651861190796 +97,, +98,, +98,BOWL,SUM,0,0,0,0,0,29,0,11.85982084274292 +98,CUP,SUM,0,0,0,0,0,4,1,8.366240978240967 +98,SPOON,SUM,0,0,0,0,0,264,0,26.839765071868896 +98,,SUM,0,0,0,0,0,297,1,47.06582689285278 +98,, +99,, +99,BOWL,SUM,0,0,0,0,2,456,2,36.29320788383484 +99,CUP,SUM,0,0,0,0,2,46,11,23.06481695175171 +99,SPOON,SUM,0,0,0,0,0,47,1,15.517863988876343 +99,,SUM,0,0,0,0,4,549,14,74.87588882446289 +99,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_15.5.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_15.5.csv new file mode 100644 index 0000000000..63da8ad58a --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_15.5.csv @@ -0,0 +1,303 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,0,7,2,13.948299884796143 +0,CUP,SUM,0,0,0,0,0,16,7,9.530455827713013 +0,SPOON,SUM,0,0,0,0,0,15,2,14.101624011993408 +0,,SUM,0,0,0,0,0,38,11,37.58037972450256 +0,, +1,, +1,BOWL,SUM,0,0,0,0,8,24,0,14.390920877456665 +1,CUP,SUM,0,0,0,0,0,23,9,9.089267015457153 +1,SPOON,SUM,0,0,0,0,0,14,1,15.136269092559814 +1,,SUM,0,0,0,0,8,61,10,38.61645698547363 +1,, +2,, +2,BOWL,SUM,0,0,0,0,0,10,1,11.393633842468262 +2,CUP,SUM,0,0,0,0,0,16,4,8.606426000595093 +2,SPOON,SUM,0,0,0,0,0,0,0,12.997578144073486 +2,,SUM,0,0,0,0,0,26,5,32.99763798713684 +2,, +3,, +3,BOWL,SUM,0,0,0,0,4,14,0,11.891854047775269 +3,CUP,SUM,0,0,0,0,0,16,4,8.858577013015747 +3,SPOON,SUM,0,0,0,0,0,23,0,13.459754943847656 +3,,SUM,0,0,0,0,4,53,4,34.21018600463867 +3,, +4,, +4,BOWL,SUM,0,0,0,0,0,11,0,10.237595081329346 +4,CUP,SUM,0,0,0,0,0,4,2,8.335808992385864 +4,SPOON,SUM,0,0,0,0,0,6,4,16.074904918670654 +4,,SUM,0,0,0,0,0,21,6,34.648308992385864 +4,, +5,, +5,BOWL,SUM,0,0,0,0,0,6,0,10.242151021957397 +5,CUP,SUM,0,0,0,0,0,43,0,9.283221960067749 +5,SPOON,SUM,1,0,1,0,10,1582,0,0.0 +5,,SUM,1,0,1,0,10,1631,0,19.525372982025146 +5,, +6,, +6,BOWL,SUM,0,0,0,0,112,50,4,59.895740032196045 +6,CUP,SUM,0,0,0,0,0,39,2,9.036813974380493 +6,SPOON,SUM,0,0,0,0,4,3,1,15.994086027145386 +6,,SUM,0,0,0,0,116,92,7,84.92664003372192 +6,, +7,, +7,BOWL,SUM,0,0,0,0,0,6,2,10.120087146759033 +7,CUP,SUM,0,0,0,0,0,30,0,8.818104982376099 +7,SPOON,SUM,0,0,0,0,0,15,0,13.272444009780884 +7,,SUM,0,0,0,0,0,51,2,32.210636138916016 +7,, +8,, +8,BOWL,SUM,0,0,0,0,0,36,0,11.172857999801636 +8,CUP,SUM,1,0,0,1,10,170,58,0.0 +8,SPOON,SUM,0,0,0,0,2,78,0,17.561167001724243 +8,,SUM,1,0,0,1,12,284,58,28.73402500152588 +8,, +9,, +9,BOWL,SUM,0,0,0,0,0,1,0,9.932767868041992 +9,CUP,SUM,1,0,0,1,2,217,51,0.0 +9,SPOON,SUM,0,0,0,0,0,9,0,13.260983943939209 +9,,SUM,1,0,0,1,2,227,51,23.1937518119812 +9,, +10,, +10,BOWL,SUM,0,0,0,0,0,11,0,10.23193907737732 +10,CUP,SUM,0,0,0,0,0,3,2,8.408581972122192 +10,SPOON,SUM,0,0,0,0,0,76,0,16.47628903388977 +10,,SUM,0,0,0,0,0,90,2,35.11681008338928 +10,, +11,, +11,BOWL,SUM,0,0,0,0,0,13,0,10.42850399017334 +11,CUP,SUM,1,0,0,1,0,240,53,0.0 +11,SPOON,SUM,0,0,0,0,0,8,0,13.527013063430786 +11,,SUM,1,0,0,1,0,261,53,23.955517053604126 +11,, +12,, +12,BOWL,SUM,0,0,0,0,0,6,2,10.511088132858276 +12,CUP,SUM,0,0,0,0,0,19,5,8.958712100982666 +12,SPOON,SUM,0,0,0,0,0,1,1,15.014839887619019 +12,,SUM,0,0,0,0,0,26,8,34.48464012145996 +12,, +13,, +13,BOWL,SUM,0,0,0,0,2,180,4,22.33324098587036 +13,CUP,SUM,0,0,0,0,0,25,0,8.922868967056274 +13,SPOON,SUM,0,0,0,0,16,295,0,35.82969403266907 +13,,SUM,0,0,0,0,18,500,4,67.0858039855957 +13,, +14,, +14,BOWL,SUM,0,0,0,0,22,20,4,20.887563943862915 +14,CUP,SUM,1,0,0,1,2,208,55,0.0 +14,SPOON,SUM,0,0,0,0,0,103,0,18.329650163650513 +14,,SUM,1,0,0,1,24,331,59,39.21721410751343 +14,, +15,, +15,BOWL,SUM,0,0,0,0,0,3,0,9.826875925064087 +15,CUP,SUM,0,0,0,0,0,10,3,9.906938076019287 +15,SPOON,SUM,0,0,0,0,0,95,0,18.569635152816772 +15,,SUM,0,0,0,0,0,108,3,38.30344915390015 +15,, +16,, +16,BOWL,SUM,0,0,0,0,0,7,0,10.002515077590942 +16,CUP,SUM,1,0,0,1,2,208,58,0.0 +16,SPOON,SUM,0,0,0,0,0,38,0,14.969866037368774 +16,,SUM,1,0,0,1,2,253,58,24.972381114959717 +16,, +17,, +17,BOWL,SUM,0,0,0,0,0,12,0,10.142360925674438 +17,CUP,SUM,0,0,0,0,0,9,1,8.452614068984985 +17,SPOON,SUM,0,0,0,0,0,4,3,14.547868013381958 +17,,SUM,0,0,0,0,0,25,4,33.14284300804138 +17,, +18,, +18,BOWL,SUM,0,0,0,0,4,36,0,12.264889001846313 +18,CUP,SUM,0,0,0,0,0,6,2,8.297279119491577 +18,SPOON,SUM,0,0,0,0,0,170,0,21.875121116638184 +18,,SUM,0,0,0,0,4,212,2,42.437289237976074 +18,, +19,, +19,BOWL,SUM,0,0,0,0,2,118,1,18.033231019973755 +19,CUP,SUM,1,0,0,1,0,232,53,0.0 +19,SPOON,SUM,0,0,0,0,2,0,0,14.258772134780884 +19,,SUM,1,0,0,1,4,350,54,32.29200315475464 +19,, +20,, +20,BOWL,SUM,1,0,1,0,0,769,86,0.0 +20,CUP,SUM,1,0,0,1,0,195,59,0.0 +20,SPOON,SUM,0,0,0,0,0,13,0,14.377342224121094 +20,,SUM,2,0,1,1,0,977,145,14.377342224121094 +20,, +21,, +21,BOWL,SUM,0,0,0,0,0,26,1,12.56479001045227 +21,CUP,SUM,0,0,0,0,0,15,7,10.104963064193726 +21,SPOON,SUM,0,0,0,0,0,59,0,16.0970299243927 +21,,SUM,0,0,0,0,0,100,8,38.766782999038696 +21,, +22,, +22,BOWL,SUM,0,0,0,0,2,10,0,11.056380033493042 +22,CUP,SUM,0,0,0,0,0,15,0,8.505072116851807 +22,SPOON,SUM,0,0,0,0,0,63,1,18.669026136398315 +22,,SUM,0,0,0,0,2,88,1,38.230478286743164 +22,, +23,, +23,BOWL,SUM,0,0,0,0,0,29,3,13.129120111465454 +23,CUP,SUM,0,0,0,0,0,29,16,20.55093002319336 +23,SPOON,SUM,0,0,0,0,0,33,0,15.65382981300354 +23,,SUM,0,0,0,0,0,91,19,49.33387994766235 +23,, +24,, +24,BOWL,SUM,0,0,0,0,0,10,0,10.275693893432617 +24,CUP,SUM,0,0,0,0,0,16,4,8.93819785118103 +24,SPOON,SUM,0,0,0,0,0,4,1,14.569167137145996 +24,,SUM,0,0,0,0,0,30,5,33.783058881759644 +24,, +25,, +25,BOWL,SUM,0,0,0,0,0,16,2,11.161906003952026 +25,CUP,SUM,0,0,0,0,0,7,0,8.98196792602539 +25,SPOON,SUM,0,0,0,0,0,129,0,19.567727088928223 +25,,SUM,0,0,0,0,0,152,2,39.71160101890564 +25,, +26,, +26,BOWL,SUM,0,0,0,0,2,13,0,10.863338947296143 +26,CUP,SUM,0,0,0,0,0,205,54,74.81058311462402 +26,SPOON,SUM,0,0,0,0,0,11,0,14.068456888198853 +26,,SUM,0,0,0,0,2,229,54,99.74237895011902 +26,, +27,, +27,BOWL,SUM,0,0,0,0,0,59,4,14.315881967544556 +27,CUP,SUM,0,0,0,0,0,15,7,8.864304065704346 +27,SPOON,SUM,0,0,0,0,0,71,0,17.224674940109253 +27,,SUM,0,0,0,0,0,145,11,40.404860973358154 +27,, +28,, +28,BOWL,SUM,0,0,0,0,20,22,0,19.312823057174683 +28,CUP,SUM,0,0,0,0,0,22,10,17.051253080368042 +28,SPOON,SUM,0,0,0,0,0,8,0,13.366859912872314 +28,,SUM,0,0,0,0,20,52,10,49.73093605041504 +28,, +29,, +29,BOWL,SUM,0,0,0,0,2,70,2,14.89876389503479 +29,CUP,SUM,1,0,1,0,0,146,107,0.0 +29,SPOON,SUM,0,0,0,0,8,137,2,23.118212938308716 +29,,SUM,1,0,1,0,10,353,111,38.016976833343506 +29,, +30,, +30,BOWL,SUM,0,0,0,0,12,31,0,15.49197506904602 +30,CUP,SUM,0,0,0,0,0,15,5,11.25974702835083 +30,SPOON,SUM,0,0,0,0,0,3,1,14.416865825653076 +30,,SUM,0,0,0,0,12,49,6,41.16858792304993 +30,, +31,, +31,BOWL,SUM,0,0,0,0,0,40,0,13.018692970275879 +31,CUP,SUM,0,0,0,0,2,18,5,10.742736101150513 +31,SPOON,SUM,0,0,0,0,0,13,0,14.818656206130981 +31,,SUM,0,0,0,0,2,71,5,38.58008527755737 +31,, +32,, +32,BOWL,SUM,0,0,0,0,152,72,3,80.76700091362 +32,CUP,SUM,0,0,0,0,0,16,6,9.365687131881714 +32,SPOON,SUM,0,0,0,0,0,1,0,13.528763055801392 +32,,SUM,0,0,0,0,152,89,9,103.6614511013031 +32,, +33,, +33,BOWL,SUM,0,0,0,0,12,52,4,19.430487155914307 +33,CUP,SUM,0,0,0,0,6,126,46,57.29286003112793 +33,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +33,,SUM,1,0,1,0,18,1759,50,76.72334718704224 +33,, +34,, +34,BOWL,SUM,0,0,0,0,6,4,0,12.191718101501465 +34,CUP,SUM,0,0,0,0,0,46,3,12.515341997146606 +34,SPOON,SUM,0,0,0,0,2,176,1,25.14903688430786 +34,,SUM,0,0,0,0,8,226,4,49.85609698295593 +34,, +35,, +35,BOWL,SUM,0,0,0,0,0,37,0,11.27121615409851 +35,CUP,SUM,1,0,0,1,0,168,51,0.0 +35,SPOON,SUM,0,0,0,0,0,23,3,15.238203048706055 +35,,SUM,1,0,0,1,0,228,54,26.509419202804565 +35,, +36,, +36,BOWL,SUM,0,0,0,0,0,16,2,10.920048952102661 +36,CUP,SUM,1,0,0,1,0,209,51,0.0 +36,SPOON,SUM,0,0,0,0,0,46,0,15.599369049072266 +36,,SUM,1,0,0,1,0,271,53,26.519418001174927 +36,, +37,, +37,BOWL,SUM,0,0,0,0,62,116,0,42.59788393974304 +37,CUP,SUM,0,0,0,0,0,23,3,10.107172012329102 +37,SPOON,SUM,1,0,1,0,2,1639,0,0.0 +37,,SUM,1,0,1,0,64,1778,3,52.705055952072144 +37,, +38,, +38,BOWL,SUM,0,0,0,0,0,5,0,10.395364999771118 +38,CUP,SUM,1,0,1,0,2,222,104,0.0 +38,SPOON,SUM,0,0,0,0,6,25,0,16.497148990631104 +38,,SUM,1,0,1,0,8,252,104,26.89251399040222 +38,, +39,, +39,BOWL,SUM,0,0,0,0,0,22,0,10.775833129882813 +39,CUP,SUM,0,0,0,0,2,19,4,9.831626892089844 +39,SPOON,SUM,0,0,0,0,0,375,0,35.423551082611084 +39,,SUM,0,0,0,0,2,416,4,56.03101110458374 +39,, +40,, +40,BOWL,SUM,0,0,0,0,0,9,0,10.481473207473755 +40,CUP,SUM,0,0,0,0,2,35,5,12.669173955917358 +40,SPOON,SUM,0,0,0,0,0,0,0,14.027204036712646 +40,,SUM,0,0,0,0,2,44,5,37.17785120010376 +40,, +41,, +41,BOWL,SUM,0,0,0,0,2,29,3,13.334300994873047 +41,CUP,SUM,0,0,0,0,0,5,0,8.7018301486969 +41,SPOON,SUM,0,0,0,0,4,129,0,21.679119110107422 +41,,SUM,0,0,0,0,6,163,3,43.71525025367737 +41,, +42,, +42,BOWL,SUM,0,0,0,0,6,40,0,13.931771993637085 +42,CUP,SUM,1,0,0,1,0,185,51,0.0 +42,SPOON,SUM,0,0,0,0,2,283,0,29.980721950531006 +42,,SUM,1,0,0,1,8,508,51,43.91249394416809 +42,, +43,, +43,BOWL,SUM,0,0,0,0,0,6,0,10.395173072814941 +43,CUP,SUM,0,0,0,0,2,20,0,9.207948923110962 +43,SPOON,SUM,0,0,0,0,0,1,0,13.848039150238037 +43,,SUM,0,0,0,0,2,27,0,33.45116114616394 +43,, +44,, +44,BOWL,SUM,0,0,0,0,0,44,2,13.255220174789429 +44,CUP,SUM,0,0,0,0,0,46,21,21.38408398628235 +44,SPOON,SUM,0,0,0,0,0,142,1,22.680320024490356 +44,,SUM,0,0,0,0,0,232,24,57.319624185562134 +44,, +45,, +45,BOWL,SUM,0,0,0,0,2,47,2,13.215199947357178 +45,CUP,SUM,0,0,0,0,2,19,4,12.420746088027954 +45,SPOON,SUM,0,0,0,0,0,78,0,18.063354969024658 +45,,SUM,0,0,0,0,4,144,6,43.69930100440979 +45,, +46,, +46,BOWL,SUM,0,0,0,0,0,44,2,15.596676111221313 +46,CUP,SUM,0,0,0,0,6,12,4,12.388921976089478 +46,SPOON,SUM,0,0,0,0,4,18,1,16.851836919784546 +46,,SUM,0,0,0,0,10,74,7,44.83743500709534 +46,, +47,, +47,BOWL,SUM,0,0,0,0,2,41,0,13.455971002578735 +47,CUP,SUM,0,0,0,0,0,20,8,9.957876920700073 +47,SPOON,SUM,0,0,0,0,8,1,1,18.53771996498108 +47,,SUM,0,0,0,0,10,62,9,41.95156788825989 +47,, +48,, +48,BOWL,SUM,0,0,0,0,0,11,0,10.504843950271606 +48,CUP,SUM,0,0,0,0,0,7,8,9.3197660446167 +48,SPOON,SUM,0,0,0,0,2,104,0,19.817841053009033 +48,,SUM,0,0,0,0,2,122,8,39.64245104789734 +48,, +49,, +49,BOWL,SUM,0,0,0,0,10,33,0,15.089070081710815 +49,CUP,SUM,0,0,0,0,0,144,41,55.87661600112915 +49,SPOON,SUM,0,0,0,0,0,598,0,46.061420917510986 +49,,SUM,0,0,0,0,10,775,41,117.02710700035095 +49,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_15.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_15.csv new file mode 100644 index 0000000000..6bf88391b3 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_15.csv @@ -0,0 +1,303 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,7,2,15.1845328808 +0,CUP,SUM,0,0,0,0,0,16,7,10.4609401226 +0,SPOON,SUM,0,0,0,0,0,16,2,14.6517879963 +0,,SUM,0,0,0,0,0,39,11,40.2972609997 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,8,24,0,15.6547579765 +1,CUP,SUM,0,0,0,0,0,27,3,11.3313641548 +1,SPOON,SUM,0,0,0,0,0,38,0,15.3437728882 +1,,SUM,0,0,0,0,8,89,3,42.3298950195 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,48,207,2,37.5680618286 +2,CUP,SUM,0,0,0,0,0,20,7,9.1141469479 +2,SPOON,SUM,0,0,0,0,2,11,0,13.9227240086 +2,,SUM,0,0,0,0,50,238,9,60.604932785 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,2,30,0,11.2623660564 +3,CUP,SUM,0,0,0,0,0,22,10,11.6094470024 +3,SPOON,SUM,0,0,0,0,0,54,0,15.7964279652 +3,,SUM,0,0,0,0,2,106,10,38.668241024 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,39,0,10.8246588707 +4,CUP,SUM,0,0,0,0,0,9,3,8.5817699432 +4,SPOON,SUM,0,0,0,0,0,47,0,15.0049440861 +4,,SUM,0,0,0,0,0,95,3,34.4113729 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,1,0,1,0,0,1114,50,0 +5,CUP,SUM,0,0,0,0,0,12,9,15.7677490711 +5,SPOON,SUM,0,0,0,0,0,52,0,15.6883580685 +5,,SUM,1,0,1,0,0,1178,59,31.4561071396 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,4,24,0,11.50096488 +6,CUP,SUM,0,0,0,0,0,21,5,8.9336669445 +6,SPOON,SUM,0,0,0,0,0,187,0,21.8702208996 +6,,SUM,0,0,0,0,4,232,5,42.3048527241 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,6,9,1,13.3281030655 +7,CUP,SUM,0,0,0,0,2,13,2,10.5130288601 +7,SPOON,SUM,0,0,0,0,0,54,0,15.1695170403 +7,,SUM,0,0,0,0,8,76,3,39.0106489658 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,16,14,0,16.9877369404 +8,CUP,SUM,0,0,0,0,0,11,4,8.4904379845 +8,SPOON,SUM,1,0,1,0,0,1581,0,0 +8,,SUM,1,0,1,0,16,1606,4,25.4781749249 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,22,2,10.5650441647 +9,CUP,SUM,0,0,0,0,4,31,7,12.8354051113 +9,SPOON,SUM,0,0,0,0,0,26,0,13.610435009 +9,,SUM,0,0,0,0,4,79,9,37.010884285 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,21,4,12.3243029118 +10,CUP,SUM,0,0,0,0,0,5,9,8.559128046 +10,SPOON,SUM,0,0,0,0,0,620,0,46.2229290009 +10,,SUM,0,0,0,0,0,646,13,67.1063599586 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,24,342,0,37.272603035 +11,CUP,SUM,0,0,0,0,0,23,4,14.0327529907 +11,SPOON,SUM,0,0,0,0,0,6,1,13.2583889961 +11,,SUM,0,0,0,0,24,371,5,64.5637450218 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,0,9,1,9.9094910622 +12,CUP,SUM,0,0,0,0,0,18,3,8.8846421242 +12,SPOON,SUM,0,0,0,0,2,3,0,13.4922850132 +12,,SUM,0,0,0,0,2,30,4,32.2864181995 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,16,66,0,18.2685332298 +13,CUP,SUM,0,0,0,0,0,10,0,8.5229618549 +13,SPOON,SUM,0,0,0,0,0,169,0,21.8394529819 +13,,SUM,0,0,0,0,16,245,0,48.6309480667 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,0,11,0,10.6259660721 +14,CUP,SUM,1,0,0,1,0,180,51,0 +14,SPOON,SUM,0,0,0,0,6,237,0,27.5602128506 +14,,SUM,1,0,0,1,6,428,51,38.1861789227 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,14,18,0,15.5853219032 +15,CUP,SUM,1,0,0,1,0,232,59,0 +15,SPOON,SUM,0,0,0,0,0,4,1,13.027755022 +15,,SUM,1,0,0,1,14,254,60,28.6130769253 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,6,18,0,12.1378040314 +16,CUP,SUM,0,0,0,0,0,37,6,11.7367908955 +16,SPOON,SUM,0,0,0,0,6,63,0,18.6586668491 +16,,SUM,0,0,0,0,12,118,6,42.533261776 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,0,234,46,45.787227869 +17,CUP,SUM,0,0,0,0,2,26,6,9.6391830444 +17,SPOON,SUM,0,0,0,0,0,2,0,13.1964728832 +17,,SUM,0,0,0,0,2,262,52,68.6228837967 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,4,15,0,11.4685790539 +18,CUP,SUM,0,0,0,0,0,15,12,9.2380700111 +18,SPOON,SUM,0,0,0,0,2,202,1,25.7549917698 +18,,SUM,0,0,0,0,6,232,13,46.4616408348 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,28,0,10.5170559883 +19,CUP,SUM,0,0,0,0,0,18,5,10.3598339558 +19,SPOON,SUM,0,0,0,0,0,85,0,16.909031868 +19,,SUM,0,0,0,0,0,131,5,37.7859218121 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,58,45,2,35.1988070011 +20,CUP,SUM,0,0,0,0,0,14,0,8.509139061 +20,SPOON,SUM,0,0,0,0,0,94,0,18.437515974 +20,,SUM,0,0,0,0,58,153,2,62.1454620361 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,29,0,10.6080420017 +21,CUP,SUM,0,0,0,0,0,176,41,59.49137187 +21,SPOON,SUM,0,0,0,0,0,81,0,17.2561631203 +21,,SUM,0,0,0,0,0,286,41,87.355576992 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,14,54,0,17.4340310097 +22,CUP,SUM,0,0,0,0,0,14,2,8.4629831314 +22,SPOON,SUM,0,0,0,0,0,74,0,16.7390320301 +22,,SUM,0,0,0,0,14,142,2,42.6360461712 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,22,0,10.6467940807 +23,CUP,SUM,1,0,0,1,2,164,56,0 +23,SPOON,SUM,0,0,0,0,12,262,0,31.4139449596 +23,,SUM,1,0,0,1,14,448,56,42.0607390404 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,0,18,0,10.9165780544 +24,CUP,SUM,1,0,0,1,0,156,53,0 +24,SPOON,SUM,0,0,0,0,0,8,0,13.3713371754 +24,,SUM,1,0,0,1,0,182,53,24.2879152298 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,0,56,0,13.1415817738 +25,CUP,SUM,0,0,0,0,0,11,0,9.0234770775 +25,SPOON,SUM,0,0,0,0,4,259,0,27.8799300194 +25,,SUM,0,0,0,0,4,326,0,50.0449888706 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,0,36,6,14.4595768452 +26,CUP,SUM,1,0,0,1,2,213,52,0 +26,SPOON,SUM,0,0,0,0,0,57,1,16.5205118656 +26,,SUM,1,0,0,1,2,306,59,30.9800887108 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,62,30,2,35.980453968 +27,CUP,SUM,0,0,0,0,2,6,4,9.3247299194 +27,SPOON,SUM,0,0,0,0,0,11,0,13.2186310291 +27,,SUM,0,0,0,0,64,47,6,58.5238149166 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,0,1,0,10.4467360973 +28,CUP,SUM,0,0,0,0,0,15,0,9.106705904 +28,SPOON,SUM,0,0,0,0,0,511,0,40.5737149715 +28,,SUM,0,0,0,0,0,527,0,60.1271569729 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,0,11,0,9.9725971222 +29,CUP,SUM,1,0,0,1,0,203,53,0 +29,SPOON,SUM,0,0,0,0,10,222,0,29.0064160824 +29,,SUM,1,0,0,1,10,436,53,38.9790132046 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,0,21,1,11.7833631039 +30,CUP,SUM,1,0,0,1,2,224,57,0 +30,SPOON,SUM,0,0,0,0,2,6,0,14.1396758556 +30,,SUM,1,0,0,1,4,251,58,25.9230389595 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,0,5,0,10.2528531551 +31,CUP,SUM,1,0,0,1,0,209,61,0 +31,SPOON,SUM,0,0,0,0,8,909,0,66.7085080147 +31,,SUM,1,0,0,1,8,1123,61,76.9613611698 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,0,7,0,10.1045300961 +32,CUP,SUM,0,0,0,0,2,12,4,9.2841508389 +32,SPOON,SUM,1,0,1,0,0,1581,0,0 +32,,SUM,1,0,1,0,2,1600,4,19.3886809349 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,7,2,13.9399249554 +33,CUP,SUM,0,0,0,0,0,16,7,9.5185439587 +33,SPOON,SUM,0,0,0,0,0,16,2,13.7570779324 +33,,SUM,0,0,0,0,0,39,11,37.2155468464 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,8,24,0,14.4881169796 +34,CUP,SUM,0,0,0,0,0,27,3,10.1361179352 +34,SPOON,SUM,0,0,0,0,0,38,0,14.8839359283 +34,,SUM,0,0,0,0,8,89,3,39.5081708431 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,48,207,2,41.1127948761 +35,CUP,SUM,0,0,0,0,0,20,7,9.0009350777 +35,SPOON,SUM,0,0,0,0,2,11,0,13.9935839176 +35,,SUM,0,0,0,0,50,238,9,64.1073138714 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,2,30,0,11.4588251114 +36,CUP,SUM,0,0,0,0,0,22,10,11.7198979855 +36,SPOON,SUM,0,0,0,0,0,54,0,15.3438110352 +36,,SUM,0,0,0,0,2,106,10,38.522534132 +36,,,,,,,,,, +37,,,,,,,,,, +37,BOWL,SUM,0,0,0,0,0,39,0,10.8230888844 +37,CUP,SUM,0,0,0,0,0,9,3,8.7053380013 +37,SPOON,SUM,0,0,0,0,0,47,0,15.3232691288 +37,,SUM,0,0,0,0,0,95,3,34.8516960144 +37,,,,,,,,,, +38,,,,,,,,,, +38,BOWL,SUM,1,0,1,0,0,1114,50,0 +38,CUP,SUM,0,0,0,0,0,12,9,16.2044999599 +38,SPOON,SUM,0,0,0,0,0,52,0,16.0970740318 +38,,SUM,1,0,1,0,0,1178,59,32.3015739918 +38,,,,,,,,,, +39,,,,,,,,,, +39,BOWL,SUM,0,0,0,0,4,24,0,12.1371529102 +39,CUP,SUM,0,0,0,0,0,21,5,9.2413108349 +39,SPOON,SUM,0,0,0,0,0,187,0,23.1670300961 +39,,SUM,0,0,0,0,4,232,5,44.5454938412 +39,,,,,,,,,, +40,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,6,9,1,13.9139418602 +40,CUP,SUM,0,0,0,0,2,13,2,10.8960139751 +40,SPOON,SUM,0,0,0,0,0,54,0,15.9723100662 +40,,SUM,0,0,0,0,8,76,3,40.7822659016 +40,,,,,,,,,, +41,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,16,14,0,17.6286730766 +41,CUP,SUM,0,0,0,0,0,11,4,8.4902310371 +41,SPOON,SUM,1,0,1,0,0,1581,0,0 +41,,SUM,1,0,1,0,16,1606,4,26.1189041138 +41,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,0,22,2,10.6728990078 +42,CUP,SUM,0,0,0,0,4,31,7,13.5690071583 +42,SPOON,SUM,0,0,0,0,0,26,0,14.0027480125 +42,,SUM,0,0,0,0,4,79,9,38.2446541786 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,0,21,4,12.3010978699 +43,CUP,SUM,0,0,0,0,0,5,9,8.8024380207 +43,SPOON,SUM,0,0,0,0,0,620,0,46.802932024 +43,,SUM,0,0,0,0,0,646,13,67.9064679146 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,24,342,0,38.3659570217 +44,CUP,SUM,0,0,0,0,0,23,4,13.8344049454 +44,SPOON,SUM,0,0,0,0,0,6,1,13.7046589851 +44,,SUM,0,0,0,0,24,371,5,65.9050209522 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,0,9,1,10.0775430202 +45,CUP,SUM,0,0,0,0,0,18,3,8.9088521004 +45,SPOON,SUM,0,0,0,0,2,3,0,13.9183540344 +45,,SUM,0,0,0,0,2,30,4,32.904749155 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,16,66,0,18.2154450417 +46,CUP,SUM,0,0,0,0,0,10,0,8.515048027 +46,SPOON,SUM,0,0,0,0,0,169,0,21.9372508526 +46,,SUM,0,0,0,0,16,245,0,48.6677439213 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,0,0,0,0,0,11,0,10.6816039085 +47,CUP,SUM,1,0,0,1,0,180,51,0 +47,SPOON,SUM,0,0,0,0,6,237,0,27.4656040668 +47,,SUM,1,0,0,1,6,428,51,38.1472079754 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,14,18,0,16.252300024 +48,CUP,SUM,1,0,0,1,0,232,59,0 +48,SPOON,SUM,0,0,0,0,0,4,1,13.3424630165 +48,,SUM,1,0,0,1,14,254,60,29.5947630405 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,6,18,0,12.6153640747 +49,CUP,SUM,0,0,0,0,0,37,6,11.7359170914 +49,SPOON,SUM,0,0,0,0,6,63,0,18.9049930573 +49,,SUM,0,0,0,0,12,118,6,43.2562742233 +49,,,,,,,,,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_16.5.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_16.5.csv new file mode 100644 index 0000000000..e7baafe030 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_16.5.csv @@ -0,0 +1,303 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,0,7,2,13.773998975753784 +0,CUP,SUM,0,0,0,0,0,16,7,9.445077896118164 +0,SPOON,SUM,0,0,0,0,0,15,2,14.10568904876709 +0,,SUM,0,0,0,0,0,38,11,37.32476592063904 +0,, +1,, +1,BOWL,SUM,0,0,0,0,0,18,0,10.421386957168579 +1,CUP,SUM,0,0,0,0,0,14,8,8.806395053863525 +1,SPOON,SUM,0,0,0,0,2,303,1,31.251430988311768 +1,,SUM,0,0,0,0,2,335,9,50.47921299934387 +1,, +2,, +2,BOWL,SUM,0,0,0,0,6,27,0,12.644556999206543 +2,CUP,SUM,1,0,1,0,0,145,110,0.0 +2,SPOON,SUM,0,0,0,0,6,0,0,15.183855056762695 +2,,SUM,1,0,1,0,12,172,110,27.82841205596924 +2,, +3,, +3,BOWL,SUM,0,0,0,0,0,1,0,10.15218710899353 +3,CUP,SUM,0,0,0,0,0,45,16,21.15432906150818 +3,SPOON,SUM,0,0,0,0,6,21,0,16.051762104034424 +3,,SUM,0,0,0,0,6,67,16,47.35827827453613 +3,, +4,, +4,BOWL,SUM,0,0,0,0,2,24,0,11.31284499168396 +4,CUP,SUM,0,0,0,0,2,4,0,8.867406845092773 +4,SPOON,SUM,0,0,0,0,22,465,0,46.824743032455444 +4,,SUM,0,0,0,0,26,493,0,67.00499486923218 +4,, +5,, +5,BOWL,SUM,0,0,0,0,0,6,5,13.349265098571777 +5,CUP,SUM,1,0,0,1,0,207,51,0.0 +5,SPOON,SUM,0,0,0,0,0,5,0,13.652068138122559 +5,,SUM,1,0,0,1,0,218,56,27.001333236694336 +5,, +6,, +6,BOWL,SUM,0,0,0,0,2,6,0,10.809960842132568 +6,CUP,SUM,0,0,0,0,0,11,1,8.697201013565063 +6,SPOON,SUM,0,0,0,0,0,308,0,29.889983892440796 +6,,SUM,0,0,0,0,2,325,1,49.39714574813843 +6,, +7,, +7,BOWL,SUM,0,0,0,0,0,32,0,11.35204005241394 +7,CUP,SUM,0,0,0,0,0,5,2,8.66207504272461 +7,SPOON,SUM,0,0,0,0,0,14,0,13.590266942977905 +7,,SUM,0,0,0,0,0,51,2,33.604382038116455 +7,, +8,, +8,BOWL,SUM,0,0,0,0,10,14,0,14.920955896377563 +8,CUP,SUM,0,0,0,0,0,7,0,8.454499959945679 +8,SPOON,SUM,0,0,0,0,0,5,0,13.710582971572876 +8,,SUM,0,0,0,0,10,26,0,37.08603882789612 +8,, +9,, +9,BOWL,SUM,0,0,0,0,6,47,0,13.527168989181519 +9,CUP,SUM,0,0,0,0,0,12,4,9.982880115509033 +9,SPOON,SUM,0,0,0,0,6,88,0,19.765563011169434 +9,,SUM,0,0,0,0,12,147,4,43.275612115859985 +9,, +10,, +10,BOWL,SUM,0,0,0,0,0,9,2,10.235051155090332 +10,CUP,SUM,0,0,0,0,0,23,2,8.842787027359009 +10,SPOON,SUM,0,0,0,0,0,0,3,17.156041145324707 +10,,SUM,0,0,0,0,0,32,7,36.23387932777405 +10,, +11,, +11,BOWL,SUM,0,0,0,0,0,29,2,13.301645994186401 +11,CUP,SUM,0,0,0,0,0,36,2,9.338912963867188 +11,SPOON,SUM,0,0,0,0,0,1,0,13.080003023147583 +11,,SUM,0,0,0,0,0,66,4,35.72056198120117 +11,, +12,, +12,BOWL,SUM,0,0,0,0,56,23,0,36.932979106903076 +12,CUP,SUM,0,0,0,0,0,25,14,17.591048002243042 +12,SPOON,SUM,0,0,0,0,0,277,0,27.28699803352356 +12,,SUM,0,0,0,0,56,325,14,81.81102514266968 +12,, +13,, +13,BOWL,SUM,0,0,0,0,0,8,0,10.571115970611572 +13,CUP,SUM,1,0,0,1,2,187,55,0.0 +13,SPOON,SUM,0,0,0,0,0,0,1,14.961539030075073 +13,,SUM,1,0,0,1,2,195,56,25.532655000686646 +13,, +14,, +14,BOWL,SUM,0,0,0,0,2,234,4,23.559278964996338 +14,CUP,SUM,0,0,0,0,0,16,6,9.849476099014282 +14,SPOON,SUM,0,0,0,0,0,421,0,36.12267994880676 +14,,SUM,0,0,0,0,2,671,10,69.53143501281738 +14,, +15,, +15,BOWL,SUM,0,0,0,0,0,3,0,10.378861904144287 +15,CUP,SUM,0,0,0,0,0,32,11,16.522902011871338 +15,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +15,,SUM,1,0,1,0,0,1616,11,26.901763916015625 +15,, +16,, +16,BOWL,SUM,0,0,0,0,0,4,0,10.076928853988647 +16,CUP,SUM,0,0,0,0,0,10,8,9.005650997161865 +16,SPOON,SUM,0,0,0,0,0,38,0,15.705518960952759 +16,,SUM,0,0,0,0,0,52,8,34.78809881210327 +16,, +17,, +17,BOWL,SUM,0,0,0,0,0,100,0,15.434729099273682 +17,CUP,SUM,1,0,0,1,0,197,51,0.0 +17,SPOON,SUM,0,0,0,0,0,9,0,13.660583972930908 +17,,SUM,1,0,0,1,0,306,51,29.09531307220459 +17,, +18,, +18,BOWL,SUM,0,0,0,0,2,14,0,10.884665966033936 +18,CUP,SUM,1,0,0,1,0,205,57,0.0 +18,SPOON,SUM,0,0,0,0,0,106,0,18.266254901885986 +18,,SUM,1,0,0,1,2,325,57,29.150920867919922 +18,, +19,, +19,BOWL,SUM,0,0,0,0,2,550,22,49.47420406341553 +19,CUP,SUM,1,0,0,1,6,166,66,0.0 +19,SPOON,SUM,0,0,0,0,0,10,0,13.471352100372314 +19,,SUM,1,0,0,1,8,726,88,62.94555616378784 +19,, +20,, +20,BOWL,SUM,1,0,1,0,0,1552,10,0.0 +20,CUP,SUM,0,0,0,0,0,31,9,12.567783832550049 +20,SPOON,SUM,0,0,0,0,0,3,0,13.564290046691895 +20,,SUM,1,0,1,0,0,1586,19,26.132073879241943 +20,, +21,, +21,BOWL,SUM,0,0,0,0,0,73,2,14.323215007781982 +21,CUP,SUM,0,0,0,0,0,8,0,8.357249975204468 +21,SPOON,SUM,0,0,0,0,0,2,1,14.617622137069702 +21,,SUM,0,0,0,0,0,83,3,37.29808712005615 +21,, +22,, +22,BOWL,SUM,0,0,0,0,2,38,2,13.077831029891968 +22,CUP,SUM,0,0,0,0,0,27,4,12.01083779335022 +22,SPOON,SUM,0,0,0,0,0,2,0,13.620428085327148 +22,,SUM,0,0,0,0,2,67,6,38.709096908569336 +22,, +23,, +23,BOWL,SUM,0,0,0,0,42,199,0,36.24434518814087 +23,CUP,SUM,0,0,0,0,0,48,4,12.005114078521729 +23,SPOON,SUM,0,0,0,0,0,163,0,22.561534881591797 +23,,SUM,0,0,0,0,42,410,4,70.8109941482544 +23,, +24,, +24,BOWL,SUM,0,0,0,0,0,23,2,10.884299993515015 +24,CUP,SUM,0,0,0,0,6,38,16,15.706028938293457 +24,SPOON,SUM,0,0,0,0,2,11,0,14.603107929229736 +24,,SUM,0,0,0,0,8,72,18,41.19343686103821 +24,, +25,, +25,BOWL,SUM,0,0,0,0,56,38,0,35.33160591125488 +25,CUP,SUM,0,0,0,0,0,35,11,16.506471157073975 +25,SPOON,SUM,1,0,1,0,0,1638,0,0.0 +25,,SUM,1,0,1,0,56,1711,11,51.83807706832886 +25,, +26,, +26,BOWL,SUM,0,0,0,0,6,2,0,11.90247392654419 +26,CUP,SUM,1,0,0,1,0,222,55,0.0 +26,SPOON,SUM,0,0,0,0,6,30,1,15.858657121658325 +26,,SUM,1,0,0,1,12,254,56,27.761131048202515 +26,, +27,, +27,BOWL,SUM,1,0,1,0,0,887,72,0.0 +27,CUP,SUM,0,0,0,0,2,28,4,9.947768926620483 +27,SPOON,SUM,0,0,0,0,0,168,0,22.585607051849365 +27,,SUM,1,0,1,0,2,1083,76,32.53337597846985 +27,, +28,, +28,BOWL,SUM,0,0,0,0,18,4,2,17.870797872543335 +28,CUP,SUM,0,0,0,0,2,6,0,8.95806097984314 +28,SPOON,SUM,0,0,0,0,0,20,1,15.684126853942871 +28,,SUM,0,0,0,0,20,30,3,42.512985706329346 +28,, +29,, +29,BOWL,SUM,0,0,0,0,4,66,2,13.829850912094116 +29,CUP,SUM,0,0,0,0,2,2,6,9.21509599685669 +29,SPOON,SUM,0,0,0,0,2,102,0,19.677727937698364 +29,,SUM,0,0,0,0,8,170,8,42.72267484664917 +29,, +30,, +30,BOWL,SUM,0,0,0,0,0,47,0,12.556228876113892 +30,CUP,SUM,0,0,0,0,0,7,2,8.777536153793335 +30,SPOON,SUM,0,0,0,0,8,27,0,17.581028938293457 +30,,SUM,0,0,0,0,8,81,2,38.914793968200684 +30,, +31,, +31,BOWL,SUM,0,0,0,0,2,23,0,11.476010084152222 +31,CUP,SUM,0,0,0,0,0,9,1,9.897201776504517 +31,SPOON,SUM,1,0,1,0,0,850,88,0.0 +31,,SUM,1,0,1,0,2,882,89,21.37321186065674 +31,, +32,, +32,BOWL,SUM,1,0,1,0,0,1076,68,0.0 +32,CUP,SUM,0,0,0,0,0,25,1,10.796339988708496 +32,SPOON,SUM,0,0,0,0,0,290,0,29.32633399963379 +32,,SUM,1,0,1,0,0,1391,69,40.122673988342285 +32,, +33,, +33,BOWL,SUM,0,0,0,0,0,11,0,10.652302026748657 +33,CUP,SUM,1,0,0,1,0,214,59,0.0 +33,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +33,,SUM,2,0,1,1,0,1806,59,10.652302026748657 +33,, +34,, +34,BOWL,SUM,0,0,0,0,2,3,0,11.452414989471436 +34,CUP,SUM,0,0,0,0,0,15,10,9.342797994613647 +34,SPOON,SUM,0,0,0,0,6,3,2,16.021085023880005 +34,,SUM,0,0,0,0,8,21,12,36.81629800796509 +34,, +35,, +35,BOWL,SUM,0,0,0,0,0,26,1,12.392921924591064 +35,CUP,SUM,1,0,1,0,0,223,111,0.0 +35,SPOON,SUM,0,0,0,0,0,99,0,19.253056049346924 +35,,SUM,1,0,1,0,0,348,112,31.64597797393799 +35,, +36,, +36,BOWL,SUM,0,0,0,0,24,39,2,21.916619777679443 +36,CUP,SUM,1,0,0,1,0,190,60,0.0 +36,SPOON,SUM,0,0,0,0,0,4,0,14.056336879730225 +36,,SUM,1,0,0,1,24,233,62,35.97295665740967 +36,, +37,, +37,BOWL,SUM,0,0,0,0,14,94,11,26.04070806503296 +37,CUP,SUM,0,0,0,0,0,0,3,8.618479013442993 +37,SPOON,SUM,0,0,0,0,0,1,1,13.425542831420898 +37,,SUM,0,0,0,0,14,95,15,48.08472990989685 +37,, +38,, +38,BOWL,SUM,0,0,0,0,0,5,0,10.54425597190857 +38,CUP,SUM,0,0,0,0,0,8,5,9.508531093597412 +38,SPOON,SUM,0,0,0,0,0,1,0,13.73652195930481 +38,,SUM,0,0,0,0,0,14,5,33.78930902481079 +38,, +39,, +39,BOWL,SUM,0,0,0,0,2,134,6,20.35333514213562 +39,CUP,SUM,0,0,0,0,0,16,8,17.388757944107056 +39,SPOON,SUM,0,0,0,0,0,8,0,13.980731964111328 +39,,SUM,0,0,0,0,2,158,14,51.722825050354004 +39,, +40,, +40,BOWL,SUM,0,0,0,0,6,30,0,12.759814977645874 +40,CUP,SUM,0,0,0,0,0,16,8,9.045090198516846 +40,SPOON,SUM,0,0,0,0,0,89,0,17.811264038085938 +40,,SUM,0,0,0,0,6,135,8,39.61616921424866 +40,, +41,, +41,BOWL,SUM,0,0,0,0,0,14,0,10.564246892929077 +41,CUP,SUM,0,0,0,0,2,9,10,9.863490104675293 +41,SPOON,SUM,0,0,0,0,0,32,0,15.489268779754639 +41,,SUM,0,0,0,0,2,55,10,35.91700577735901 +41,, +42,, +42,BOWL,SUM,0,0,0,0,0,20,1,11.868051052093506 +42,CUP,SUM,0,0,0,0,0,15,6,8.876657962799072 +42,SPOON,SUM,0,0,0,0,0,34,0,15.121057987213135 +42,,SUM,0,0,0,0,0,69,7,35.86576700210571 +42,, +43,, +43,BOWL,SUM,0,0,0,0,0,8,2,10.723121881484985 +43,CUP,SUM,1,0,0,1,0,175,59,0.0 +43,SPOON,SUM,0,0,0,0,0,178,0,23.38519597053528 +43,,SUM,1,0,0,1,0,361,61,34.108317852020264 +43,, +44,, +44,BOWL,SUM,0,0,0,0,2,25,0,11.528568983078003 +44,CUP,SUM,0,0,0,0,0,8,4,8.83116602897644 +44,SPOON,SUM,0,0,0,0,0,49,0,16.488433122634888 +44,,SUM,0,0,0,0,2,82,4,36.84816813468933 +44,, +45,, +45,BOWL,SUM,0,0,0,0,0,9,0,10.295148134231567 +45,CUP,SUM,0,0,0,0,6,28,6,11.477301836013794 +45,SPOON,SUM,0,0,0,0,0,279,0,28.017148971557617 +45,,SUM,0,0,0,0,6,316,6,49.78959894180298 +45,, +46,, +46,BOWL,SUM,0,0,0,0,14,40,0,17.819385051727295 +46,CUP,SUM,0,0,0,0,0,64,8,16.803736925125122 +46,SPOON,SUM,0,0,0,0,0,141,2,21.949932098388672 +46,,SUM,0,0,0,0,14,245,10,56.57305407524109 +46,, +47,, +47,BOWL,SUM,0,0,0,0,0,6,0,10.232990026473999 +47,CUP,SUM,0,0,0,0,2,58,14,26.876555919647217 +47,SPOON,SUM,0,0,0,0,0,47,0,15.270538091659546 +47,,SUM,0,0,0,0,2,111,14,52.38008403778076 +47,, +48,, +48,BOWL,SUM,0,0,0,0,0,33,1,11.333511114120483 +48,CUP,SUM,0,0,0,0,0,17,1,10.145162105560303 +48,SPOON,SUM,0,0,0,0,8,238,0,29.29531502723694 +48,,SUM,0,0,0,0,8,288,2,50.773988246917725 +48,, +49,, +49,BOWL,SUM,0,0,0,0,0,5,0,10.416998863220215 +49,CUP,SUM,0,0,0,0,0,0,8,8.543437957763672 +49,SPOON,SUM,0,0,0,0,2,83,0,18.59263515472412 +49,,SUM,0,0,0,0,2,88,8,37.55307197570801 +49,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_16.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_16.csv new file mode 100644 index 0000000000..537167346c --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_16.csv @@ -0,0 +1,303 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,7,2,14.1363930702 +0,CUP,SUM,0,0,0,0,0,16,7,9.6061439514 +0,SPOON,SUM,0,0,0,0,0,15,2,14.6411380768 +0,,SUM,0,0,0,0,0,38,11,38.3836750984 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,6,24,2,12.8219151497 +1,CUP,SUM,0,0,0,0,0,14,8,8.9827091694 +1,SPOON,SUM,0,0,0,0,2,461,0,38.4582269192 +1,,SUM,0,0,0,0,8,499,10,60.2628512383 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,0,6,0,10.0326869488 +2,CUP,SUM,1,0,0,1,4,209,53,0 +2,SPOON,SUM,0,0,0,0,4,443,0,38.5402178764 +2,,SUM,1,0,0,1,8,658,53,48.5729048252 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,2,53,4,14.6690118313 +3,CUP,SUM,0,0,0,0,14,89,36,54.1937630177 +3,SPOON,SUM,1,0,1,0,0,1596,0,0 +3,,SUM,1,0,1,0,16,1738,40,68.8627748489 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,2,42,2,13.0301728249 +4,CUP,SUM,0,0,0,0,0,14,8,11.4678850174 +4,SPOON,SUM,0,0,0,0,0,47,0,14.8949370384 +4,,SUM,0,0,0,0,2,103,10,39.3929948807 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,0,50,0,11.2852580547 +5,CUP,SUM,0,0,0,0,2,22,2,9.5451338291 +5,SPOON,SUM,0,0,0,0,0,1,0,13.3528020382 +5,,SUM,0,0,0,0,2,73,2,34.183193922 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,0,20,0,10.6854729652 +6,CUP,SUM,0,0,0,0,4,15,2,9.9713129997 +6,SPOON,SUM,0,0,0,0,0,82,2,17.5681900978 +6,,SUM,0,0,0,0,4,117,4,38.2249760628 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,0,72,4,14.4747130871 +7,CUP,SUM,0,0,0,0,0,22,4,9.1190140247 +7,SPOON,SUM,0,0,0,0,6,2,0,15.4525411129 +7,,SUM,0,0,0,0,6,96,8,39.0462682247 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,0,138,0,17.5052568913 +8,CUP,SUM,0,0,0,0,0,22,4,9.1790728569 +8,SPOON,SUM,0,0,0,0,0,380,0,34.4191539288 +8,,SUM,0,0,0,0,0,540,4,61.1034836769 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,33,0,10.7849910259 +9,CUP,SUM,0,0,0,0,0,7,6,8.788339138 +9,SPOON,SUM,0,0,0,0,2,100,2,19.7836039066 +9,,SUM,0,0,0,0,2,140,8,39.3569340706 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,162,0,19.2491078377 +10,CUP,SUM,0,0,0,0,0,11,0,8.8869690895 +10,SPOON,SUM,0,0,0,0,0,131,0,20.8581609726 +10,,SUM,0,0,0,0,0,304,0,48.9942378998 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,0,13,2,10.9315729141 +11,CUP,SUM,0,0,0,0,0,13,0,8.7731189728 +11,SPOON,SUM,0,0,0,0,0,5,0,13.6908209324 +11,,SUM,0,0,0,0,0,31,2,33.3955128193 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,126,574,0,94.5502750874 +12,CUP,SUM,0,0,0,0,0,23,0,9.23782897 +12,SPOON,SUM,0,0,0,0,0,7,0,14.1358120441 +12,,SUM,0,0,0,0,126,604,0,117.9239161015 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,0,13,1,12.392482996 +13,CUP,SUM,0,0,0,0,0,14,4,9.0737011433 +13,SPOON,SUM,0,0,0,0,0,13,4,15.9506180286 +13,,SUM,0,0,0,0,0,40,9,37.4168021679 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,0,82,16,23.8006970882 +14,CUP,SUM,0,0,0,0,2,15,1,9.7386481762 +14,SPOON,SUM,0,0,0,0,0,338,0,31.7641458511 +14,,SUM,0,0,0,0,2,435,17,65.3034911156 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,0,11,1,12.2888159752 +15,CUP,SUM,0,0,0,0,4,20,4,10.8996429443 +15,SPOON,SUM,0,0,0,0,2,369,0,34.5334498882 +15,,SUM,0,0,0,0,6,400,5,57.7219088078 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,30,4,12.8648250103 +16,CUP,SUM,0,0,0,0,0,11,2,8.5995140076 +16,SPOON,SUM,0,0,0,0,0,5,2,13.9635119438 +16,,SUM,0,0,0,0,0,46,8,35.4278509617 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,0,41,0,12.4151360989 +17,CUP,SUM,0,0,0,0,0,22,2,9.0861959457 +17,SPOON,SUM,0,0,0,0,10,142,0,24.3935010433 +17,,SUM,0,0,0,0,10,205,2,45.8948330879 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,0,38,0,12.3251099586 +18,CUP,SUM,0,0,0,0,0,35,2,9.3397119045 +18,SPOON,SUM,0,0,0,0,0,46,0,16.0619139671 +18,,SUM,0,0,0,0,0,119,2,37.7267358303 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,120,52,2,68.5458071232 +19,CUP,SUM,0,0,0,0,0,11,2,8.6570489407 +19,SPOON,SUM,0,0,0,0,2,25,0,15.1914508343 +19,,SUM,0,0,0,0,122,88,4,92.3943068981 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,0,65,1,15.0724570751 +20,CUP,SUM,0,0,0,0,0,12,3,11.6316359043 +20,SPOON,SUM,0,0,0,0,2,12,0,14.9098129272 +20,,SUM,0,0,0,0,2,89,4,41.6139059067 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,13,0,10.7170348167 +21,CUP,SUM,1,0,0,1,0,189,53,0 +21,SPOON,SUM,0,0,0,0,8,68,0,21.5375728607 +21,,SUM,1,0,0,1,8,270,53,32.2546076775 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,6,16,0,12.8987689018 +22,CUP,SUM,1,0,0,1,0,247,53,0 +22,SPOON,SUM,0,0,0,0,2,15,1,15.2817409039 +22,,SUM,1,0,0,1,8,278,54,28.1805098057 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,76,8,17.2984490395 +23,CUP,SUM,0,0,0,0,0,25,14,17.2405910492 +23,SPOON,SUM,0,0,0,0,0,301,0,30.4740791321 +23,,SUM,0,0,0,0,0,402,22,65.0131192207 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,0,81,6,15.923584938 +24,CUP,SUM,0,0,0,0,0,11,4,9.1103551388 +24,SPOON,SUM,0,0,0,0,0,57,1,18.3546581268 +24,,SUM,0,0,0,0,0,149,11,43.3885982037 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,0,16,2,11.3467600346 +25,CUP,SUM,1,0,0,1,0,196,51,0 +25,SPOON,SUM,0,0,0,0,0,123,0,20.3003721237 +25,,SUM,1,0,0,1,0,335,53,31.6471321583 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,8,63,4,18.7226610184 +26,CUP,SUM,0,0,0,0,0,25,0,9.05605793 +26,SPOON,SUM,0,0,0,0,0,29,0,14.925590992 +26,,SUM,0,0,0,0,8,117,4,42.7043099403 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,0,14,2,11.138792038 +27,CUP,SUM,1,0,0,1,0,212,55,0 +27,SPOON,SUM,0,0,0,0,0,112,0,20.1115760803 +27,,SUM,1,0,0,1,0,338,57,31.2503681183 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,2,18,0,11.4790258408 +28,CUP,SUM,0,0,0,0,2,8,2,9.6611499786 +28,SPOON,SUM,0,0,0,0,0,41,0,16.1453771591 +28,,SUM,0,0,0,0,4,67,2,37.2855529785 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,0,12,2,11.2896208763 +29,CUP,SUM,0,0,0,0,2,12,2,9.5648770332 +29,SPOON,SUM,0,0,0,0,0,359,0,33.8653860092 +29,,SUM,0,0,0,0,2,383,4,54.7198839188 +29,,,,,,,,,, +31,, +31,BOWL,SUM,0,0,0,0,6,6,0,15.057893991470337 +31,CUP,SUM,0,0,0,0,0,10,3,8.617418050765991 +31,SPOON,SUM,0,0,0,0,0,146,0,20.908615827560425 +31,,SUM,0,0,0,0,6,162,3,44.58392786979675 +31,, +32,, +32,BOWL,SUM,0,0,0,0,2,19,2,14.10529088973999 +32,CUP,SUM,0,0,0,0,0,13,1,10.114291906356812 +32,SPOON,SUM,0,0,0,0,0,64,0,16.75191903114319 +32,,SUM,0,0,0,0,2,96,3,40.97150182723999 +32,, +33,, +33,BOWL,SUM,0,0,0,0,0,31,0,11.02997899055481 +33,CUP,SUM,1,0,1,0,2,339,84,0.0 +33,SPOON,SUM,0,0,0,0,0,23,1,15.289561986923218 +33,,SUM,1,0,1,0,2,393,85,26.319540977478027 +33,, +34,, +34,BOWL,SUM,0,0,0,0,0,1,0,10.39458680152893 +34,CUP,SUM,0,0,0,0,0,45,18,22.173605918884277 +34,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +34,,SUM,1,0,1,0,0,1627,18,32.56819272041321 +34,, +35,, +35,BOWL,SUM,0,0,0,0,4,9,4,13.501821994781494 +35,CUP,SUM,0,0,0,0,2,105,22,31.949313163757324 +35,SPOON,SUM,0,0,0,0,2,138,0,21.85546612739563 +35,,SUM,0,0,0,0,8,252,26,67.30660128593445 +35,, +36,, +36,BOWL,SUM,0,0,0,0,0,58,0,12.87164306640625 +36,CUP,SUM,1,0,0,1,0,237,54,0.0 +36,SPOON,SUM,0,0,0,0,48,1304,0,106.29555082321167 +36,,SUM,1,0,0,1,48,1599,54,119.16719388961792 +36,, +37,, +37,BOWL,SUM,0,0,0,0,0,3,2,10.336344957351685 +37,CUP,SUM,0,0,0,0,0,117,34,47.267849922180176 +37,SPOON,SUM,0,0,0,0,0,194,0,24.05083918571472 +37,,SUM,0,0,0,0,0,314,36,81.65503406524658 +37,, +38,, +38,BOWL,SUM,1,0,1,0,0,820,78,0.0 +38,CUP,SUM,0,0,0,0,0,23,3,11.766853094100952 +38,SPOON,SUM,0,0,0,0,0,27,1,16.132206916809082 +38,,SUM,1,0,1,0,0,870,82,27.899060010910034 +38,, +39,, +39,BOWL,SUM,0,0,0,0,0,10,0,10.39905309677124 +39,CUP,SUM,0,0,0,0,0,14,2,8.7240469455719 +39,SPOON,SUM,1,0,1,0,0,767,54,0.0 +39,,SUM,1,0,1,0,0,791,56,19.12310004234314 +39,, +40,, +40,BOWL,SUM,0,0,0,0,56,49,0,36.54698300361633 +40,CUP,SUM,0,0,0,0,0,17,4,10.230739116668701 +40,SPOON,SUM,0,0,0,0,10,82,0,22.156725883483887 +40,,SUM,0,0,0,0,66,148,4,68.93444800376892 +40,, +41,, +41,BOWL,SUM,0,0,0,0,0,35,0,10.755496978759766 +41,CUP,SUM,0,0,0,0,0,161,43,54.21676993370056 +41,SPOON,SUM,0,0,0,0,4,37,0,16.21724796295166 +41,,SUM,0,0,0,0,4,233,43,81.18951487541199 +41,, +42,, +42,BOWL,SUM,0,0,0,0,18,88,6,23.61358904838562 +42,CUP,SUM,1,0,0,1,0,205,51,0.0 +42,SPOON,SUM,0,0,0,0,2,89,0,18.129169940948486 +42,,SUM,1,0,0,1,20,382,57,41.742758989334106 +42,, +43,, +43,BOWL,SUM,0,0,0,0,0,33,0,11.076931953430176 +43,CUP,SUM,0,0,0,0,4,3,8,9.965747117996216 +43,SPOON,SUM,0,0,0,0,0,2,2,13.515909194946289 +43,,SUM,0,0,0,0,4,38,10,34.55858826637268 +43,, +44,, +44,BOWL,SUM,0,0,0,0,0,56,0,12.408797979354858 +44,CUP,SUM,0,0,0,0,0,5,2,8.19886302947998 +44,SPOON,SUM,0,0,0,0,0,26,0,14.308616876602173 +44,,SUM,0,0,0,0,0,87,2,34.91627788543701 +44,, +45,, +45,BOWL,SUM,0,0,0,0,0,8,1,10.972524166107178 +45,CUP,SUM,0,0,0,0,0,6,10,16.56041717529297 +45,SPOON,SUM,0,0,0,0,0,19,0,13.710371971130371 +45,,SUM,0,0,0,0,0,33,11,41.24331331253052 +45,, +46,, +46,BOWL,SUM,0,0,0,0,0,2,0,10.13145112991333 +46,CUP,SUM,0,0,0,0,0,5,1,8.553359985351563 +46,SPOON,SUM,0,0,0,0,0,75,0,17.69516110420227 +46,,SUM,0,0,0,0,0,82,1,36.37997221946716 +46,, +47,, +47,BOWL,SUM,0,0,0,0,0,5,0,10.841613054275513 +47,CUP,SUM,0,0,0,0,0,7,4,8.770914793014526 +47,SPOON,SUM,0,0,0,0,0,6,3,15.126304149627686 +47,,SUM,0,0,0,0,0,18,7,34.738831996917725 +47,, +48,, +48,BOWL,SUM,0,0,0,0,6,120,8,22.810351848602295 +48,CUP,SUM,0,0,0,0,0,10,0,8.56762409210205 +48,SPOON,SUM,0,0,0,0,2,12,0,14.541586875915527 +48,,SUM,0,0,0,0,8,142,8,45.91956281661987 +48,, +49,, +49,BOWL,SUM,0,0,0,0,4,23,1,13.452290058135986 +49,CUP,SUM,0,0,0,0,0,42,7,11.095093965530396 +49,SPOON,SUM,0,0,0,0,0,10,0,13.852302074432373 +49,,SUM,0,0,0,0,4,75,8,38.399686098098755 +49,, +50,, +50,BOWL,SUM,0,0,0,0,0,7,0,10.269216775894165 +50,CUP,SUM,0,0,0,0,0,3,9,9.185931921005249 +50,SPOON,SUM,0,0,0,0,0,12,0,13.818592071533203 +50,,SUM,0,0,0,0,0,22,9,33.27374076843262 +50,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_17.5.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_17.5.csv new file mode 100644 index 0000000000..e1f21d1a00 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_17.5.csv @@ -0,0 +1,303 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,7,2,13.9451739788 +0,CUP,SUM,0,0,0,0,0,16,7,9.3566141129 +0,SPOON,SUM,0,0,0,0,0,15,2,14.1914579868 +0,,SUM,0,0,0,0,0,38,11,37.4932460785 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,0,18,0,10.1102399826 +1,CUP,SUM,0,0,0,0,0,14,8,8.8081021309 +1,SPOON,SUM,0,0,0,0,2,227,0,25.523884058 +1,,SUM,0,0,0,0,2,259,8,44.4422261715 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,0,100,10,19.1704981327 +2,CUP,SUM,0,0,0,0,0,9,2,8.4745750427 +2,SPOON,SUM,0,0,0,0,0,169,2,22.0678930283 +2,,SUM,0,0,0,0,0,278,14,49.7129662037 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,0,30,0,11.2277810574 +3,CUP,SUM,0,0,0,0,0,19,3,9.2081410885 +3,SPOON,SUM,0,0,0,0,0,8,0,13.306032896 +3,,SUM,0,0,0,0,0,57,3,33.7419550419 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,19,1,11.7038531303 +4,CUP,SUM,0,0,0,0,0,2,8,8.5587980747 +4,SPOON,SUM,0,0,0,0,0,37,0,14.9424569607 +4,,SUM,0,0,0,0,0,58,9,35.2051081657 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,0,23,10,17.6899728775 +5,CUP,SUM,0,0,0,0,2,7,3,8.9743900299 +5,SPOON,SUM,1,0,1,0,0,1581,0,0 +5,,SUM,1,0,1,0,2,1611,13,26.6643629074 +5,,,,,,,,,, +6,, +6,BOWL,SUM,0,0,0,0,0,7,2,14.569053173065186 +6,CUP,SUM,0,0,0,0,0,16,7,10.590179920196533 +6,SPOON,SUM,0,0,0,0,0,15,2,14.804325103759766 +6,,SUM,0,0,0,0,0,38,11,39.963558197021484 +6,, +7,, +7,BOWL,SUM,0,0,0,0,0,18,0,11.200407981872559 +7,CUP,SUM,0,0,0,0,0,14,8,8.936420202255249 +7,SPOON,SUM,0,0,0,0,2,227,0,25.1076500415802 +7,,SUM,0,0,0,0,2,259,8,45.24447822570801 +7,, +8,, +8,BOWL,SUM,0,0,0,0,0,100,10,18.979886054992676 +8,CUP,SUM,0,0,0,0,0,9,2,8.557487964630127 +8,SPOON,SUM,0,0,0,0,0,169,2,21.442219018936157 +8,,SUM,0,0,0,0,0,278,14,48.97959303855896 +8,, +9,, +9,BOWL,SUM,0,0,0,0,0,30,0,10.812140941619873 +9,CUP,SUM,0,0,0,0,0,19,3,9.081263780593872 +9,SPOON,SUM,0,0,0,0,0,8,0,12.920178174972534 +9,,SUM,0,0,0,0,0,57,3,32.81358289718628 +9,, +10,, +10,BOWL,SUM,0,0,0,0,0,19,1,11.476960182189941 +10,CUP,SUM,0,0,0,0,0,2,8,8.405571222305298 +10,SPOON,SUM,0,0,0,0,0,37,0,14.756139993667603 +10,,SUM,0,0,0,0,0,58,9,34.63867139816284 +10,, +11,, +11,BOWL,SUM,0,0,0,0,0,23,10,17.204679012298584 +11,CUP,SUM,0,0,0,0,2,7,3,8.853396892547607 +11,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +11,,SUM,1,0,1,0,2,1611,13,26.05807590484619 +11,, +12,, +12,BOWL,SUM,0,0,0,0,0,6,4,11.384666919708252 +12,CUP,SUM,0,0,0,0,0,95,26,39.408366203308105 +12,SPOON,SUM,0,0,0,0,0,2,2,12.932496070861816 +12,,SUM,0,0,0,0,0,103,32,63.725529193878174 +12,, +13,, +13,BOWL,SUM,0,0,0,0,0,19,0,10.42485499382019 +13,CUP,SUM,0,0,0,0,0,23,5,9.356853008270264 +13,SPOON,SUM,0,0,0,0,0,78,0,16.447747945785522 +13,,SUM,0,0,0,0,0,120,5,36.22945594787598 +13,, +14,, +14,BOWL,SUM,0,0,0,0,2,30,0,11.17302918434143 +14,CUP,SUM,0,0,0,0,0,4,10,9.832649230957031 +14,SPOON,SUM,0,0,0,0,0,145,1,21.066134929656982 +14,,SUM,0,0,0,0,2,179,11,42.071813344955444 +14,, +15,, +15,BOWL,SUM,0,0,0,0,0,4,0,9.947368860244751 +15,CUP,SUM,0,0,0,0,2,9,1,10.242518901824951 +15,SPOON,SUM,0,0,0,0,2,78,0,17.275336980819702 +15,,SUM,0,0,0,0,4,91,1,37.465224742889404 +15,, +16,, +16,BOWL,SUM,0,0,0,0,0,19,0,10.253627061843872 +16,CUP,SUM,1,0,1,0,0,170,95,0.0 +16,SPOON,SUM,0,0,0,0,0,9,0,13.149956941604614 +16,,SUM,1,0,1,0,0,198,95,23.403584003448486 +16,, +17,, +17,BOWL,SUM,0,0,0,0,0,7,0,10.030026197433472 +17,CUP,SUM,0,0,0,0,0,20,3,8.799379110336304 +17,SPOON,SUM,0,0,0,0,0,79,0,16.91415286064148 +17,,SUM,0,0,0,0,0,106,3,35.743558168411255 +17,, +18,, +18,BOWL,SUM,0,0,0,0,0,20,4,11.960149049758911 +18,CUP,SUM,0,0,0,0,0,34,6,14.278753995895386 +18,SPOON,SUM,0,0,0,0,8,2,0,16.315744161605835 +18,,SUM,0,0,0,0,8,56,10,42.55464720726013 +18,, +19,, +19,BOWL,SUM,0,0,0,0,0,80,14,20.573750972747803 +19,CUP,SUM,1,0,0,1,0,217,60,0.0 +19,SPOON,SUM,0,0,0,0,2,338,0,31.037477016448975 +19,,SUM,1,0,0,1,2,635,74,51.61122798919678 +19,, +20,, +20,BOWL,SUM,0,0,0,0,2,40,2,12.91769003868103 +20,CUP,SUM,0,0,0,0,0,13,0,8.69304609298706 +20,SPOON,SUM,0,0,0,0,0,5,0,13.22344708442688 +20,,SUM,0,0,0,0,2,58,2,34.83418321609497 +20,, +21,, +21,BOWL,SUM,0,0,0,0,10,48,0,15.75945496559143 +21,CUP,SUM,0,0,0,0,0,24,5,10.088212966918945 +21,SPOON,SUM,0,0,0,0,0,94,0,18.419475078582764 +21,,SUM,0,0,0,0,10,166,5,44.26714301109314 +21,, +22,, +22,BOWL,SUM,0,0,0,0,0,13,3,11.598948001861572 +22,CUP,SUM,0,0,0,0,0,6,4,8.176360845565796 +22,SPOON,SUM,0,0,0,0,0,172,1,23.1340069770813 +22,,SUM,0,0,0,0,0,191,8,42.90931582450867 +22,, +23,, +23,BOWL,SUM,0,0,0,0,0,4,2,10.038491010665894 +23,CUP,SUM,0,0,0,0,0,33,12,17.329558849334717 +23,SPOON,SUM,0,0,0,0,0,66,0,15.70145297050476 +23,,SUM,0,0,0,0,0,103,14,43.06950283050537 +23,, +24,, +24,BOWL,SUM,0,0,0,0,6,42,4,13.94121503829956 +24,CUP,SUM,0,0,0,0,2,17,2,8.982668161392212 +24,SPOON,SUM,0,0,0,0,0,77,2,16.55486798286438 +24,,SUM,0,0,0,0,8,136,8,39.47875118255615 +24,, +25,, +25,BOWL,SUM,0,0,0,0,2,15,0,10.481435060501099 +25,CUP,SUM,0,0,0,0,0,81,24,36.408385038375854 +25,SPOON,SUM,0,0,0,0,0,193,0,23.406883001327515 +25,,SUM,0,0,0,0,2,289,24,70.29670310020447 +25,, +26,, +26,BOWL,SUM,1,0,1,0,0,1259,42,0.0 +26,CUP,SUM,1,0,0,1,2,239,56,0.0 +26,SPOON,SUM,0,0,0,0,0,0,0,13.204085111618042 +26,,SUM,2,0,1,1,2,1498,98,13.204085111618042 +26,, +27,, +27,BOWL,SUM,0,0,0,0,0,30,0,10.55806589126587 +27,CUP,SUM,1,0,0,1,0,160,51,0.0 +27,SPOON,SUM,0,0,0,0,0,0,0,12.849298000335693 +27,,SUM,1,0,0,1,0,190,51,23.407363891601563 +27,, +28,, +28,BOWL,SUM,1,0,1,0,0,1292,22,0.0 +28,CUP,SUM,0,0,0,0,0,24,0,8.902515172958374 +28,SPOON,SUM,0,0,0,0,0,142,0,19.514474868774414 +28,,SUM,1,0,1,0,0,1458,22,28.416990041732788 +28,, +29,, +29,BOWL,SUM,0,0,0,0,0,167,0,18.36049509048462 +29,CUP,SUM,1,0,0,1,0,198,53,0.0 +29,SPOON,SUM,0,0,0,0,0,21,2,13.512940883636475 +29,,SUM,1,0,0,1,0,386,55,31.873435974121094 +29,, +30,, +30,BOWL,SUM,0,0,0,0,12,32,0,15.223389863967896 +30,CUP,SUM,1,0,0,1,2,289,53,0.0 +30,SPOON,SUM,0,0,0,0,0,321,14,37.370795011520386 +30,,SUM,1,0,0,1,14,642,67,52.59418487548828 +30,, +31,, +31,BOWL,SUM,0,0,0,0,0,7,0,10.19150996208191 +31,CUP,SUM,0,0,0,0,2,10,3,10.23010516166687 +31,SPOON,SUM,0,0,0,0,0,0,0,13.139682054519653 +31,,SUM,0,0,0,0,2,17,3,33.56129717826843 +31,, +32,, +32,BOWL,SUM,0,0,0,0,2,6,0,10.655803918838501 +32,CUP,SUM,0,0,0,0,0,17,3,10.097561120986938 +32,SPOON,SUM,0,0,0,0,2,84,2,17.654443979263306 +32,,SUM,0,0,0,0,4,107,5,38.407809019088745 +32,, +33,, +33,BOWL,SUM,0,0,0,0,0,6,2,10.740783929824829 +33,CUP,SUM,0,0,0,0,0,20,7,10.645166158676147 +33,SPOON,SUM,0,0,0,0,0,20,0,13.522602081298828 +33,,SUM,0,0,0,0,0,46,9,34.908552169799805 +33,, +34,, +34,BOWL,SUM,0,0,0,0,0,23,2,10.58270001411438 +34,CUP,SUM,0,0,0,0,0,27,10,9.403616905212402 +34,SPOON,SUM,0,0,0,0,0,156,0,21.383787155151367 +34,,SUM,0,0,0,0,0,206,12,41.37010407447815 +34,, +35,, +35,BOWL,SUM,0,0,0,0,0,27,0,10.596670866012573 +35,CUP,SUM,0,0,0,0,0,3,1,8.166481018066406 +35,SPOON,SUM,0,0,0,0,0,10,2,13.359344959259033 +35,,SUM,0,0,0,0,0,40,3,32.12249684333801 +35,, +36,, +36,BOWL,SUM,0,0,0,0,2,47,0,12.557111024856567 +36,CUP,SUM,0,0,0,0,0,12,1,8.524389028549194 +36,SPOON,SUM,0,0,0,0,0,14,0,13.490128993988037 +36,,SUM,0,0,0,0,2,73,1,34.5716290473938 +36,, +37,, +37,BOWL,SUM,1,0,1,0,0,865,82,0.0 +37,CUP,SUM,1,0,0,1,2,214,57,0.0 +37,SPOON,SUM,0,0,0,0,2,4,0,15.507368803024292 +37,,SUM,2,0,1,1,4,1083,139,15.507368803024292 +37,, +38,, +38,BOWL,SUM,0,0,0,0,178,126,2,88.01676297187805 +38,CUP,SUM,0,0,0,0,0,19,9,9.267417192459106 +38,SPOON,SUM,0,0,0,0,4,101,0,20.19009304046631 +38,,SUM,0,0,0,0,182,246,11,117.47427320480347 +38,, +39,, +39,BOWL,SUM,0,0,0,0,0,22,2,13.497056007385254 +39,CUP,SUM,0,0,0,0,8,16,11,14.414193153381348 +39,SPOON,SUM,1,0,1,0,0,1289,38,0.0 +39,,SUM,1,0,1,0,8,1327,51,27.9112491607666 +39,, +40,, +40,BOWL,SUM,0,0,0,0,10,22,0,14.437949895858765 +40,CUP,SUM,1,0,1,0,0,140,112,0.0 +40,SPOON,SUM,0,0,0,0,0,102,0,18.437822103500366 +40,,SUM,1,0,1,0,10,264,112,32.87577199935913 +40,, +41,, +41,BOWL,SUM,0,0,0,0,42,89,4,31.10947299003601 +41,CUP,SUM,0,0,0,0,0,6,0,8.41758918762207 +41,SPOON,SUM,0,0,0,0,6,0,3,18.390878915786743 +41,,SUM,0,0,0,0,48,95,7,57.917941093444824 +41,, +42,, +42,BOWL,SUM,0,0,0,0,0,11,0,10.248656988143921 +42,CUP,SUM,1,0,0,1,0,226,55,0.0 +42,SPOON,SUM,0,0,0,0,0,0,0,13.54102110862732 +42,,SUM,1,0,0,1,0,237,55,23.78967809677124 +42,, +43,, +43,BOWL,SUM,0,0,0,0,24,38,8,25.921900987625122 +43,CUP,SUM,0,0,0,0,0,22,13,16.09581184387207 +43,SPOON,SUM,0,0,0,0,0,2,0,12.961474895477295 +43,,SUM,0,0,0,0,24,62,21,54.97918772697449 +43,, +44,, +44,BOWL,SUM,0,0,0,0,0,13,0,10.451351165771484 +44,CUP,SUM,0,0,0,0,0,27,13,10.933742046356201 +44,SPOON,SUM,1,0,1,0,0,996,54,0.0 +44,,SUM,1,0,1,0,0,1036,67,21.385093212127686 +44,, +45,, +45,BOWL,SUM,0,0,0,0,6,73,4,17.175331115722656 +45,CUP,SUM,0,0,0,0,0,13,6,10.048475980758667 +45,SPOON,SUM,0,0,0,0,2,56,0,16.227377891540527 +45,,SUM,0,0,0,0,8,142,10,43.45118498802185 +45,, +46,, +46,BOWL,SUM,0,0,0,0,4,157,11,24.812328815460205 +46,CUP,SUM,1,0,0,1,58,196,60,0.0 +46,SPOON,SUM,1,0,1,0,0,1142,50,0.0 +46,,SUM,2,0,1,1,62,1495,121,24.812328815460205 +46,, +47,, +47,BOWL,SUM,0,0,0,0,46,251,20,49.130024909973145 +47,CUP,SUM,0,0,0,0,0,33,7,15.652801036834717 +47,SPOON,SUM,0,0,0,0,0,17,0,13.44504690170288 +47,,SUM,0,0,0,0,46,301,27,78.22787284851074 +47,, +48,, +48,BOWL,SUM,0,0,0,0,0,38,0,12.173233985900879 +48,CUP,SUM,0,0,0,0,0,1,8,8.477849006652832 +48,SPOON,SUM,0,0,0,0,0,75,2,15.905733108520508 +48,,SUM,0,0,0,0,0,114,10,36.55681610107422 +48,, +49,, +49,BOWL,SUM,0,0,0,0,0,62,6,15.302048921585083 +49,CUP,SUM,0,0,0,0,2,4,4,8.816324949264526 +49,SPOON,SUM,0,0,0,0,0,1,0,13.436700820922852 +49,,SUM,0,0,0,0,2,67,10,37.55507469177246 +49,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_20.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_20.csv new file mode 100644 index 0000000000..dbd2b3f2e2 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_20.csv @@ -0,0 +1,303 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +51,, +51,BOWL,SUM,0,0,0,0,4,15,2,12.186187982559204 +51,CUP,SUM,0,0,0,0,0,10,3,8.694437980651855 +51,SPOON,SUM,0,0,0,0,2,312,4,31.935042142868042 +51,,SUM,0,0,0,0,6,337,9,52.8156681060791 +51,, +52,, +52,BOWL,SUM,0,0,0,0,6,7,0,12.447911977767944 +52,CUP,SUM,0,0,0,0,0,18,6,11.798091888427734 +52,SPOON,SUM,0,0,0,0,0,90,2,18.22928500175476 +52,,SUM,0,0,0,0,6,115,8,42.47528886795044 +52,, +53,, +53,BOWL,SUM,0,0,0,0,0,53,0,12.314332962036133 +53,CUP,SUM,0,0,0,0,0,5,6,8.704952001571655 +53,SPOON,SUM,0,0,0,0,0,124,3,23.981666088104248 +53,,SUM,0,0,0,0,0,182,9,45.000951051712036 +53,, +54,, +54,BOWL,SUM,0,0,0,0,34,63,2,28.117475032806396 +54,CUP,SUM,0,0,0,0,0,88,23,38.69858694076538 +54,SPOON,SUM,0,0,0,0,0,59,2,16.146908044815063 +54,,SUM,0,0,0,0,34,210,27,82.96297001838684 +54,, +55,, +55,BOWL,SUM,0,0,0,0,48,22,0,33.44092607498169 +55,CUP,SUM,1,0,0,1,0,203,51,0.0 +55,SPOON,SUM,0,0,0,0,0,69,3,17.86117386817932 +55,,SUM,1,0,0,1,48,294,54,51.30209994316101 +55,, +56,, +56,BOWL,SUM,0,0,0,0,0,16,10,17.79976201057434 +56,CUP,SUM,1,0,0,1,0,192,57,0.0 +56,SPOON,SUM,0,0,0,0,0,6,1,15.176290035247803 +56,,SUM,1,0,0,1,0,214,68,32.976052045822144 +56,, +57,, +57,BOWL,SUM,0,0,0,0,0,12,0,10.769926071166992 +57,CUP,SUM,0,0,0,0,6,96,29,45.35774898529053 +57,SPOON,SUM,0,0,0,0,0,45,4,17.93012499809265 +57,,SUM,0,0,0,0,6,153,33,74.05780005455017 +57,, +58,, +58,BOWL,SUM,0,0,0,0,0,48,2,12.852033853530884 +58,CUP,SUM,0,0,0,0,0,44,7,12.131989002227783 +58,SPOON,SUM,0,0,0,0,6,8,1,17.21527099609375 +58,,SUM,0,0,0,0,6,100,10,42.19929385185242 +58,, +59,, +59,BOWL,SUM,0,0,0,0,4,82,2,16.159932851791382 +59,CUP,SUM,0,0,0,0,0,50,22,27.71592903137207 +59,SPOON,SUM,0,0,0,0,0,53,2,16.640881061553955 +59,,SUM,0,0,0,0,4,185,26,60.51674294471741 +59,, +60,, +60,BOWL,SUM,0,0,0,0,0,5,0,10.34693193435669 +60,CUP,SUM,0,0,0,0,0,3,5,8.527642965316772 +60,SPOON,SUM,0,0,0,0,0,35,0,15.415772199630737 +60,,SUM,0,0,0,0,0,43,5,34.2903470993042 +60,, +61,, +61,BOWL,SUM,0,0,0,0,0,18,1,10.455413103103638 +61,CUP,SUM,0,0,0,0,0,16,10,14.431854009628296 +61,SPOON,SUM,0,0,0,0,0,1,0,13.740025997161865 +61,,SUM,0,0,0,0,0,35,11,38.6272931098938 +61,, +62,, +62,BOWL,SUM,0,0,0,0,286,138,2,150.36397504806519 +62,CUP,SUM,0,0,0,0,0,57,20,26.223912954330444 +62,SPOON,SUM,0,0,0,0,0,0,0,13.494127988815308 +62,,SUM,0,0,0,0,286,195,22,190.08201599121094 +62,, +63,, +63,BOWL,SUM,0,0,0,0,0,141,0,16.95600414276123 +63,CUP,SUM,1,0,0,1,0,230,56,0.0 +63,SPOON,SUM,0,0,0,0,0,143,0,21.076701164245605 +63,,SUM,1,0,0,1,0,514,56,38.032705307006836 +63,, +64,, +64,BOWL,SUM,0,0,0,0,2,109,5,18.919923067092896 +64,CUP,SUM,0,0,0,0,2,20,8,12.867565155029297 +64,SPOON,SUM,0,0,0,0,8,5,0,17.776346921920776 +64,,SUM,0,0,0,0,12,134,13,49.56383514404297 +64,, +65,, +65,BOWL,SUM,0,0,0,0,0,5,0,10.566080093383789 +65,CUP,SUM,0,0,0,0,0,23,10,14.638098001480103 +65,SPOON,SUM,0,0,0,0,2,52,0,16.853545904159546 +65,,SUM,0,0,0,0,2,80,10,42.05772399902344 +65,, +66,, +66,BOWL,SUM,0,0,0,0,2,3,2,11.089510917663574 +66,CUP,SUM,1,0,0,1,0,163,54,0.0 +66,SPOON,SUM,1,0,1,0,0,1434,24,0.0 +66,,SUM,2,0,1,1,2,1600,80,11.089510917663574 +66,, +67,, +67,BOWL,SUM,0,0,0,0,0,3,0,10.365445852279663 +67,CUP,SUM,0,0,0,0,0,18,8,16.736809015274048 +67,SPOON,SUM,0,0,0,0,0,36,13,23.034528970718384 +67,,SUM,0,0,0,0,0,57,21,50.136783838272095 +67,, +68,, +68,BOWL,SUM,1,0,1,0,16,791,90,0.0 +68,CUP,SUM,0,0,0,0,2,15,5,13.586894035339355 +68,SPOON,SUM,0,0,0,0,0,77,2,18.019426107406616 +68,,SUM,1,0,1,0,18,883,97,31.60632014274597 +68,, +69,, +69,BOWL,SUM,0,0,0,0,0,18,0,11.257336139678955 +69,CUP,SUM,0,0,0,0,0,12,5,9.522210836410522 +69,SPOON,SUM,0,0,0,0,0,8,0,14.495919942855835 +69,,SUM,0,0,0,0,0,38,5,35.27546691894531 +69,, +70,, +70,BOWL,SUM,1,0,1,0,0,953,80,0.0 +70,CUP,SUM,0,0,0,0,6,5,9,11.116737842559814 +70,SPOON,SUM,0,0,0,0,0,174,16,30.245218992233276 +70,,SUM,1,0,1,0,6,1132,105,41.36195683479309 +70,, +71,, +71,BOWL,SUM,0,0,0,0,2,8,1,12.590007066726685 +71,CUP,SUM,0,0,0,0,0,7,4,8.428292036056519 +71,SPOON,SUM,1,0,1,0,0,1613,0,0.0 +71,,SUM,1,0,1,0,2,1628,5,21.018299102783203 +71,, +72,, +72,BOWL,SUM,0,0,0,0,0,9,0,10.573545932769775 +72,CUP,SUM,0,0,0,0,0,8,10,9.070533990859985 +72,SPOON,SUM,0,0,0,0,0,1,4,15.358044862747192 +72,,SUM,0,0,0,0,0,18,14,35.00212478637695 +72,, +73,, +73,BOWL,SUM,0,0,0,0,58,32,4,39.594969034194946 +73,CUP,SUM,0,0,0,0,2,59,25,32.58656883239746 +73,SPOON,SUM,0,0,0,0,0,299,8,34.284703969955444 +73,,SUM,0,0,0,0,60,390,37,106.46624183654785 +73,, +74,, +74,BOWL,SUM,0,0,0,0,2,42,0,13.573660850524902 +74,CUP,SUM,0,0,0,0,6,144,41,58.62905192375183 +74,SPOON,SUM,0,0,0,0,0,4,0,14.142145872116089 +74,,SUM,0,0,0,0,8,190,41,86.34485864639282 +74,, +75,, +75,BOWL,SUM,0,0,0,0,0,6,0,10.53589415550232 +75,CUP,SUM,0,0,0,0,10,14,2,13.013277769088745 +75,SPOON,SUM,0,0,0,0,0,116,3,23.39135193824768 +75,,SUM,0,0,0,0,10,136,5,46.940523862838745 +75,, +76,, +76,BOWL,SUM,0,0,0,0,4,18,0,12.253029108047485 +76,CUP,SUM,0,0,0,0,0,7,0,8.657482862472534 +76,SPOON,SUM,0,0,0,0,0,224,0,25.863271951675415 +76,,SUM,0,0,0,0,4,249,0,46.773783922195435 +76,, +77,, +77,BOWL,SUM,0,0,0,0,0,2,0,10.150593996047974 +77,CUP,SUM,0,0,0,0,0,9,3,10.202600002288818 +77,SPOON,SUM,0,0,0,0,0,72,2,17.98551607131958 +77,,SUM,0,0,0,0,0,83,5,38.33871006965637 +77,, +78,, +78,BOWL,SUM,0,0,0,0,4,21,0,12.10313105583191 +78,CUP,SUM,0,0,0,0,2,20,11,11.601127862930298 +78,SPOON,SUM,0,0,0,0,0,22,0,14.111839056015015 +78,,SUM,0,0,0,0,6,63,11,37.81609797477722 +78,, +79,, +79,BOWL,SUM,0,0,0,0,0,12,2,10.349902868270874 +79,CUP,SUM,0,0,0,0,4,50,7,17.518488883972168 +79,SPOON,SUM,0,0,0,0,0,0,0,13.499490022659302 +79,,SUM,0,0,0,0,4,62,9,41.367881774902344 +79,, +80,, +80,BOWL,SUM,0,0,0,0,0,7,2,10.642746925354004 +80,CUP,SUM,0,0,0,0,0,2,3,8.670536994934082 +80,SPOON,SUM,0,0,0,0,0,5,0,13.960278034210205 +80,,SUM,0,0,0,0,0,14,5,33.27356195449829 +80,, +81,, +81,BOWL,SUM,0,0,0,0,2,6,0,11.157981872558594 +81,CUP,SUM,0,0,0,0,16,97,21,43.04349708557129 +81,SPOON,SUM,0,0,0,0,0,90,1,17.96235704421997 +81,,SUM,0,0,0,0,18,193,22,72.16383600234985 +81,, +82,, +82,BOWL,SUM,0,0,0,0,0,19,0,10.84932804107666 +82,CUP,SUM,1,0,0,1,0,177,53,0.0 +82,SPOON,SUM,0,0,0,0,0,234,2,26.59049892425537 +82,,SUM,1,0,0,1,0,430,55,37.43982696533203 +82,, +83,, +83,BOWL,SUM,0,0,0,0,0,19,0,10.467561960220337 +83,CUP,SUM,0,0,0,0,0,74,21,26.53603196144104 +83,SPOON,SUM,1,0,1,0,0,1037,60,0.0 +83,,SUM,1,0,1,0,0,1130,81,37.00359392166138 +83,, +84,, +84,BOWL,SUM,0,0,0,0,2,13,6,14.226849794387817 +84,CUP,SUM,0,0,0,0,0,6,2,8.5852370262146 +84,SPOON,SUM,0,0,0,0,0,166,0,22.261247873306274 +84,,SUM,0,0,0,0,2,185,8,45.07333469390869 +84,, +85,, +85,BOWL,SUM,0,0,0,0,0,3,0,10.364792823791504 +85,CUP,SUM,1,0,0,1,2,197,51,0.0 +85,SPOON,SUM,1,0,1,0,4,1544,0,0.0 +85,,SUM,2,0,1,1,6,1744,51,10.364792823791504 +85,, +86,, +86,BOWL,SUM,0,0,0,0,62,15,0,36.122886180877686 +86,CUP,SUM,0,0,0,0,0,5,2,8.37294888496399 +86,SPOON,SUM,0,0,0,0,0,4,2,16.121750831604004 +86,,SUM,0,0,0,0,62,24,4,60.61758589744568 +86,, +87,, +87,BOWL,SUM,0,0,0,0,0,61,4,13.421251058578491 +87,CUP,SUM,1,0,0,1,0,214,57,0.0 +87,SPOON,SUM,0,0,0,0,0,31,0,14.234555006027222 +87,,SUM,1,0,0,1,0,306,61,27.655806064605713 +87,, +88,, +88,BOWL,SUM,1,0,1,0,6,931,70,0.0 +88,CUP,SUM,0,0,0,0,0,33,13,12.891424894332886 +88,SPOON,SUM,0,0,0,0,0,113,1,21.246580839157104 +88,,SUM,1,0,1,0,6,1077,84,34.13800573348999 +88,, +89,, +89,BOWL,SUM,0,0,0,0,0,30,4,12.414751052856445 +89,CUP,SUM,0,0,0,0,0,7,4,8.872709035873413 +89,SPOON,SUM,0,0,0,0,0,35,0,15.58523416519165 +89,,SUM,0,0,0,0,0,72,8,36.87269425392151 +89,, +90,, +90,BOWL,SUM,0,0,0,0,0,17,0,10.800798177719116 +90,CUP,SUM,1,0,0,1,0,180,54,0.0 +90,SPOON,SUM,0,0,0,0,0,60,1,17.781461000442505 +90,,SUM,1,0,0,1,0,257,55,28.58225917816162 +90,, +91,, +91,BOWL,SUM,0,0,0,0,168,216,4,97.5922749042511 +91,CUP,SUM,0,0,0,0,6,28,9,15.45278286933899 +91,SPOON,SUM,0,0,0,0,0,2,3,17.773619890213013 +91,,SUM,0,0,0,0,174,246,16,130.8186776638031 +91,, +92,, +92,BOWL,SUM,0,0,0,0,0,12,0,10.466746807098389 +92,CUP,SUM,0,0,0,0,0,1,4,8.700435876846313 +92,SPOON,SUM,0,0,0,0,0,5,5,17.177227020263672 +92,,SUM,0,0,0,0,0,18,9,36.344409704208374 +92,, +93,, +93,BOWL,SUM,0,0,0,0,0,54,4,14.841961860656738 +93,CUP,SUM,0,0,0,0,0,13,2,9.106750965118408 +93,SPOON,SUM,0,0,0,0,0,30,3,18.392714977264404 +93,,SUM,0,0,0,0,0,97,9,42.34142780303955 +93,, +94,, +94,BOWL,SUM,0,0,0,0,2,91,10,20.091187000274658 +94,CUP,SUM,1,0,0,1,0,188,58,0.0 +94,SPOON,SUM,0,0,0,0,0,14,6,19.539252042770386 +94,,SUM,1,0,0,1,2,293,74,39.630439043045044 +94,, +95,, +95,BOWL,SUM,1,0,1,0,6,561,98,0.0 +95,CUP,SUM,0,0,0,0,0,20,16,14.256440877914429 +95,SPOON,SUM,0,0,0,0,6,142,8,26.334341764450073 +95,,SUM,1,0,1,0,12,723,122,40.5907826423645 +95,, +96,, +96,BOWL,SUM,0,0,0,0,0,20,4,12.607413053512573 +96,CUP,SUM,1,0,0,1,0,179,59,0.0 +96,SPOON,SUM,0,0,0,0,0,0,0,13.926568984985352 +96,,SUM,1,0,0,1,0,199,63,26.533982038497925 +96,, +97,, +97,BOWL,SUM,0,0,0,0,0,22,0,10.727303981781006 +97,CUP,SUM,1,0,0,1,6,138,60,0.0 +97,SPOON,SUM,0,0,0,0,0,2,7,17.95981502532959 +97,,SUM,1,0,0,1,6,162,67,28.687119007110596 +97,, +98,, +98,BOWL,SUM,1,0,1,0,2,1011,68,0.0 +98,CUP,SUM,0,0,0,0,0,28,2,9.329376935958862 +98,SPOON,SUM,0,0,0,0,8,10,5,22.075309991836548 +98,,SUM,1,0,1,0,10,1049,75,31.40468692779541 +98,, +99,, +99,BOWL,SUM,0,0,0,0,0,6,0,10.95746397972107 +99,CUP,SUM,0,0,0,0,0,6,8,9.32381296157837 +99,SPOON,SUM,0,0,0,0,2,51,3,19.4740309715271 +99,,SUM,0,0,0,0,2,63,11,39.75530791282654 +99,, +100,, +100,BOWL,SUM,0,0,0,0,0,19,1,12.473479986190796 +100,CUP,SUM,0,0,0,0,0,14,11,10.779015064239502 +100,SPOON,SUM,0,0,0,0,0,716,1,54.970688819885254 +100,,SUM,0,0,0,0,0,749,13,78.22318387031555 +100,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_25.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_25.csv new file mode 100644 index 0000000000..2704c8490d --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_orig_data_offset_25.csv @@ -0,0 +1,303 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +50,, +50,BOWL,SUM,1,0,1,0,0,890,70,0.0 +50,CUP,SUM,0,0,0,0,0,12,6,8.93585991859436 +50,SPOON,SUM,0,0,0,0,0,453,12,44.15076303482056 +50,,SUM,1,0,1,0,0,1355,88,53.08662295341492 +50,, +51,, +51,BOWL,SUM,1,0,1,0,0,967,47,0.0 +51,CUP,SUM,0,0,0,0,0,82,37,46.40668988227844 +51,SPOON,SUM,0,0,0,0,0,106,7,25.567936897277832 +51,,SUM,1,0,1,0,0,1155,91,71.97462677955627 +51,, +52,, +52,BOWL,SUM,0,0,0,0,0,29,6,13.804650068283081 +52,CUP,SUM,0,0,0,0,0,21,9,13.233856916427612 +52,SPOON,SUM,0,0,0,0,0,2,4,14.682561159133911 +52,,SUM,0,0,0,0,0,52,19,41.721068143844604 +52,, +53,, +53,BOWL,SUM,0,0,0,0,0,43,10,17.65164589881897 +53,CUP,SUM,0,0,0,0,0,21,10,9.393015146255493 +53,SPOON,SUM,0,0,0,0,0,102,13,28.881847143173218 +53,,SUM,0,0,0,0,0,166,33,55.92650818824768 +53,, +54,, +54,BOWL,SUM,1,0,1,0,0,437,100,0.0 +54,CUP,SUM,0,0,0,0,0,4,10,9.04190182685852 +54,SPOON,SUM,1,0,1,0,0,1192,44,0.0 +54,,SUM,2,0,2,0,0,1633,154,9.04190182685852 +54,, +55,, +55,BOWL,SUM,0,0,0,0,2,8,0,10.630002975463867 +55,CUP,SUM,0,0,0,0,0,9,5,8.587064981460571 +55,SPOON,SUM,0,0,0,0,0,23,3,17.33568501472473 +55,,SUM,0,0,0,0,2,40,8,36.55275297164917 +55,, +56,, +56,BOWL,SUM,0,0,0,0,0,57,0,12.858620882034302 +56,CUP,SUM,0,0,0,0,2,17,14,18.43940806388855 +56,SPOON,SUM,0,0,0,0,0,74,12,22.124573945999146 +56,,SUM,0,0,0,0,2,148,26,53.422602891922 +56,, +57,, +57,BOWL,SUM,0,0,0,0,0,8,4,11.6407630443573 +57,CUP,SUM,1,0,0,1,0,171,55,0.0 +57,SPOON,SUM,0,0,0,0,0,22,1,15.173563957214355 +57,,SUM,1,0,0,1,0,201,60,26.814327001571655 +57,, +58,, +58,BOWL,SUM,0,0,0,0,0,8,0,10.147644996643066 +58,CUP,SUM,0,0,0,0,0,21,4,8.889150142669678 +58,SPOON,SUM,0,0,0,0,0,5,3,16.8959059715271 +58,,SUM,0,0,0,0,0,34,7,35.932701110839844 +58,, +59,, +59,BOWL,SUM,0,0,0,0,0,9,1,12.13927412033081 +59,CUP,SUM,1,0,1,0,24,279,111,0.0 +59,SPOON,SUM,1,0,1,0,0,1180,46,0.0 +59,,SUM,2,0,2,0,24,1468,158,12.13927412033081 +59,, +60,, +60,BOWL,SUM,1,0,1,0,18,424,102,0.0 +60,CUP,SUM,0,0,0,0,0,31,3,10.728516817092896 +60,SPOON,SUM,0,0,0,0,32,337,10,54.98841691017151 +60,,SUM,1,0,1,0,50,792,115,65.7169337272644 +60,, +61,, +61,BOWL,SUM,0,0,0,0,0,14,0,10.445367097854614 +61,CUP,SUM,0,0,0,0,6,26,13,15.202934980392456 +61,SPOON,SUM,0,0,0,0,0,1,3,14.588773965835571 +61,,SUM,0,0,0,0,6,41,16,40.23707604408264 +61,, +62,, +62,BOWL,SUM,1,0,1,0,22,433,96,0.0 +62,CUP,SUM,1,0,0,1,0,158,55,0.0 +62,SPOON,SUM,1,0,1,0,0,1297,46,0.0 +62,,SUM,3,0,2,1,22,1888,197,0.0 +62,, +63,, +63,BOWL,SUM,0,0,0,0,10,438,58,68.298819065094 +63,CUP,SUM,0,0,0,0,0,3,8,8.833461999893188 +63,SPOON,SUM,1,0,1,0,0,1326,40,0.0 +63,,SUM,1,0,1,0,10,1767,106,77.13228106498718 +63,, +64,, +64,BOWL,SUM,1,0,1,0,0,1098,56,0.0 +64,CUP,SUM,1,0,0,1,0,169,55,0.0 +64,SPOON,SUM,0,0,0,0,0,29,13,23.660743951797485 +64,,SUM,2,0,1,1,0,1296,124,23.660743951797485 +64,, +65,, +65,BOWL,SUM,0,0,0,0,0,18,2,10.731034994125366 +65,CUP,SUM,0,0,0,0,0,15,2,8.498472929000854 +65,SPOON,SUM,0,0,0,0,0,76,6,19.24315595626831 +65,,SUM,0,0,0,0,0,109,10,38.47266387939453 +65,, +66,, +66,BOWL,SUM,0,0,0,0,2,45,8,16.184258937835693 +66,CUP,SUM,0,0,0,0,32,35,14,29.284816026687622 +66,SPOON,SUM,0,0,0,0,0,9,23,29.834562063217163 +66,,SUM,0,0,0,0,34,89,45,75.30363702774048 +66,, +67,, +67,BOWL,SUM,0,0,0,0,0,4,0,10.265935897827148 +67,CUP,SUM,1,0,0,1,4,225,57,0.0 +67,SPOON,SUM,0,0,0,0,0,21,0,14.22153115272522 +67,,SUM,1,0,0,1,4,250,57,24.487467050552368 +67,, +68,, +68,BOWL,SUM,0,0,0,0,0,32,17,22.394520044326782 +68,CUP,SUM,0,0,0,0,0,19,4,9.301872968673706 +68,SPOON,SUM,1,0,1,0,0,1314,34,0.0 +68,,SUM,1,0,1,0,0,1365,55,31.69639301300049 +68,, +69,, +69,BOWL,SUM,0,0,0,0,0,6,0,10.409188032150269 +69,CUP,SUM,0,0,0,0,0,21,8,12.14023208618164 +69,SPOON,SUM,0,0,0,0,0,65,7,23.30705976486206 +69,,SUM,0,0,0,0,0,92,15,45.85647988319397 +69,, +70,, +70,BOWL,SUM,0,0,0,0,0,141,28,33.31101608276367 +70,CUP,SUM,0,0,0,0,6,13,1,12.015382051467896 +70,SPOON,SUM,0,0,0,0,0,7,2,16.074002981185913 +70,,SUM,0,0,0,0,6,161,31,61.40040111541748 +70,, +71,, +71,BOWL,SUM,0,0,0,0,0,28,4,12.740403890609741 +71,CUP,SUM,0,0,0,0,0,7,7,8.91979694366455 +71,SPOON,SUM,0,0,0,0,2,110,10,24.808822870254517 +71,,SUM,0,0,0,0,2,145,21,46.46902370452881 +71,, +72,, +72,BOWL,SUM,0,0,0,0,6,12,0,12.341320991516113 +72,CUP,SUM,0,0,0,0,8,47,27,33.37550497055054 +72,SPOON,SUM,1,0,1,0,0,1302,40,0.0 +72,,SUM,1,0,1,0,14,1361,67,45.71682596206665 +72,, +73,, +73,BOWL,SUM,0,0,0,0,0,18,5,16.702401161193848 +73,CUP,SUM,1,0,0,1,2,180,59,0.0 +73,SPOON,SUM,0,0,0,0,0,83,8,22.744966983795166 +73,,SUM,1,0,0,1,2,281,72,39.447368144989014 +73,, +74,, +74,BOWL,SUM,0,0,0,0,0,41,14,20.84632706642151 +74,CUP,SUM,1,0,0,1,2,186,51,0.0 +74,SPOON,SUM,0,0,0,0,0,36,5,16.862563133239746 +74,,SUM,1,0,0,1,2,263,70,37.708890199661255 +74,, +75,, +75,BOWL,SUM,0,0,0,0,2,7,3,14.638206005096436 +75,CUP,SUM,0,0,0,0,0,21,10,19.790127992630005 +75,SPOON,SUM,0,0,0,0,0,7,2,13.7706139087677 +75,,SUM,0,0,0,0,2,35,15,48.19894790649414 +75,, +76,, +76,BOWL,SUM,0,0,0,0,6,9,2,15.022495985031128 +76,CUP,SUM,0,0,0,0,0,16,10,9.429924011230469 +76,SPOON,SUM,1,0,1,0,6,1419,18,0.0 +76,,SUM,1,0,1,0,12,1444,30,24.452419996261597 +76,, +77,, +77,BOWL,SUM,0,0,0,0,12,40,4,17.88798499107361 +77,CUP,SUM,0,0,0,0,0,10,0,8.317317008972168 +77,SPOON,SUM,1,0,1,0,0,1401,26,0.0 +77,,SUM,1,0,1,0,12,1451,30,26.205302000045776 +77,, +78,, +78,BOWL,SUM,0,0,0,0,0,247,15,30.96972417831421 +78,CUP,SUM,0,0,0,0,0,6,7,12.731056213378906 +78,SPOON,SUM,1,0,1,0,0,672,88,0.0 +78,,SUM,1,0,1,0,0,925,110,43.700780391693115 +78,, +79,, +79,BOWL,SUM,0,0,0,0,0,7,2,10.600502014160156 +79,CUP,SUM,0,0,0,0,0,11,2,8.640973806381226 +79,SPOON,SUM,1,0,1,0,0,1252,40,0.0 +79,,SUM,1,0,1,0,0,1270,44,19.241475820541382 +79,, +80,, +80,BOWL,SUM,0,0,0,0,0,51,1,12.557586193084717 +80,CUP,SUM,0,0,0,0,0,9,3,9.993021965026855 +80,SPOON,SUM,0,0,0,0,0,13,3,15.327550172805786 +80,,SUM,0,0,0,0,0,73,7,37.87815833091736 +80,, +81,, +81,BOWL,SUM,1,0,1,0,0,732,92,0.0 +81,CUP,SUM,0,0,0,0,0,2,2,8.722843885421753 +81,SPOON,SUM,0,0,0,0,0,52,2,16.04670286178589 +81,,SUM,1,0,1,0,0,786,96,24.76954674720764 +81,, +82,, +82,BOWL,SUM,0,0,0,0,0,16,2,13.39530897140503 +82,CUP,SUM,0,0,0,0,2,3,6,10.585959911346436 +82,SPOON,SUM,0,0,0,0,0,111,8,29.192575931549072 +82,,SUM,0,0,0,0,2,130,16,53.17384481430054 +82,, +83,, +83,BOWL,SUM,0,0,0,0,0,17,0,10.554890871047974 +83,CUP,SUM,0,0,0,0,0,33,6,14.669070959091187 +83,SPOON,SUM,0,0,0,0,0,147,12,28.444278955459595 +83,,SUM,0,0,0,0,0,197,18,53.668240785598755 +83,, +84,, +84,BOWL,SUM,0,0,0,0,0,15,4,12.327567100524902 +84,CUP,SUM,0,0,0,0,0,17,3,8.916131019592285 +84,SPOON,SUM,0,0,0,0,0,40,1,15.481518983840942 +84,,SUM,0,0,0,0,0,72,8,36.72521710395813 +84,, +85,, +85,BOWL,SUM,0,0,0,0,0,716,46,75.24214506149292 +85,CUP,SUM,0,0,0,0,2,4,2,9.504024982452393 +85,SPOON,SUM,0,0,0,0,0,16,5,16.913002967834473 +85,,SUM,0,0,0,0,2,736,53,101.65917301177979 +85,, +86,, +86,BOWL,SUM,0,0,0,0,0,76,0,13.902153015136719 +86,CUP,SUM,1,0,0,1,0,196,60,0.0 +86,SPOON,SUM,0,0,0,0,0,2,2,13.331705093383789 +86,,SUM,1,0,0,1,0,274,62,27.233858108520508 +86,, +87,, +87,BOWL,SUM,1,0,1,0,0,926,70,0.0 +87,CUP,SUM,0,0,0,0,0,14,18,16.63231110572815 +87,SPOON,SUM,0,0,0,0,0,60,4,18.65141010284424 +87,,SUM,1,0,1,0,0,1000,92,35.28372120857239 +87,, +88,, +88,BOWL,SUM,0,0,0,0,6,17,0,12.441144943237305 +88,CUP,SUM,1,0,0,1,0,225,55,0.0 +88,SPOON,SUM,0,0,0,0,0,1,3,17.295112133026123 +88,,SUM,1,0,0,1,6,243,58,29.736257076263428 +88,, +89,, +89,BOWL,SUM,0,0,0,0,0,33,14,20.267099857330322 +89,CUP,SUM,0,0,0,0,0,12,15,18.829206943511963 +89,SPOON,SUM,0,0,0,0,2,1,5,20.32014799118042 +89,,SUM,0,0,0,0,2,46,34,59.416454792022705 +89,, +90,, +90,BOWL,SUM,0,0,0,0,6,70,10,20.74235200881958 +90,CUP,SUM,0,0,0,0,0,110,33,34.49366998672485 +90,SPOON,SUM,0,0,0,0,0,61,0,15.986006021499634 +90,,SUM,0,0,0,0,6,241,43,71.22202801704407 +90,, +91,, +91,BOWL,SUM,0,0,0,0,0,35,0,12.119944095611572 +91,CUP,SUM,0,0,0,0,0,42,12,20.57489800453186 +91,SPOON,SUM,0,0,0,0,4,101,2,22.244054794311523 +91,,SUM,0,0,0,0,4,178,14,54.938896894454956 +91,, +92,, +92,BOWL,SUM,0,0,0,0,0,25,2,13.28533387184143 +92,CUP,SUM,0,0,0,0,6,15,4,13.01633906364441 +92,SPOON,SUM,0,0,0,0,0,2,3,14.87937593460083 +92,,SUM,0,0,0,0,6,42,9,41.18104887008667 +92,, +93,, +93,BOWL,SUM,0,0,0,0,0,40,2,12.698732137680054 +93,CUP,SUM,1,0,0,1,0,183,51,0.0 +93,SPOON,SUM,0,0,0,0,2,6,3,17.82746410369873 +93,,SUM,1,0,0,1,2,229,56,30.526196241378784 +93,, +94,, +94,BOWL,SUM,0,0,0,0,2,8,2,11.662945032119751 +94,CUP,SUM,0,0,0,0,2,17,4,12.674993991851807 +94,SPOON,SUM,1,0,1,0,0,1338,44,0.0 +94,,SUM,1,0,1,0,4,1363,50,24.337939023971558 +94,, +95,, +95,BOWL,SUM,0,0,0,0,0,5,2,10.581735849380493 +95,CUP,SUM,0,0,0,0,0,4,10,9.249181032180786 +95,SPOON,SUM,1,0,1,0,0,1406,26,0.0 +95,,SUM,1,0,1,0,0,1415,38,19.83091688156128 +95,, +96,, +96,BOWL,SUM,0,0,0,0,6,9,2,14.224050045013428 +96,CUP,SUM,1,0,0,1,0,174,54,0.0 +96,SPOON,SUM,0,0,0,0,2,111,10,28.31165313720703 +96,,SUM,1,0,0,1,8,294,66,42.53570318222046 +96,, +97,, +97,BOWL,SUM,0,0,0,0,0,381,26,47.864253997802734 +97,CUP,SUM,1,0,0,1,0,147,51,0.0 +97,SPOON,SUM,0,0,0,0,0,4,5,17.922039031982422 +97,,SUM,1,0,0,1,0,532,82,65.78629302978516 +97,, +98,, +98,BOWL,SUM,1,0,1,0,10,1045,70,0.0 +98,CUP,SUM,0,0,0,0,0,16,6,13.320242881774902 +98,SPOON,SUM,0,0,0,0,0,87,3,21.136648893356323 +98,,SUM,1,0,1,0,10,1148,79,34.456891775131226 +98,, +99,, +99,BOWL,SUM,0,0,0,0,2,3,0,11.718209981918335 +99,CUP,SUM,1,0,0,1,0,164,57,0.0 +99,SPOON,SUM,0,0,0,0,0,79,24,37.985482931137085 +99,,SUM,1,0,0,1,2,246,81,49.70369291305542 +99,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_14.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_14.csv new file mode 100644 index 0000000000..287b35831a --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_14.csv @@ -0,0 +1,603 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,16,5,19.7104530334 +0,CUP,SUM,0,0,0,0,0,4,2,10.5347168446 +0,SPOON,SUM,0,0,0,0,4,22,0,15.8982439041 +0,,SUM,0,0,0,0,4,42,7,46.1434137821 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,0,30,0,12.6628859043 +1,CUP,SUM,0,0,0,0,0,27,2,11.221683979 +1,SPOON,SUM,1,0,1,0,2,1581,0,0 +1,,SUM,1,0,1,0,2,1638,2,23.8845698833 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,0,74,12,21.5048098564 +2,CUP,SUM,0,0,0,0,0,10,2,9.9219989777 +2,SPOON,SUM,0,0,0,0,0,86,2,18.3816020489 +2,,SUM,0,0,0,0,0,170,16,49.8084108829 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,10,24,3,17.5297119617 +3,CUP,SUM,0,0,0,0,0,5,1,9.7039110661 +3,SPOON,SUM,0,0,0,0,2,24,4,17.3498659134 +3,,SUM,0,0,0,0,12,53,8,44.5834889412 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,56,69,0,38.2279188633 +4,CUP,SUM,0,0,0,0,0,30,1,9.9705960751 +4,SPOON,SUM,0,0,0,0,18,1,0,22.3829779625 +4,,SUM,0,0,0,0,74,100,1,70.5814929008 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,0,37,6,15.4214169979 +5,CUP,SUM,0,0,0,0,0,5,7,9.953122139 +5,SPOON,SUM,1,0,1,0,0,1591,0,0 +5,,SUM,1,0,1,0,0,1633,13,25.3745391369 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,0,5,0,11.1817610264 +6,CUP,SUM,0,0,0,0,0,27,0,9.9061229229 +6,SPOON,SUM,0,0,0,0,2,173,0,24.8599381447 +6,,SUM,0,0,0,0,2,205,0,45.947822094 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,4,16,8,18.9419031143 +7,CUP,SUM,0,0,0,0,4,27,0,11.5123288631 +7,SPOON,SUM,1,0,1,0,10,1593,0,0 +7,,SUM,1,0,1,0,18,1636,8,30.4542319775 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,2,22,0,12.1499590874 +8,CUP,SUM,0,0,0,0,0,23,0,10.0172710419 +8,SPOON,SUM,0,0,0,0,0,5,6,18.7393159866 +8,,SUM,0,0,0,0,2,50,6,40.9065461159 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,1,0,1,0,0,1376,24,0 +9,CUP,SUM,0,0,0,0,0,25,10,10.7706189156 +9,SPOON,SUM,0,0,0,0,4,8,2,16.1837770939 +9,,SUM,1,0,1,0,4,1409,36,26.9543960094 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,42,0,13.0719168186 +10,CUP,SUM,0,0,0,0,0,16,2,9.9536838531 +10,SPOON,SUM,0,0,0,0,0,128,1,22.0167140961 +10,,SUM,0,0,0,0,0,186,3,45.0423147678 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,0,140,0,18.1159079075 +11,CUP,SUM,0,0,0,0,0,5,4,9.7439479828 +11,SPOON,SUM,0,0,0,0,0,103,4,21.2222321033 +11,,SUM,0,0,0,0,0,248,8,49.0820879936 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,6,326,0,30.9046521187 +12,CUP,SUM,1,0,0,1,2,373,51,0 +12,SPOON,SUM,1,0,1,0,0,1649,0,0 +12,,SUM,2,0,1,1,8,2348,51,30.9046521187 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,0,143,2,19.4246320724 +13,CUP,SUM,0,0,0,0,0,5,2,9.7750768661 +13,SPOON,SUM,0,0,0,0,6,13,0,16.6959159374 +13,,SUM,0,0,0,0,6,161,4,45.895624876 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,0,52,1,13.7049689293 +14,CUP,SUM,0,0,0,0,0,37,2,11.643581152 +14,SPOON,SUM,0,0,0,0,0,7,0,14.5907931328 +14,,SUM,0,0,0,0,0,96,3,39.939343214 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,0,8,0,11.3100960255 +15,CUP,SUM,0,0,0,0,0,16,2,10.1909000874 +15,SPOON,SUM,0,0,0,0,0,14,2,14.4327809811 +15,,SUM,0,0,0,0,0,38,4,35.9337770939 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,40,0,12.0391960144 +16,CUP,SUM,0,0,0,0,2,8,2,10.4260110855 +16,SPOON,SUM,0,0,0,0,0,194,0,26.4936220646 +16,,SUM,0,0,0,0,2,242,2,48.9588291645 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,0,2,0,11.2001259327 +17,CUP,SUM,0,0,0,0,0,5,5,9.9287569523 +17,SPOON,SUM,0,0,0,0,0,700,0,58.2422640324 +17,,SUM,0,0,0,0,0,707,5,79.3711469173 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,2,1,2,11.9095649719 +18,CUP,SUM,0,0,0,0,0,33,12,12.910241127 +18,SPOON,SUM,0,0,0,0,0,62,0,17.2643418312 +18,,SUM,0,0,0,0,2,96,14,42.0841479301 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,79,10,19.7947318554 +19,CUP,SUM,0,0,0,0,0,7,7,9.9072699547 +19,SPOON,SUM,0,0,0,0,0,356,0,35.2960920334 +19,,SUM,0,0,0,0,0,442,17,64.9980938435 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,0,34,1,13.5036070347 +20,CUP,SUM,1,0,0,1,0,254,62,0 +20,SPOON,SUM,0,0,0,0,2,118,1,22.6949779987 +20,,SUM,1,0,0,1,2,406,64,36.1985850334 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,8,0,11.1276299953 +21,CUP,SUM,0,0,0,0,0,21,0,9.8739218712 +21,SPOON,SUM,0,0,0,0,8,4,3,19.5607919693 +21,,SUM,0,0,0,0,8,33,3,40.5623438358 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,0,37,0,11.9925680161 +22,CUP,SUM,1,0,0,1,2,406,55,0 +22,SPOON,SUM,1,0,1,0,10,1665,0,0 +22,,SUM,2,0,1,1,12,2108,55,11.9925680161 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,92,0,15.6032829285 +23,CUP,SUM,1,0,0,1,2,394,72,0 +23,SPOON,SUM,0,0,0,0,0,10,0,14.5753939152 +23,,SUM,1,0,0,1,2,496,72,30.1786768436 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,6,344,0,34.0303580761 +24,CUP,SUM,1,0,0,1,14,392,63,0 +24,SPOON,SUM,0,0,0,0,0,3,2,14.4368619919 +24,,SUM,1,0,0,1,20,739,65,48.467220068 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,0,21,2,14.6593379974 +25,CUP,SUM,0,0,0,0,0,1,4,9.5238339901 +25,SPOON,SUM,0,0,0,0,0,16,0,14.6673381329 +25,,SUM,0,0,0,0,0,38,6,38.8505101204 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,0,401,8,37.3130497932 +26,CUP,SUM,1,0,0,1,0,466,67,0 +26,SPOON,SUM,0,0,0,0,18,118,0,28.9122610092 +26,,SUM,1,0,0,1,18,985,75,66.2253108025 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,0,16,0,11.5010471344 +27,CUP,SUM,1,0,0,1,0,352,53,0 +27,SPOON,SUM,0,0,0,0,0,10,0,14.6955461502 +27,,SUM,1,0,0,1,0,378,53,26.1965932846 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,0,14,0,11.8806929588 +28,CUP,SUM,1,0,0,1,0,390,63,0 +28,SPOON,SUM,0,0,0,0,16,19,1,23.576633215 +28,,SUM,1,0,0,1,16,423,64,35.4573261738 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,0,101,0,17.1687619686 +29,CUP,SUM,1,0,0,1,16,449,58,0 +29,SPOON,SUM,0,0,0,0,0,3,0,14.3934080601 +29,,SUM,1,0,0,1,16,553,58,31.5621700287 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,0,42,1,13.6012868881 +30,CUP,SUM,0,0,0,0,10,30,2,14.7344961166 +30,SPOON,SUM,0,0,0,0,0,60,0,16.9963228703 +30,,SUM,0,0,0,0,10,132,3,45.332105875 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,0,64,0,13.9033911228 +31,CUP,SUM,0,0,0,0,0,43,7,14.380407095 +31,SPOON,SUM,0,0,0,0,0,18,0,14.4227459431 +31,,SUM,0,0,0,0,0,125,7,42.7065441608 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,4,11,0,12.6414430141 +32,CUP,SUM,0,0,0,0,0,10,5,10.2919728756 +32,SPOON,SUM,0,0,0,0,0,69,2,21.4660251141 +32,,SUM,0,0,0,0,4,90,7,44.3994410038 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,14,0,11.4471638203 +33,CUP,SUM,1,0,0,1,2,383,68,0 +33,SPOON,SUM,0,0,0,0,0,1,0,13.992305994 +33,,SUM,1,0,0,1,2,398,68,25.4394698143 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,0,31,0,12.0761210918 +34,CUP,SUM,1,0,0,1,0,335,67,0 +34,SPOON,SUM,0,0,0,0,0,3,0,14.9023602009 +34,,SUM,1,0,0,1,0,369,67,26.9784812927 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,0,59,6,17.1473839283 +35,CUP,SUM,0,0,0,0,0,8,5,10.2110350132 +35,SPOON,SUM,1,0,1,0,0,1582,0,0 +35,,SUM,1,0,1,0,0,1649,11,27.3584189415 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,0,7,0,11.2223720551 +36,CUP,SUM,0,0,0,0,0,16,5,10.3533701897 +36,SPOON,SUM,0,0,0,0,0,14,0,15.192481041 +36,,SUM,0,0,0,0,0,37,5,36.7682232857 +36,,,,,,,,,, +37,,,,,,,,,, +37,BOWL,SUM,0,0,0,0,0,191,0,21.8411409855 +37,CUP,SUM,1,0,0,1,0,326,56,0 +37,SPOON,SUM,0,0,0,0,0,51,0,17.1638760567 +37,,SUM,1,0,0,1,0,568,56,39.0050170422 +37,,,,,,,,,, +38,,,,,,,,,, +38,BOWL,SUM,0,0,0,0,0,8,0,11.3343770504 +38,CUP,SUM,0,0,0,0,0,12,0,9.9155871868 +38,SPOON,SUM,1,0,1,0,0,1603,0,0 +38,,SUM,1,0,1,0,0,1623,0,21.2499642372 +38,,,,,,,,,, +39,,,,,,,,,, +39,BOWL,SUM,0,0,0,0,0,13,2,12.088752985 +39,CUP,SUM,0,0,0,0,0,55,1,12.8559072018 +39,SPOON,SUM,0,0,0,0,0,65,0,18.3514490128 +39,,SUM,0,0,0,0,0,133,3,43.2961091995 +39,,,,,,,,,, +40,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,54,252,0,46.7954361439 +40,CUP,SUM,0,0,0,0,0,26,2,10.3554549217 +40,SPOON,SUM,0,0,0,0,0,49,0,15.8226029873 +40,,SUM,0,0,0,0,54,327,2,72.9734940529 +40,,,,,,,,,, +41,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,0,43,0,13.7518548965 +41,CUP,SUM,1,0,0,1,2,398,54,0 +41,SPOON,SUM,0,0,0,0,2,57,0,17.7895247936 +41,,SUM,1,0,0,1,4,498,54,31.5413796902 +41,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,0,60,6,16.1208097935 +42,CUP,SUM,0,0,0,0,0,35,2,10.1927230358 +42,SPOON,SUM,0,0,0,0,0,34,0,16.6059110165 +42,,SUM,0,0,0,0,0,129,8,42.9194438457 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,0,43,0,12.4133241177 +43,CUP,SUM,0,0,0,0,0,17,7,13.0294280052 +43,SPOON,SUM,0,0,0,0,0,1,0,14.4265139103 +43,,SUM,0,0,0,0,0,61,7,39.8692660332 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,58,27,0,38.2279279232 +44,CUP,SUM,0,0,0,0,0,23,0,10.2332129478 +44,SPOON,SUM,0,0,0,0,0,246,0,28.8228089809 +44,,SUM,0,0,0,0,58,296,0,77.283949852 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,2,100,8,20.5309090614 +45,CUP,SUM,1,0,0,1,8,448,70,0 +45,SPOON,SUM,1,0,1,0,0,1581,0,0 +45,,SUM,2,0,1,1,10,2129,78,20.5309090614 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,0,138,26,36.426035881 +46,CUP,SUM,0,0,0,0,0,19,2,10.2865390778 +46,SPOON,SUM,0,0,0,0,0,96,2,19.617305994 +46,,SUM,0,0,0,0,0,253,30,66.3298809528 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,0,0,0,0,0,28,2,12.1899468899 +47,CUP,SUM,0,0,0,0,0,7,3,10.2459568977 +47,SPOON,SUM,0,0,0,0,0,107,0,20.8484919071 +47,,SUM,0,0,0,0,0,142,5,43.2843956947 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,0,26,2,12.5048701763 +48,CUP,SUM,0,0,0,0,0,18,7,10.5652389526 +48,SPOON,SUM,0,0,0,0,4,46,0,18.5283939838 +48,,SUM,0,0,0,0,4,90,9,41.5985031128 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,0,46,4,14.65457201 +49,CUP,SUM,1,0,0,1,0,437,69,0 +49,SPOON,SUM,0,0,0,0,2,90,0,20.7705590725 +49,,SUM,1,0,0,1,2,573,73,35.4251310825 +49,,,,,,,,,, +50,,,,,,,,,, +50,BOWL,SUM,0,0,0,0,8,720,16,69.3736560345 +50,CUP,SUM,0,0,0,0,2,67,13,16.7400290966 +50,SPOON,SUM,0,0,0,0,0,21,0,15.4247019291 +50,,SUM,0,0,0,0,10,808,29,101.5383870602 +50,,,,,,,,,, +51,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,0,44,6,16.413613081 +51,CUP,SUM,0,0,0,0,0,32,1,10.7118878365 +51,SPOON,SUM,1,0,1,0,0,1584,0,0 +51,,SUM,1,0,1,0,0,1660,7,27.1255009174 +51,,,,,,,,,, +52,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,10,35,0,17.5176420212 +52,CUP,SUM,1,0,0,1,8,254,51,0 +52,SPOON,SUM,0,0,0,0,0,110,0,20.8509149551 +52,,SUM,1,0,0,1,18,399,51,38.3685569763 +52,,,,,,,,,, +53,,,,,,,,,, +53,BOWL,SUM,0,0,0,0,0,906,28,82.6933820248 +53,CUP,SUM,1,0,0,1,0,402,53,0 +53,SPOON,SUM,1,0,1,0,2,1606,0,0 +53,,SUM,2,0,1,1,2,2914,81,82.6933820248 +53,,,,,,,,,, +54,,,,,,,,,, +54,BOWL,SUM,0,0,0,0,0,43,0,14.3764760494 +54,CUP,SUM,0,0,0,0,0,11,2,10.7939491272 +54,SPOON,SUM,0,0,0,0,0,1,2,15.0481319427 +54,,SUM,0,0,0,0,0,55,4,40.2185571194 +54,,,,,,,,,, +55,,,,,,,,,, +55,BOWL,SUM,0,0,0,0,0,6,0,11.8259780407 +55,CUP,SUM,1,0,0,1,0,402,54,0 +55,SPOON,SUM,0,0,0,0,0,99,0,20.8324961662 +55,,SUM,1,0,0,1,0,507,54,32.6584742069 +55,,,,,,,,,, +56,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,0,129,8,23.319234848 +56,CUP,SUM,0,0,0,0,0,13,0,9.7532701492 +56,SPOON,SUM,0,0,0,0,6,47,4,22.3104479313 +56,,SUM,0,0,0,0,6,189,12,55.3829529285 +56,,,,,,,,,, +57,,,,,,,,,, +57,BOWL,SUM,0,0,0,0,2,27,0,13.0002658367 +57,CUP,SUM,0,0,0,0,0,24,6,12.432986021 +57,SPOON,SUM,0,0,0,0,0,313,1,34.6413300037 +57,,SUM,0,0,0,0,2,364,7,60.0745818615 +57,,,,,,,,,, +58,,,,,,,,,, +58,BOWL,SUM,0,0,0,0,2,36,0,13.0997068882 +58,CUP,SUM,0,0,0,0,2,19,2,11.2219359875 +58,SPOON,SUM,0,0,0,0,0,67,3,22.4742519856 +58,,SUM,0,0,0,0,4,122,5,46.7958948612 +58,,,,,,,,,, +59,,,,,,,,,, +59,BOWL,SUM,0,0,0,0,0,21,0,11.9752931595 +59,CUP,SUM,1,0,0,1,0,360,70,0 +59,SPOON,SUM,0,0,0,0,0,1,4,16.4726779461 +59,,SUM,1,0,0,1,0,382,74,28.4479711056 +59,,,,,,,,,, +60,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,0,27,2,12.6788079739 +60,CUP,SUM,1,0,0,1,0,346,54,0 +60,SPOON,SUM,0,0,0,0,0,0,0,14.7294499874 +60,,SUM,1,0,0,1,0,373,56,27.4082579613 +60,,,,,,,,,, +61,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,0,30,2,12.4015347958 +61,CUP,SUM,0,0,0,0,0,20,15,16.0155050755 +61,SPOON,SUM,0,0,0,0,2,70,0,19.0258381367 +61,,SUM,0,0,0,0,2,120,17,47.4428780079 +61,,,,,,,,,, +62,,,,,,,,,, +62,BOWL,SUM,0,0,0,0,2,57,4,16.4462740421 +62,CUP,SUM,1,0,0,1,0,415,53,0 +62,SPOON,SUM,1,0,1,0,0,1611,0,0 +62,,SUM,2,0,1,1,2,2083,57,16.4462740421 +62,,,,,,,,,, +63,, +63,BOWL,SUM,0,0,0,0,0,16,5,18.515136003494263 +63,CUP,SUM,0,0,0,0,0,4,2,10.450773000717163 +63,SPOON,SUM,0,0,0,0,4,22,0,16.881502866744995 +63,,SUM,0,0,0,0,4,42,7,45.84741187095642 +63,, +64,, +64,BOWL,SUM,0,0,0,0,0,30,0,12.798389911651611 +64,CUP,SUM,0,0,0,0,0,27,2,11.386091947555542 +64,SPOON,SUM,1,0,1,0,2,1581,0,0.0 +64,,SUM,1,0,1,0,2,1638,2,24.184481859207153 +64,, +65,, +65,BOWL,SUM,0,0,0,0,0,74,12,21.93322515487671 +65,CUP,SUM,0,0,0,0,0,10,2,10.114991903305054 +65,SPOON,SUM,0,0,0,0,0,86,2,18.90839910507202 +65,,SUM,0,0,0,0,0,170,16,50.956616163253784 +65,, +66,, +66,BOWL,SUM,0,0,0,0,10,24,3,18.4059419631958 +66,CUP,SUM,0,0,0,0,0,5,1,9.995272874832153 +66,SPOON,SUM,0,0,0,0,2,24,4,17.606877088546753 +66,,SUM,0,0,0,0,12,53,8,46.00809192657471 +66,, +67,, +67,BOWL,SUM,0,0,0,0,56,69,0,40.85194110870361 +67,CUP,SUM,0,0,0,0,0,30,1,10.335769176483154 +67,SPOON,SUM,0,0,0,0,18,1,0,23.27121591567993 +67,,SUM,0,0,0,0,74,100,1,74.4589262008667 +67,, +68,, +68,BOWL,SUM,0,0,0,0,0,37,6,15.582658052444458 +68,CUP,SUM,0,0,0,0,0,5,7,10.416778087615967 +68,SPOON,SUM,1,0,1,0,0,1591,0,0.0 +68,,SUM,1,0,1,0,0,1633,13,25.999436140060425 +68,, +69,, +69,BOWL,SUM,0,0,0,0,0,5,0,11.14756989479065 +69,CUP,SUM,0,0,0,0,0,27,0,10.105465173721313 +69,SPOON,SUM,0,0,0,0,2,173,0,25.092673778533936 +69,,SUM,0,0,0,0,2,205,0,46.3457088470459 +69,, +70,, +70,BOWL,SUM,0,0,0,0,4,16,8,19.62594199180603 +70,CUP,SUM,0,0,0,0,4,27,0,11.881678819656372 +70,SPOON,SUM,1,0,1,0,10,1593,0,0.0 +70,,SUM,1,0,1,0,18,1636,8,31.507620811462402 +70,, +71,, +71,BOWL,SUM,0,0,0,0,2,22,0,12.541749000549316 +71,CUP,SUM,0,0,0,0,0,23,0,10.155385971069336 +71,SPOON,SUM,0,0,0,0,0,5,6,19.18397617340088 +71,,SUM,0,0,0,0,2,50,6,41.88111114501953 +71,, +72,, +72,BOWL,SUM,1,0,1,0,0,1376,24,0.0 +72,CUP,SUM,0,0,0,0,0,25,10,11.089781999588013 +72,SPOON,SUM,0,0,0,0,4,8,2,16.384889125823975 +72,,SUM,1,0,1,0,4,1409,36,27.474671125411987 +72,, +73,, +73,BOWL,SUM,0,0,0,0,0,42,0,13.617830038070679 +73,CUP,SUM,0,0,0,0,0,16,2,9.929851055145264 +73,SPOON,SUM,0,0,0,0,0,128,1,22.56933903694153 +73,,SUM,0,0,0,0,0,186,3,46.11702013015747 +73,, +74,, +74,BOWL,SUM,0,0,0,0,0,140,0,18.21588397026062 +74,CUP,SUM,0,0,0,0,0,5,4,9.958508014678955 +74,SPOON,SUM,0,0,0,0,0,103,4,21.19081711769104 +74,,SUM,0,0,0,0,0,248,8,49.365209102630615 +74,, +75,, +75,BOWL,SUM,0,0,0,0,6,326,0,31.732427835464478 +75,CUP,SUM,1,0,0,1,2,373,51,0.0 +75,SPOON,SUM,1,0,1,0,0,1649,0,0.0 +75,,SUM,2,0,1,1,8,2348,51,31.732427835464478 +75,, +76,, +76,BOWL,SUM,0,0,0,0,0,143,2,19.742789030075073 +76,CUP,SUM,0,0,0,0,0,5,2,9.985291004180908 +76,SPOON,SUM,0,0,0,0,6,13,0,16.998174905776978 +76,,SUM,0,0,0,0,6,161,4,46.72625494003296 +76,, +77,, +77,BOWL,SUM,0,0,0,0,0,52,1,13.833261966705322 +77,CUP,SUM,0,0,0,0,0,37,2,11.969598054885864 +77,SPOON,SUM,0,0,0,0,0,7,0,14.625041007995605 +77,,SUM,0,0,0,0,0,96,3,40.42790102958679 +77,, +78,, +78,BOWL,SUM,0,0,0,0,0,8,0,11.336392879486084 +78,CUP,SUM,0,0,0,0,0,16,2,10.360757112503052 +78,SPOON,SUM,0,0,0,0,0,14,2,14.903745174407959 +78,,SUM,0,0,0,0,0,38,4,36.600895166397095 +78,, +79,, +79,BOWL,SUM,0,0,0,0,0,40,0,12.372803926467896 +79,CUP,SUM,0,0,0,0,2,8,2,10.582283020019531 +79,SPOON,SUM,0,0,0,0,0,194,0,26.734483003616333 +79,,SUM,0,0,0,0,2,242,2,49.68956995010376 +79,, +80,, +80,BOWL,SUM,0,0,0,0,0,2,0,11.263998985290527 +80,CUP,SUM,0,0,0,0,0,5,5,10.124406099319458 +80,SPOON,SUM,0,0,0,0,0,700,0,58.5040180683136 +80,,SUM,0,0,0,0,0,707,5,79.89242315292358 +80,, +81,, +81,BOWL,SUM,0,0,0,0,2,1,2,12.132714033126831 +81,CUP,SUM,0,0,0,0,0,33,12,13.030946969985962 +81,SPOON,SUM,0,0,0,0,0,62,0,17.334068059921265 +81,,SUM,0,0,0,0,2,96,14,42.49772906303406 +81,, +82,, +82,BOWL,SUM,0,0,0,0,0,79,10,19.653544902801514 +82,CUP,SUM,0,0,0,0,0,7,7,9.898811101913452 +82,SPOON,SUM,0,0,0,0,0,356,0,36.16022992134094 +82,,SUM,0,0,0,0,0,442,17,65.71258592605591 +82,, +83,, +83,BOWL,SUM,0,0,0,0,0,34,1,13.956339120864868 +83,CUP,SUM,1,0,0,1,0,254,62,0.0 +83,SPOON,SUM,0,0,0,0,2,118,1,23.199337005615234 +83,,SUM,1,0,0,1,2,406,64,37.1556761264801 +83,, +84,, +84,BOWL,SUM,0,0,0,0,0,8,0,11.401490926742554 +84,CUP,SUM,0,0,0,0,0,21,0,10.091331958770752 +84,SPOON,SUM,0,0,0,0,8,4,3,19.96319603919983 +84,,SUM,0,0,0,0,8,33,3,41.456018924713135 +84,, +85,, +85,BOWL,SUM,0,0,0,0,0,37,0,12.048748016357422 +85,CUP,SUM,1,0,0,1,2,406,55,0.0 +85,SPOON,SUM,1,0,1,0,10,1665,0,0.0 +85,,SUM,2,0,1,1,12,2108,55,12.048748016357422 +85,, +86,, +86,BOWL,SUM,0,0,0,0,0,92,0,15.508181095123291 +86,CUP,SUM,1,0,0,1,2,394,72,0.0 +86,SPOON,SUM,0,0,0,0,0,10,0,15.016891956329346 +86,,SUM,1,0,0,1,2,496,72,30.525073051452637 +86,, +87,, +87,BOWL,SUM,0,0,0,0,6,344,0,34.57426881790161 +87,CUP,SUM,1,0,0,1,14,392,63,0.0 +87,SPOON,SUM,0,0,0,0,0,3,2,14.797830820083618 +87,,SUM,1,0,0,1,20,739,65,49.37209963798523 +87,, +88,, +88,BOWL,SUM,0,0,0,0,0,21,2,15.118170022964478 +88,CUP,SUM,0,0,0,0,0,1,4,9.67613410949707 +88,SPOON,SUM,0,0,0,0,0,16,0,15.169486999511719 +88,,SUM,0,0,0,0,0,38,6,39.96379113197327 +88,, +89,, +89,BOWL,SUM,0,0,0,0,0,401,8,37.96573519706726 +89,CUP,SUM,1,0,0,1,0,466,67,0.0 +89,SPOON,SUM,0,0,0,0,18,118,0,29.936551094055176 +89,,SUM,1,0,0,1,18,985,75,67.90228629112244 +89,, +90,, +90,BOWL,SUM,0,0,0,0,0,16,0,11.796853065490723 +90,CUP,SUM,1,0,0,1,0,352,53,0.0 +90,SPOON,SUM,0,0,0,0,0,10,0,15.028589010238647 +90,,SUM,1,0,0,1,0,378,53,26.82544207572937 +90,, +91,, +91,BOWL,SUM,0,0,0,0,0,14,0,12.003217935562134 +91,CUP,SUM,1,0,0,1,0,390,63,0.0 +91,SPOON,SUM,0,0,0,0,16,19,1,24.96173095703125 +91,,SUM,1,0,0,1,16,423,64,36.964948892593384 +91,, +92,, +92,BOWL,SUM,0,0,0,0,0,101,0,17.623608827590942 +92,CUP,SUM,1,0,0,1,16,449,58,0.0 +92,SPOON,SUM,0,0,0,0,0,3,0,15.180214881896973 +92,,SUM,1,0,0,1,16,553,58,32.803823709487915 +92,, +93,, +93,BOWL,SUM,0,0,0,0,0,42,1,13.841717958450317 +93,CUP,SUM,0,0,0,0,10,30,2,15.347672939300537 +93,SPOON,SUM,0,0,0,0,0,60,0,17.247388124465942 +93,,SUM,0,0,0,0,10,132,3,46.4367790222168 +93,, +94,, +94,BOWL,SUM,0,0,0,0,0,64,0,14.51310396194458 +94,CUP,SUM,0,0,0,0,0,43,7,14.522704839706421 +94,SPOON,SUM,0,0,0,0,0,18,0,14.726864099502563 +94,,SUM,0,0,0,0,0,125,7,43.762672901153564 +94,, +95,, +95,BOWL,SUM,0,0,0,0,4,11,0,12.885769128799438 +95,CUP,SUM,0,0,0,0,0,10,5,10.222028970718384 +95,SPOON,SUM,0,0,0,0,0,69,2,21.735219955444336 +95,,SUM,0,0,0,0,4,90,7,44.84301805496216 +95,, +96,, +96,BOWL,SUM,0,0,0,0,0,14,0,11.482326984405518 +96,CUP,SUM,1,0,0,1,2,383,68,0.0 +96,SPOON,SUM,0,0,0,0,0,1,0,14.625627994537354 +96,,SUM,1,0,0,1,2,398,68,26.10795497894287 +96,, +97,, +97,BOWL,SUM,0,0,0,0,0,31,0,12.182454109191895 +97,CUP,SUM,1,0,0,1,0,335,67,0.0 +97,SPOON,SUM,0,0,0,0,0,3,0,15.229948043823242 +97,,SUM,1,0,0,1,0,369,67,27.412402153015137 +97,, +98,, +98,BOWL,SUM,0,0,0,0,0,59,6,17.61213707923889 +98,CUP,SUM,0,0,0,0,0,8,5,10.391617059707642 +98,SPOON,SUM,1,0,1,0,0,1582,0,0.0 +98,,SUM,1,0,1,0,0,1649,11,28.003754138946533 +98,, +99,, +99,BOWL,SUM,0,0,0,0,0,7,0,11.713080883026123 +99,CUP,SUM,0,0,0,0,0,16,5,10.607483148574829 +99,SPOON,SUM,0,0,0,0,0,14,0,15.038994073867798 +99,,SUM,0,0,0,0,0,37,5,37.35955810546875 +99,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_16.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_16.csv new file mode 100644 index 0000000000..21e0232680 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_16.csv @@ -0,0 +1,1203 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,0,4,4,24.54337191581726 +0,CUP,SUM,0,0,0,0,0,15,4,12.625468015670776 +0,SPOON,SUM,0,0,0,0,0,60,0,18.57148504257202 +0,,SUM,0,0,0,0,0,79,8,55.74032497406006 +0,, +1,, +1,BOWL,SUM,0,0,0,0,0,30,0,13.96725606918335 +1,CUP,SUM,0,0,0,0,0,43,10,20.207912921905518 +1,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +1,,SUM,1,1,0,0,0,1592,10,34.17516899108887 +1,, +2,, +2,BOWL,SUM,0,0,0,0,48,54,0,33.73983907699585 +2,CUP,SUM,0,0,0,0,0,19,1,9.874038934707642 +2,SPOON,SUM,0,0,0,0,0,1,2,17.35610294342041 +2,,SUM,0,0,0,0,48,74,3,60.9699809551239 +2,, +3,, +3,BOWL,SUM,0,0,0,0,10,35,4,17.660601139068604 +3,CUP,SUM,0,0,0,0,0,5,9,9.888159990310669 +3,SPOON,SUM,0,0,0,0,2,36,10,22.196382999420166 +3,,SUM,0,0,0,0,12,76,23,49.74514412879944 +3,, +4,, +4,BOWL,SUM,0,0,0,0,0,10,0,11.380998849868774 +4,CUP,SUM,0,0,0,0,2,29,3,11.058233976364136 +4,SPOON,SUM,1,0,1,0,2,1581,0,0.0 +4,,SUM,1,0,1,0,4,1620,3,22.43923282623291 +4,, +5,, +5,BOWL,SUM,0,0,0,0,10,70,6,21.041211128234863 +5,CUP,SUM,0,0,0,0,0,6,2,9.751543998718262 +5,SPOON,SUM,0,0,0,0,4,3,2,15.662068843841553 +5,,SUM,0,0,0,0,14,79,10,46.45482397079468 +5,, +6,, +6,BOWL,SUM,0,0,0,0,0,16,4,13.339970111846924 +6,CUP,SUM,0,0,0,0,0,12,1,9.848779916763306 +6,SPOON,SUM,0,0,0,0,0,13,0,14.880536079406738 +6,,SUM,0,0,0,0,0,41,5,38.06928610801697 +6,, +7,, +7,BOWL,SUM,0,0,0,0,0,20,0,11.450657844543457 +7,CUP,SUM,1,0,0,1,0,353,62,0.0 +7,SPOON,SUM,1,0,1,0,2,1583,0,0.0 +7,,SUM,2,0,1,1,2,1956,62,11.450657844543457 +7,, +8,, +8,BOWL,SUM,0,0,0,0,0,27,0,11.89420199394226 +8,CUP,SUM,0,0,0,0,0,12,8,10.501392126083374 +8,SPOON,SUM,0,0,0,0,0,527,1,47.207112073898315 +8,,SUM,0,0,0,0,0,566,9,69.60270619392395 +8,, +9,, +9,BOWL,SUM,0,0,0,0,0,21,0,11.392682075500488 +9,CUP,SUM,0,0,0,0,0,244,49,80.78395009040833 +9,SPOON,SUM,0,0,0,0,0,63,4,21.746443033218384 +9,,SUM,0,0,0,0,0,328,53,113.9230751991272 +9,, +10,, +10,BOWL,SUM,0,0,0,0,6,22,1,14.771162033081055 +10,CUP,SUM,0,0,0,0,0,8,5,9.957229137420654 +10,SPOON,SUM,0,0,0,0,0,512,1,47.9955050945282 +10,,SUM,0,0,0,0,6,542,7,72.72389626502991 +10,, +11,, +11,BOWL,SUM,0,0,0,0,0,6,0,11.214770078659058 +11,CUP,SUM,1,0,0,1,0,344,57,0.0 +11,SPOON,SUM,0,0,0,0,62,500,14,77.97215604782104 +11,,SUM,1,0,0,1,62,850,71,89.1869261264801 +11,, +12,, +12,BOWL,SUM,0,0,0,0,4,98,1,17.431682109832764 +12,CUP,SUM,1,0,0,1,4,468,52,0.0 +12,SPOON,SUM,0,0,0,0,0,197,0,26.32459592819214 +12,,SUM,1,0,0,1,8,763,53,43.7562780380249 +12,, +13,, +13,BOWL,SUM,0,0,0,0,4,22,0,12.80170202255249 +13,CUP,SUM,0,0,0,0,0,10,3,11.369863986968994 +13,SPOON,SUM,0,0,0,0,0,167,7,28.27169394493103 +13,,SUM,0,0,0,0,4,199,10,52.443259954452515 +13,, +14,, +14,BOWL,SUM,0,0,0,0,54,32,0,35.70345401763916 +14,CUP,SUM,0,0,0,0,0,76,5,16.105321168899536 +14,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +14,,SUM,1,0,1,0,54,1689,5,51.808775186538696 +14,, +15,, +15,BOWL,SUM,0,0,0,0,2,67,0,14.321353912353516 +15,CUP,SUM,0,0,0,0,0,9,3,9.908807039260864 +15,SPOON,SUM,0,0,0,0,0,95,1,21.776051998138428 +15,,SUM,0,0,0,0,2,171,4,46.00621294975281 +15,, +16,, +16,BOWL,SUM,0,0,0,0,6,30,1,15.07345700263977 +16,CUP,SUM,0,0,0,0,0,14,2,9.8352952003479 +16,SPOON,SUM,0,0,0,0,0,6,0,14.56767201423645 +16,,SUM,0,0,0,0,6,50,3,39.47642421722412 +16,, +17,, +17,BOWL,SUM,0,0,0,0,0,12,2,11.684505939483643 +17,CUP,SUM,0,0,0,0,0,20,11,11.940001964569092 +17,SPOON,SUM,0,0,0,0,0,247,1,29.945831060409546 +17,,SUM,0,0,0,0,0,279,14,53.57033896446228 +17,, +18,, +18,BOWL,SUM,0,0,0,0,0,6,0,11.404459953308105 +18,CUP,SUM,1,0,0,1,2,413,51,0.0 +18,SPOON,SUM,0,0,0,0,0,227,2,28.252783060073853 +18,,SUM,1,0,0,1,2,646,53,39.65724301338196 +18,, +19,, +19,BOWL,SUM,0,0,0,0,50,212,12,50.23206901550293 +19,CUP,SUM,0,0,0,0,0,8,0,9.501404047012329 +19,SPOON,SUM,0,0,0,0,0,3,0,14.583836078643799 +19,,SUM,0,0,0,0,50,223,12,74.31730914115906 +19,, +20,, +20,BOWL,SUM,0,0,0,0,0,45,6,16.078645944595337 +20,CUP,SUM,1,0,0,1,0,418,51,0.0 +20,SPOON,SUM,0,0,0,0,0,341,0,33.92582297325134 +20,,SUM,1,0,0,1,0,804,57,50.00446891784668 +20,, +21,, +21,BOWL,SUM,1,0,1,0,2,984,72,0.0 +21,CUP,SUM,0,0,0,0,0,25,4,10.360392093658447 +21,SPOON,SUM,0,0,0,0,0,21,5,18.704766035079956 +21,,SUM,1,0,1,0,2,1030,81,29.065158128738403 +21,, +22,, +22,BOWL,SUM,0,0,0,0,6,57,0,15.636044979095459 +22,CUP,SUM,1,0,0,1,0,426,57,0.0 +22,SPOON,SUM,1,0,1,0,0,1613,0,0.0 +22,,SUM,2,0,1,1,6,2096,57,15.636044979095459 +22,, +23,, +23,BOWL,SUM,0,0,0,0,2,48,4,14.895973920822144 +23,CUP,SUM,0,0,0,0,0,9,11,10.210361003875732 +23,SPOON,SUM,1,0,1,0,0,1582,0,0.0 +23,,SUM,1,0,1,0,2,1639,15,25.106334924697876 +23,, +24,, +24,BOWL,SUM,0,0,0,0,6,66,0,15.687247037887573 +24,CUP,SUM,0,0,0,0,0,14,2,9.983771085739136 +24,SPOON,SUM,0,0,0,0,0,115,2,24.295343160629272 +24,,SUM,0,0,0,0,6,195,4,49.96636128425598 +24,, +25,, +25,BOWL,SUM,0,0,0,0,0,99,2,17.799371004104614 +25,CUP,SUM,0,0,0,0,16,17,2,17.524392127990723 +25,SPOON,SUM,0,0,0,0,0,20,2,15.402813911437988 +25,,SUM,0,0,0,0,16,136,6,50.726577043533325 +25,, +26,, +26,BOWL,SUM,0,0,0,0,88,204,0,59.09028887748718 +26,CUP,SUM,1,0,0,1,2,360,58,0.0 +26,SPOON,SUM,0,0,0,0,0,30,0,16.496177911758423 +26,,SUM,1,0,0,1,90,594,58,75.5864667892456 +26,, +27,, +27,BOWL,SUM,0,0,0,0,0,15,0,11.38733196258545 +27,CUP,SUM,0,0,0,0,8,32,3,14.27126693725586 +27,SPOON,SUM,0,0,0,0,0,57,4,19.439942836761475 +27,,SUM,0,0,0,0,8,104,7,45.09854173660278 +27,, +28,, +28,BOWL,SUM,0,0,0,0,0,59,0,14.207791090011597 +28,CUP,SUM,0,0,0,0,2,11,4,10.761696100234985 +28,SPOON,SUM,0,0,0,0,0,100,10,23.990317821502686 +28,,SUM,0,0,0,0,2,170,14,48.95980501174927 +28,, +29,, +29,BOWL,SUM,0,0,0,0,0,118,11,23.737044095993042 +29,CUP,SUM,1,0,0,1,0,372,65,0.0 +29,SPOON,SUM,1,0,1,0,6,1582,0,0.0 +29,,SUM,2,0,1,1,6,2072,76,23.737044095993042 +29,, +30,, +30,BOWL,SUM,0,0,0,0,0,35,4,14.608381032943726 +30,CUP,SUM,1,0,0,1,0,406,58,0.0 +30,SPOON,SUM,0,0,0,0,0,11,2,15.194266080856323 +30,,SUM,1,0,0,1,0,452,64,29.80264711380005 +30,, +31,, +31,BOWL,SUM,0,0,0,0,0,147,3,20.33469295501709 +31,CUP,SUM,0,0,0,0,2,16,3,11.032334089279175 +31,SPOON,SUM,0,0,0,0,0,20,0,15.184061050415039 +31,,SUM,0,0,0,0,2,183,6,46.551088094711304 +31,, +32,, +32,BOWL,SUM,0,0,0,0,0,12,4,14.021549940109253 +32,CUP,SUM,0,0,0,0,0,96,8,23.679933071136475 +32,SPOON,SUM,0,0,0,0,2,130,1,25.509828090667725 +32,,SUM,0,0,0,0,2,238,13,63.21131110191345 +32,, +33,, +33,BOWL,SUM,0,0,0,0,2,14,0,12.35636305809021 +33,CUP,SUM,0,0,0,0,0,4,5,9.828161001205444 +33,SPOON,SUM,0,0,0,0,0,39,0,17.19899010658264 +33,,SUM,0,0,0,0,2,57,5,39.383514165878296 +33,, +34,, +34,BOWL,SUM,0,0,0,0,0,10,1,11.82559084892273 +34,CUP,SUM,1,0,1,0,4,282,104,0.0 +34,SPOON,SUM,0,0,0,0,0,35,0,17.37143898010254 +34,,SUM,1,0,1,0,4,327,105,29.19702982902527 +34,, +35,, +35,BOWL,SUM,0,0,0,0,0,11,0,11.765188932418823 +35,CUP,SUM,0,0,0,0,4,24,0,11.712680101394653 +35,SPOON,SUM,0,0,0,0,2,348,0,37.17798590660095 +35,,SUM,0,0,0,0,6,383,0,60.65585494041443 +35,, +36,, +36,BOWL,SUM,0,0,0,0,2,8,0,12.135576963424683 +36,CUP,SUM,0,0,0,0,0,52,14,16.575341939926147 +36,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +36,,SUM,1,0,1,0,2,1641,14,28.71091890335083 +36,, +37,, +37,BOWL,SUM,0,0,0,0,0,15,4,13.559428930282593 +37,CUP,SUM,0,0,0,0,0,117,20,38.380462884902954 +37,SPOON,SUM,0,0,0,0,0,76,0,19.234203100204468 +37,,SUM,0,0,0,0,0,208,24,71.17409491539001 +37,, +38,, +38,BOWL,SUM,0,0,0,0,0,51,6,15.883508205413818 +38,CUP,SUM,0,0,0,0,0,228,37,62.826393127441406 +38,SPOON,SUM,0,0,0,0,0,17,1,16.9480140209198 +38,,SUM,0,0,0,0,0,296,44,95.65791535377502 +38,, +39,, +39,BOWL,SUM,0,0,0,0,2,36,0,14.12090015411377 +39,CUP,SUM,0,0,0,0,2,28,5,14.579264879226685 +39,SPOON,SUM,0,0,0,0,0,16,1,16.558656930923462 +39,,SUM,0,0,0,0,4,80,6,45.258821964263916 +39,, +40,, +40,BOWL,SUM,0,0,0,0,0,24,2,12.6232328414917 +40,CUP,SUM,0,0,0,0,6,10,4,12.134813070297241 +40,SPOON,SUM,0,0,0,0,0,0,0,14.811018943786621 +40,,SUM,0,0,0,0,6,34,6,39.56906485557556 +40,, +41,, +41,BOWL,SUM,0,0,0,0,0,120,0,18.453480005264282 +41,CUP,SUM,0,0,0,0,0,1,3,9.992319822311401 +41,SPOON,SUM,0,0,0,0,0,465,1,44.44965410232544 +41,,SUM,0,0,0,0,0,586,4,72.89545392990112 +41,, +42,, +42,BOWL,SUM,0,0,0,0,0,41,6,15.964169025421143 +42,CUP,SUM,0,0,0,0,0,20,6,10.743902921676636 +42,SPOON,SUM,0,0,0,0,24,131,26,60.256712913513184 +42,,SUM,0,0,0,0,24,192,38,86.96478486061096 +42,, +43,, +43,BOWL,SUM,0,0,0,0,0,57,6,16.66094207763672 +43,CUP,SUM,1,0,0,1,0,492,62,0.0 +43,SPOON,SUM,0,0,0,0,0,1,0,15.015262842178345 +43,,SUM,1,0,0,1,0,550,68,31.676204919815063 +43,, +44,, +44,BOWL,SUM,0,0,0,0,6,282,0,31.783413887023926 +44,CUP,SUM,1,0,1,0,2,203,97,0.0 +44,SPOON,SUM,0,0,0,0,0,1,5,18.317641973495483 +44,,SUM,1,0,1,0,8,486,102,50.10105586051941 +44,, +45,, +45,BOWL,SUM,0,0,0,0,50,20,0,34.772400856018066 +45,CUP,SUM,0,0,0,0,0,12,0,9.942831039428711 +45,SPOON,SUM,0,0,0,0,0,265,0,31.50293207168579 +45,,SUM,0,0,0,0,50,297,0,76.21816396713257 +45,, +46,, +46,BOWL,SUM,0,0,0,0,2,44,8,19.126338005065918 +46,CUP,SUM,0,0,0,0,0,17,4,10.341444969177246 +46,SPOON,SUM,0,0,0,0,0,437,1,42.949941873550415 +46,,SUM,0,0,0,0,2,498,13,72.41772484779358 +46,, +47,, +47,BOWL,SUM,0,0,0,0,0,84,24,32.1313419342041 +47,CUP,SUM,0,0,0,0,2,29,5,11.779183149337769 +47,SPOON,SUM,0,0,0,0,0,60,0,17.989014863967896 +47,,SUM,0,0,0,0,2,173,29,61.899539947509766 +47,, +48,, +48,BOWL,SUM,0,0,0,0,6,25,0,13.751540899276733 +48,CUP,SUM,1,0,1,0,0,339,111,0.0 +48,SPOON,SUM,0,0,0,0,0,81,1,20.910672903060913 +48,,SUM,1,0,1,0,6,445,112,34.66221380233765 +48,, +49,, +49,BOWL,SUM,0,0,0,0,86,279,10,67.86430287361145 +49,CUP,SUM,0,0,0,0,0,20,2,10.118289947509766 +49,SPOON,SUM,0,0,0,0,2,45,3,19.50599503517151 +49,,SUM,0,0,0,0,88,344,15,97.48858785629272 +49,, +50,, +50,BOWL,SUM,1,0,1,0,0,1467,16,0.0 +50,CUP,SUM,0,0,0,0,0,140,17,35.955869913101196 +50,SPOON,SUM,0,0,0,0,0,7,0,14.9342679977417 +50,,SUM,1,0,1,0,0,1614,33,50.890137910842896 +50,, +51,, +51,BOWL,SUM,0,0,0,0,0,137,0,19.795580863952637 +51,CUP,SUM,0,0,0,0,0,110,18,32.82719707489014 +51,SPOON,SUM,0,0,0,0,0,109,0,21.255643844604492 +51,,SUM,0,0,0,0,0,356,18,73.87842178344727 +51,, +52,, +52,BOWL,SUM,0,0,0,0,0,60,18,26.091225147247314 +52,CUP,SUM,0,0,0,0,0,16,2,10.397865056991577 +52,SPOON,SUM,0,0,0,0,2,6,9,22.580577850341797 +52,,SUM,0,0,0,0,2,82,29,59.06966805458069 +52,, +53,, +53,BOWL,SUM,0,0,0,0,2,33,2,14.73135495185852 +53,CUP,SUM,0,0,0,0,0,13,6,10.461810111999512 +53,SPOON,SUM,0,0,0,0,0,208,0,25.72783398628235 +53,,SUM,0,0,0,0,2,254,8,50.92099905014038 +53,, +54,, +54,BOWL,SUM,0,0,0,0,2,49,0,13.226491928100586 +54,CUP,SUM,0,0,0,0,2,39,5,11.413694858551025 +54,SPOON,SUM,0,0,0,0,0,164,0,25.103813886642456 +54,,SUM,0,0,0,0,4,252,5,49.74400067329407 +54,, +55,, +55,BOWL,SUM,0,0,0,0,6,58,3,17.635224103927612 +55,CUP,SUM,0,0,0,0,26,30,13,27.146502017974854 +55,SPOON,SUM,0,0,0,0,0,991,0,77.06089401245117 +55,,SUM,0,0,0,0,32,1079,16,121.84262013435364 +55,, +56,, +56,BOWL,SUM,0,0,0,0,0,14,6,15.494278907775879 +56,CUP,SUM,1,0,0,1,2,352,53,0.0 +56,SPOON,SUM,0,0,0,0,0,466,0,43.05075192451477 +56,,SUM,1,0,0,1,2,832,59,58.54503083229065 +56,, +57,, +57,BOWL,SUM,0,0,0,0,0,35,0,12.272048950195313 +57,CUP,SUM,0,0,0,0,0,31,11,12.743291854858398 +57,SPOON,SUM,0,0,0,0,0,391,0,39.147494077682495 +57,,SUM,0,0,0,0,0,457,11,64.1628348827362 +57,, +58,, +58,BOWL,SUM,1,1,0,0,392,137,0,0.0 +58,CUP,SUM,0,0,0,0,0,53,9,20.106317043304443 +58,SPOON,SUM,0,0,0,0,0,137,0,22.91206407546997 +58,,SUM,1,1,0,0,392,327,9,43.018381118774414 +58,, +59,, +59,BOWL,SUM,0,0,0,0,0,14,2,11.937980890274048 +59,CUP,SUM,0,0,0,0,0,12,0,9.784703016281128 +59,SPOON,SUM,0,0,0,0,0,5,1,16.7582368850708 +59,,SUM,0,0,0,0,0,31,3,38.48092079162598 +59,, +60,, +60,BOWL,SUM,0,0,0,0,0,78,6,18.258713960647583 +60,CUP,SUM,0,0,0,0,8,12,9,14.601055145263672 +60,SPOON,SUM,0,0,0,0,6,126,1,24.597357034683228 +60,,SUM,0,0,0,0,14,216,16,57.45712614059448 +60,, +61,, +61,BOWL,SUM,0,0,0,0,0,185,0,21.852806091308594 +61,CUP,SUM,1,0,0,1,0,368,57,0.0 +61,SPOON,SUM,0,0,0,0,0,110,1,23.312978982925415 +61,,SUM,1,0,0,1,0,663,58,45.16578507423401 +61,, +62,, +62,BOWL,SUM,0,0,0,0,0,19,0,12.127028942108154 +62,CUP,SUM,1,0,0,1,0,390,54,0.0 +62,SPOON,SUM,0,0,0,0,0,24,2,16.02785086631775 +62,,SUM,1,0,0,1,0,433,56,28.154879808425903 +62,, +63,, +63,BOWL,SUM,0,0,0,0,2,47,0,14.637321949005127 +63,CUP,SUM,1,0,0,1,0,296,57,0.0 +63,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +63,,SUM,2,0,1,1,2,1924,57,14.637321949005127 +63,, +64,, +64,BOWL,SUM,0,0,0,0,2,6,0,12.800286054611206 +64,CUP,SUM,1,0,0,1,0,463,53,0.0 +64,SPOON,SUM,0,0,0,0,4,31,0,18.547080039978027 +64,,SUM,1,0,0,1,6,500,53,31.347366094589233 +64,, +65,, +65,BOWL,SUM,0,0,0,0,0,200,0,24.5766179561615 +65,CUP,SUM,0,0,0,0,0,3,4,10.88982105255127 +65,SPOON,SUM,0,0,0,0,0,106,0,21.556545972824097 +65,,SUM,0,0,0,0,0,309,4,57.022984981536865 +65,, +66,, +66,BOWL,SUM,0,0,0,0,58,75,0,40.151126861572266 +66,CUP,SUM,1,0,0,1,0,270,51,0.0 +66,SPOON,SUM,0,0,0,0,4,60,3,20.83180809020996 +66,,SUM,1,0,0,1,62,405,54,60.98293495178223 +66,, +67,, +67,BOWL,SUM,0,0,0,0,10,27,0,16.79460906982422 +67,CUP,SUM,0,0,0,0,0,10,4,10.494379043579102 +67,SPOON,SUM,0,0,0,0,4,77,1,22.764429092407227 +67,,SUM,0,0,0,0,14,114,5,50.05341720581055 +67,, +68,, +68,BOWL,SUM,0,0,0,0,0,46,0,13.978224039077759 +68,CUP,SUM,0,0,0,0,2,5,4,10.924764156341553 +68,SPOON,SUM,0,0,0,0,0,299,0,33.01852083206177 +68,,SUM,0,0,0,0,2,350,4,57.92150902748108 +68,, +69,, +69,BOWL,SUM,0,0,0,0,0,7,1,11.46869707107544 +69,CUP,SUM,0,0,0,0,0,70,12,23.998139142990112 +69,SPOON,SUM,1,0,1,0,32,1414,0,0.0 +69,,SUM,1,0,1,0,32,1491,13,35.46683621406555 +69,, +70,, +70,BOWL,SUM,0,0,0,0,2,18,2,12.905210971832275 +70,CUP,SUM,0,0,0,0,0,26,4,10.71226978302002 +70,SPOON,SUM,0,0,0,0,0,104,0,21.566813945770264 +70,,SUM,0,0,0,0,2,148,6,45.18429470062256 +70,, +71,, +71,BOWL,SUM,0,0,0,0,0,16,0,12.35312294960022 +71,CUP,SUM,0,0,0,0,2,27,4,11.445909023284912 +71,SPOON,SUM,1,0,1,0,0,1590,0,0.0 +71,,SUM,1,0,1,0,2,1633,4,23.799031972885132 +71,, +72,, +72,BOWL,SUM,0,0,0,0,2,54,4,15.27128791809082 +72,CUP,SUM,0,0,0,0,0,21,7,10.802321910858154 +72,SPOON,SUM,0,0,0,0,72,220,0,59.083632946014404 +72,,SUM,0,0,0,0,74,295,11,85.15724277496338 +72,, +73,, +73,BOWL,SUM,0,0,0,0,2,16,4,14.747879028320313 +73,CUP,SUM,1,0,0,1,0,319,59,0.0 +73,SPOON,SUM,0,0,0,0,2,47,21,33.954288959503174 +73,,SUM,1,0,0,1,4,382,84,48.702167987823486 +73,, +74,, +74,BOWL,SUM,0,0,0,0,0,27,0,12.748864889144897 +74,CUP,SUM,0,0,0,0,2,33,1,11.224499940872192 +74,SPOON,SUM,0,0,0,0,0,86,4,22.61018991470337 +74,,SUM,0,0,0,0,2,146,5,46.58355474472046 +74,, +75,, +75,BOWL,SUM,0,0,0,0,2,4,0,12.334107160568237 +75,CUP,SUM,0,0,0,0,0,8,4,10.084824085235596 +75,SPOON,SUM,0,0,0,0,0,262,1,31.159571886062622 +75,,SUM,0,0,0,0,2,274,5,53.578503131866455 +75,, +76,, +76,BOWL,SUM,0,0,0,0,0,17,0,12.312546014785767 +76,CUP,SUM,0,0,0,0,0,3,0,9.937520980834961 +76,SPOON,SUM,0,0,0,0,0,55,3,19.638954162597656 +76,,SUM,0,0,0,0,0,75,3,41.889021158218384 +76,, +77,, +77,BOWL,SUM,0,0,0,0,2,28,1,13.238089084625244 +77,CUP,SUM,0,0,0,0,2,22,3,12.869043111801147 +77,SPOON,SUM,0,0,0,0,0,4,0,15.461163997650146 +77,,SUM,0,0,0,0,4,54,4,41.56829619407654 +77,, +78,, +78,BOWL,SUM,0,0,0,0,0,21,0,13.116600036621094 +78,CUP,SUM,1,0,1,0,0,250,108,0.0 +78,SPOON,SUM,0,0,0,0,10,56,0,22.351843118667603 +78,,SUM,1,0,1,0,10,327,108,35.468443155288696 +78,, +79,, +79,BOWL,SUM,0,0,0,0,0,15,0,12.107473850250244 +79,CUP,SUM,0,0,0,0,0,45,4,12.223834991455078 +79,SPOON,SUM,0,0,0,0,0,305,0,34.24300503730774 +79,,SUM,0,0,0,0,0,365,4,58.57431387901306 +79,, +80,, +80,BOWL,SUM,0,0,0,0,0,18,1,13.605987071990967 +80,CUP,SUM,0,0,0,0,0,4,4,10.088713884353638 +80,SPOON,SUM,0,0,0,0,0,222,2,28.98333191871643 +80,,SUM,0,0,0,0,0,244,7,52.678032875061035 +80,, +81,, +81,BOWL,SUM,0,0,0,0,24,23,0,23.16570806503296 +81,CUP,SUM,0,0,0,0,30,24,0,23.698009967803955 +81,SPOON,SUM,0,0,0,0,2,154,0,25.143399000167847 +81,,SUM,0,0,0,0,56,201,0,72.00711703300476 +81,, +82,, +82,BOWL,SUM,0,0,0,0,0,15,0,12.569922924041748 +82,CUP,SUM,0,0,0,0,0,22,2,10.421070098876953 +82,SPOON,SUM,0,0,0,0,0,209,3,32.37839102745056 +82,,SUM,0,0,0,0,0,246,5,55.36938405036926 +82,, +83,, +83,BOWL,SUM,1,0,1,0,0,1418,22,0.0 +83,CUP,SUM,0,0,0,0,0,27,3,11.004945993423462 +83,SPOON,SUM,0,0,0,0,0,198,0,27.865275144577026 +83,,SUM,1,0,1,0,0,1643,25,38.87022113800049 +83,, +84,, +84,BOWL,SUM,0,0,0,0,0,207,6,26.532320976257324 +84,CUP,SUM,0,0,0,0,4,10,5,11.707515954971313 +84,SPOON,SUM,0,0,0,0,6,115,0,22.723594903945923 +84,,SUM,0,0,0,0,10,332,11,60.96343183517456 +84,, +85,, +85,BOWL,SUM,0,0,0,0,0,37,0,14.286581993103027 +85,CUP,SUM,0,0,0,0,0,20,2,10.734475135803223 +85,SPOON,SUM,0,0,0,0,0,549,1,50.56063485145569 +85,,SUM,0,0,0,0,0,606,3,75.58169198036194 +85,, +86,, +86,BOWL,SUM,0,0,0,0,2,5,2,12.591588973999023 +86,CUP,SUM,0,0,0,0,2,7,1,10.527979850769043 +86,SPOON,SUM,0,0,0,0,0,21,2,15.743345975875854 +86,,SUM,0,0,0,0,4,33,5,38.86291480064392 +86,, +87,, +87,BOWL,SUM,0,0,0,0,0,55,0,14.34817910194397 +87,CUP,SUM,0,0,0,0,0,21,0,10.1478271484375 +87,SPOON,SUM,1,0,1,0,0,1586,0,0.0 +87,,SUM,1,0,1,0,0,1662,0,24.49600625038147 +87,, +88,, +88,BOWL,SUM,0,0,0,0,0,27,1,12.749766111373901 +88,CUP,SUM,0,0,0,0,0,16,2,10.665229082107544 +88,SPOON,SUM,0,0,0,0,0,443,0,41.58886408805847 +88,,SUM,0,0,0,0,0,486,3,65.00385928153992 +88,, +89,, +89,BOWL,SUM,0,0,0,0,0,50,2,14.222208023071289 +89,CUP,SUM,0,0,0,0,0,9,2,10.270845890045166 +89,SPOON,SUM,0,0,0,0,6,110,1,23.94803285598755 +89,,SUM,0,0,0,0,6,169,5,48.441086769104004 +89,, +90,, +90,BOWL,SUM,0,0,0,0,2,27,1,14.080209970474243 +90,CUP,SUM,0,0,0,0,0,21,9,11.635603189468384 +90,SPOON,SUM,0,0,0,0,0,211,0,27.740491151809692 +90,,SUM,0,0,0,0,2,259,10,53.45630431175232 +90,, +91,, +91,BOWL,SUM,0,0,0,0,2,32,0,13.41583800315857 +91,CUP,SUM,0,0,0,0,4,35,2,12.404540061950684 +91,SPOON,SUM,0,0,0,0,0,84,0,19.82103681564331 +91,,SUM,0,0,0,0,6,151,2,45.64141488075256 +91,, +92,, +92,BOWL,SUM,0,0,0,0,0,6,0,11.79392409324646 +92,CUP,SUM,1,0,0,1,0,416,51,0.0 +92,SPOON,SUM,0,0,0,0,0,842,0,68.42870593070984 +92,,SUM,1,0,0,1,0,1264,51,80.2226300239563 +92,, +93,, +93,BOWL,SUM,0,0,0,0,0,16,0,12.574766874313354 +93,CUP,SUM,0,0,0,0,0,6,1,10.343206882476807 +93,SPOON,SUM,0,0,0,0,0,3,0,15.075331926345825 +93,,SUM,0,0,0,0,0,25,1,37.993305683135986 +93,, +94,, +94,BOWL,SUM,1,0,1,0,0,877,80,0.0 +94,CUP,SUM,0,0,0,0,0,13,4,10.121196985244751 +94,SPOON,SUM,0,0,0,0,0,114,0,21.91958999633789 +94,,SUM,1,0,1,0,0,1004,84,32.04078698158264 +94,, +95,, +95,BOWL,SUM,0,0,0,0,0,17,0,12.204182147979736 +95,CUP,SUM,0,0,0,0,0,34,2,10.879449844360352 +95,SPOON,SUM,0,0,0,0,0,12,0,15.7879638671875 +95,,SUM,0,0,0,0,0,63,2,38.87159585952759 +95,, +96,, +96,BOWL,SUM,0,0,0,0,2,18,0,13.021147012710571 +96,CUP,SUM,0,0,0,0,0,27,0,10.56455397605896 +96,SPOON,SUM,1,0,1,0,2,1581,0,0.0 +96,,SUM,1,0,1,0,4,1626,0,23.58570098876953 +96,, +97,, +97,BOWL,SUM,0,0,0,0,0,19,0,12.792561054229736 +97,CUP,SUM,0,0,0,0,0,52,20,18.215160131454468 +97,SPOON,SUM,0,0,0,0,0,16,2,18.532243013381958 +97,,SUM,0,0,0,0,0,87,22,49.53996419906616 +97,, +98,, +98,BOWL,SUM,0,0,0,0,0,12,0,11.830620050430298 +98,CUP,SUM,0,0,0,0,2,22,7,13.019521951675415 +98,SPOON,SUM,1,0,1,0,2,1581,0,0.0 +98,,SUM,1,0,1,0,4,1615,7,24.850142002105713 +98,, +99,, +99,BOWL,SUM,0,0,0,0,6,62,8,23.35291886329651 +99,CUP,SUM,1,0,0,1,0,480,53,0.0 +99,SPOON,SUM,0,0,0,0,0,298,1,33.87840414047241 +99,,SUM,1,0,0,1,6,840,62,57.23132300376892 +99,, +100,, +100,BOWL,SUM,0,0,0,0,0,4,4,17.800010919570923 +100,CUP,SUM,0,0,0,0,0,15,4,11.686959028244019 +100,SPOON,SUM,0,0,0,0,0,60,0,19.145698070526123 +100,,SUM,0,0,0,0,0,79,8,48.632668018341064 +100,, +101,, +101,BOWL,SUM,0,0,0,0,0,30,0,13.798717021942139 +101,CUP,SUM,0,0,0,0,0,43,10,20.249855041503906 +101,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +101,,SUM,1,1,0,0,0,1592,10,34.048572063446045 +101,, +102,, +102,BOWL,SUM,0,0,0,0,48,54,0,38.50616097450256 +102,CUP,SUM,0,0,0,0,0,19,1,10.99690294265747 +102,SPOON,SUM,0,0,0,0,0,1,2,18.978677988052368 +102,,SUM,0,0,0,0,48,74,3,68.4817419052124 +102,, +103,, +103,BOWL,SUM,0,0,0,0,10,35,4,20.22366189956665 +103,CUP,SUM,0,0,0,0,0,5,9,11.357048988342285 +103,SPOON,SUM,0,0,0,0,2,36,10,24.478238821029663 +103,,SUM,0,0,0,0,12,76,23,56.0589497089386 +103,, +104,, +104,BOWL,SUM,0,0,0,0,0,10,0,12.304975986480713 +104,CUP,SUM,0,0,0,0,2,29,3,12.369860887527466 +104,SPOON,SUM,1,0,1,0,2,1581,0,0.0 +104,,SUM,1,0,1,0,4,1620,3,24.67483687400818 +104,, +105,, +105,BOWL,SUM,0,0,0,0,10,70,6,24.05211305618286 +105,CUP,SUM,0,0,0,0,0,6,2,10.620832920074463 +105,SPOON,SUM,0,0,0,0,4,3,2,16.755533933639526 +105,,SUM,0,0,0,0,14,79,10,51.42847990989685 +105,, +106,, +106,BOWL,SUM,0,0,0,0,0,16,4,14.787396907806396 +106,CUP,SUM,0,0,0,0,0,12,1,11.002654075622559 +106,SPOON,SUM,0,0,0,0,0,13,0,16.138017892837524 +106,,SUM,0,0,0,0,0,41,5,41.92806887626648 +106,, +107,, +107,BOWL,SUM,0,0,0,0,0,20,0,12.721915006637573 +107,CUP,SUM,1,0,0,1,0,353,62,0.0 +107,SPOON,SUM,1,0,1,0,2,1583,0,0.0 +107,,SUM,2,0,1,1,2,1956,62,12.721915006637573 +107,, +108,, +108,BOWL,SUM,0,0,0,0,0,27,0,12.946824073791504 +108,CUP,SUM,0,0,0,0,0,12,8,11.228179931640625 +108,SPOON,SUM,0,0,0,0,0,527,1,50.048808097839355 +108,,SUM,0,0,0,0,0,566,9,74.22381210327148 +108,, +109,, +109,BOWL,SUM,0,0,0,0,0,21,0,11.567503929138184 +109,CUP,SUM,0,0,0,0,0,244,49,81.27139186859131 +109,SPOON,SUM,0,0,0,0,0,63,4,22.029635906219482 +109,,SUM,0,0,0,0,0,328,53,114.86853170394897 +109,, +110,, +110,BOWL,SUM,0,0,0,0,6,22,1,14.89569616317749 +110,CUP,SUM,0,0,0,0,0,8,5,9.908454895019531 +110,SPOON,SUM,0,0,0,0,0,512,1,47.66607689857483 +110,,SUM,0,0,0,0,6,542,7,72.47022795677185 +110,, +111,, +111,BOWL,SUM,0,0,0,0,0,6,0,11.526550054550171 +111,CUP,SUM,1,0,0,1,0,344,57,0.0 +111,SPOON,SUM,0,0,0,0,62,500,14,78.99733400344849 +111,,SUM,1,0,0,1,62,850,71,90.52388405799866 +111,, +112,, +112,BOWL,SUM,0,0,0,0,4,98,1,17.31908893585205 +112,CUP,SUM,1,0,0,1,4,468,52,0.0 +112,SPOON,SUM,0,0,0,0,0,197,0,26.712435960769653 +112,,SUM,1,0,0,1,8,763,53,44.031524896621704 +112,, +113,, +113,BOWL,SUM,0,0,0,0,4,22,0,13.302172899246216 +113,CUP,SUM,0,0,0,0,0,10,3,11.202980995178223 +113,SPOON,SUM,0,0,0,0,0,167,7,28.18604803085327 +113,,SUM,0,0,0,0,4,199,10,52.69120192527771 +113,, +114,, +114,BOWL,SUM,0,0,0,0,54,32,0,35.96840310096741 +114,CUP,SUM,0,0,0,0,0,76,5,16.54477310180664 +114,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +114,,SUM,1,0,1,0,54,1689,5,52.51317620277405 +114,, +115,, +115,BOWL,SUM,0,0,0,0,2,67,0,14.346925973892212 +115,CUP,SUM,0,0,0,0,0,9,3,9.81387996673584 +115,SPOON,SUM,0,0,0,0,0,95,1,22.444377899169922 +115,,SUM,0,0,0,0,2,171,4,46.605183839797974 +115,, +116,, +116,BOWL,SUM,0,0,0,0,6,30,1,15.167065858840942 +116,CUP,SUM,0,0,0,0,0,14,2,9.99695897102356 +116,SPOON,SUM,0,0,0,0,0,6,0,14.599212169647217 +116,,SUM,0,0,0,0,6,50,3,39.76323699951172 +116,, +117,, +117,BOWL,SUM,0,0,0,0,0,12,2,11.847212076187134 +117,CUP,SUM,0,0,0,0,0,20,11,12.174223184585571 +117,SPOON,SUM,0,0,0,0,0,247,1,30.167553901672363 +117,,SUM,0,0,0,0,0,279,14,54.18898916244507 +117,, +118,, +118,BOWL,SUM,0,0,0,0,0,6,0,11.314472913742065 +118,CUP,SUM,1,0,0,1,2,413,51,0.0 +118,SPOON,SUM,0,0,0,0,0,227,2,28.659973859786987 +118,,SUM,1,0,0,1,2,646,53,39.97444677352905 +118,, +119,, +119,BOWL,SUM,0,0,0,0,50,212,12,51.11474418640137 +119,CUP,SUM,0,0,0,0,0,8,0,9.749650955200195 +119,SPOON,SUM,0,0,0,0,0,3,0,14.636535882949829 +119,,SUM,0,0,0,0,50,223,12,75.50093102455139 +119,, +120,, +120,BOWL,SUM,0,0,0,0,0,45,6,15.96953821182251 +120,CUP,SUM,1,0,0,1,0,418,51,0.0 +120,SPOON,SUM,0,0,0,0,0,341,0,34.78371000289917 +120,,SUM,1,0,0,1,0,804,57,50.75324821472168 +120,, +121,, +121,BOWL,SUM,1,0,1,0,2,984,72,0.0 +121,CUP,SUM,0,0,0,0,0,25,4,10.827226877212524 +121,SPOON,SUM,0,0,0,0,0,21,5,18.65322995185852 +121,,SUM,1,0,1,0,2,1030,81,29.480456829071045 +121,, +122,, +122,BOWL,SUM,0,0,0,0,6,57,0,15.853643894195557 +122,CUP,SUM,1,0,0,1,0,426,57,0.0 +122,SPOON,SUM,1,0,1,0,0,1613,0,0.0 +122,,SUM,2,0,1,1,6,2096,57,15.853643894195557 +122,, +123,, +123,BOWL,SUM,0,0,0,0,2,48,4,15.062116146087646 +123,CUP,SUM,0,0,0,0,0,9,11,10.229013919830322 +123,SPOON,SUM,1,0,1,0,0,1582,0,0.0 +123,,SUM,1,0,1,0,2,1639,15,25.29113006591797 +123,, +124,, +124,BOWL,SUM,0,0,0,0,6,66,0,16.152804136276245 +124,CUP,SUM,0,0,0,0,0,14,2,10.0834379196167 +124,SPOON,SUM,0,0,0,0,0,115,2,24.257051944732666 +124,,SUM,0,0,0,0,6,195,4,50.49329400062561 +124,, +125,, +125,BOWL,SUM,0,0,0,0,0,99,2,17.631698846817017 +125,CUP,SUM,0,0,0,0,16,17,2,18.07961106300354 +125,SPOON,SUM,0,0,0,0,0,20,2,15.418243885040283 +125,,SUM,0,0,0,0,16,136,6,51.12955379486084 +125,, +126,, +126,BOWL,SUM,0,0,0,0,88,204,0,59.95695400238037 +126,CUP,SUM,1,0,0,1,2,360,58,0.0 +126,SPOON,SUM,0,0,0,0,0,30,0,15.97238802909851 +126,,SUM,1,0,0,1,90,594,58,75.92934203147888 +126,, +127,, +127,BOWL,SUM,0,0,0,0,0,15,0,11.799583911895752 +127,CUP,SUM,0,0,0,0,8,32,3,14.448119163513184 +127,SPOON,SUM,0,0,0,0,0,57,4,19.71224808692932 +127,,SUM,0,0,0,0,8,104,7,45.95995116233826 +127,, +128,, +128,BOWL,SUM,0,0,0,0,0,59,0,14.625644207000732 +128,CUP,SUM,0,0,0,0,2,11,4,11.116237878799438 +128,SPOON,SUM,0,0,0,0,0,100,10,23.936444997787476 +128,,SUM,0,0,0,0,2,170,14,49.67832708358765 +128,, +129,, +129,BOWL,SUM,0,0,0,0,0,118,11,23.743865966796875 +129,CUP,SUM,1,0,0,1,0,372,65,0.0 +129,SPOON,SUM,1,0,1,0,6,1582,0,0.0 +129,,SUM,2,0,1,1,6,2072,76,23.743865966796875 +129,, +130,, +130,BOWL,SUM,0,0,0,0,0,35,4,14.615540027618408 +130,CUP,SUM,1,0,0,1,0,406,58,0.0 +130,SPOON,SUM,0,0,0,0,0,11,2,15.077429056167603 +130,,SUM,1,0,0,1,0,452,64,29.69296908378601 +130,, +131,, +131,BOWL,SUM,0,0,0,0,0,147,3,20.708227157592773 +131,CUP,SUM,0,0,0,0,2,16,3,10.784377098083496 +131,SPOON,SUM,0,0,0,0,0,20,0,15.591785192489624 +131,,SUM,0,0,0,0,2,183,6,47.084389448165894 +131,, +132,, +132,BOWL,SUM,0,0,0,0,0,12,4,13.987966775894165 +132,CUP,SUM,0,0,0,0,0,96,8,23.301986932754517 +132,SPOON,SUM,0,0,0,0,2,130,1,25.703633785247803 +132,,SUM,0,0,0,0,2,238,13,62.993587493896484 +132,, +133,, +133,BOWL,SUM,0,0,0,0,2,14,0,12.79937195777893 +133,CUP,SUM,0,0,0,0,0,4,5,9.971759796142578 +133,SPOON,SUM,0,0,0,0,0,39,0,17.221652030944824 +133,,SUM,0,0,0,0,2,57,5,39.99278378486633 +133,, +134,, +134,BOWL,SUM,0,0,0,0,0,10,1,12.319281101226807 +134,CUP,SUM,1,0,1,0,4,282,104,0.0 +134,SPOON,SUM,0,0,0,0,0,35,0,17.6593279838562 +134,,SUM,1,0,1,0,4,327,105,29.978609085083008 +134,, +135,, +135,BOWL,SUM,0,0,0,0,0,11,0,11.926707983016968 +135,CUP,SUM,0,0,0,0,4,24,0,11.86168885231018 +135,SPOON,SUM,0,0,0,0,2,348,0,37.15507507324219 +135,,SUM,0,0,0,0,6,383,0,60.943471908569336 +135,, +136,, +136,BOWL,SUM,0,0,0,0,2,8,0,12.542533874511719 +136,CUP,SUM,0,0,0,0,0,52,14,16.8253071308136 +136,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +136,,SUM,1,0,1,0,2,1641,14,29.367841005325317 +136,, +137,, +137,BOWL,SUM,0,0,0,0,0,15,4,13.616925954818726 +137,CUP,SUM,0,0,0,0,0,117,20,39.053832054138184 +137,SPOON,SUM,0,0,0,0,0,76,0,19.378774881362915 +137,,SUM,0,0,0,0,0,208,24,72.04953289031982 +137,, +138,, +138,BOWL,SUM,0,0,0,0,0,51,6,16.29563593864441 +138,CUP,SUM,0,0,0,0,0,228,37,62.97385907173157 +138,SPOON,SUM,0,0,0,0,0,17,1,16.847141981124878 +138,,SUM,0,0,0,0,0,296,44,96.11663699150085 +138,, +139,, +139,BOWL,SUM,0,0,0,0,2,36,0,14.364585876464844 +139,CUP,SUM,0,0,0,0,2,28,5,14.750795841217041 +139,SPOON,SUM,0,0,0,0,0,16,1,16.862453937530518 +139,,SUM,0,0,0,0,4,80,6,45.9778356552124 +139,, +140,, +140,BOWL,SUM,0,0,0,0,0,24,2,12.295330047607422 +140,CUP,SUM,0,0,0,0,6,10,4,12.134469985961914 +140,SPOON,SUM,0,0,0,0,0,0,0,14.540496826171875 +140,,SUM,0,0,0,0,6,34,6,38.97029685974121 +140,, +141,, +141,BOWL,SUM,0,0,0,0,0,120,0,18.46475386619568 +141,CUP,SUM,0,0,0,0,0,1,3,9.73424506187439 +141,SPOON,SUM,0,0,0,0,0,465,1,44.433581829071045 +141,,SUM,0,0,0,0,0,586,4,72.63258075714111 +141,, +142,, +142,BOWL,SUM,0,0,0,0,0,41,6,15.963889837265015 +142,CUP,SUM,0,0,0,0,0,20,6,10.84213399887085 +142,SPOON,SUM,0,0,0,0,24,131,26,60.47413206100464 +142,,SUM,0,0,0,0,24,192,38,87.2801558971405 +142,, +143,, +143,BOWL,SUM,0,0,0,0,0,57,6,16.570647954940796 +143,CUP,SUM,1,0,0,1,0,492,62,0.0 +143,SPOON,SUM,0,0,0,0,0,1,0,14.636968851089478 +143,,SUM,1,0,0,1,0,550,68,31.207616806030273 +143,, +144,, +144,BOWL,SUM,0,0,0,0,6,282,0,32.1173779964447 +144,CUP,SUM,1,0,1,0,2,203,97,0.0 +144,SPOON,SUM,0,0,0,0,0,1,5,18.234463930130005 +144,,SUM,1,0,1,0,8,486,102,50.35184192657471 +144,, +145,, +145,BOWL,SUM,0,0,0,0,50,20,0,34.924827098846436 +145,CUP,SUM,0,0,0,0,0,12,0,10.044093132019043 +145,SPOON,SUM,0,0,0,0,0,265,0,31.574290990829468 +145,,SUM,0,0,0,0,50,297,0,76.54321122169495 +145,, +146,, +146,BOWL,SUM,0,0,0,0,2,44,8,19.61944079399109 +146,CUP,SUM,0,0,0,0,0,17,4,10.054734945297241 +146,SPOON,SUM,0,0,0,0,0,437,1,43.566235065460205 +146,,SUM,0,0,0,0,2,498,13,73.24041080474854 +146,, +147,, +147,BOWL,SUM,0,0,0,0,0,84,24,32.48214602470398 +147,CUP,SUM,0,0,0,0,2,29,5,11.726119995117188 +147,SPOON,SUM,0,0,0,0,0,60,0,17.918895959854126 +147,,SUM,0,0,0,0,2,173,29,62.12716197967529 +147,, +148,, +148,BOWL,SUM,0,0,0,0,6,25,0,14.046570062637329 +148,CUP,SUM,1,0,1,0,0,339,111,0.0 +148,SPOON,SUM,0,0,0,0,0,81,1,20.8373920917511 +148,,SUM,1,0,1,0,6,445,112,34.88396215438843 +148,, +149,, +149,BOWL,SUM,0,0,0,0,86,279,10,68.90926003456116 +149,CUP,SUM,0,0,0,0,0,20,2,10.182114839553833 +149,SPOON,SUM,0,0,0,0,2,45,3,19.946721076965332 +149,,SUM,0,0,0,0,88,344,15,99.03809595108032 +149,, +150,, +150,BOWL,SUM,1,0,1,0,0,1467,16,0.0 +150,CUP,SUM,0,0,0,0,0,140,17,36.53234100341797 +150,SPOON,SUM,0,0,0,0,0,7,0,15.356688976287842 +150,,SUM,1,0,1,0,0,1614,33,51.88902997970581 +150,, +151,, +151,BOWL,SUM,0,0,0,0,0,137,0,19.747005939483643 +151,CUP,SUM,0,0,0,0,0,110,18,33.01140809059143 +151,SPOON,SUM,0,0,0,0,0,109,0,21.179864168167114 +151,,SUM,0,0,0,0,0,356,18,73.93827819824219 +151,, +152,, +152,BOWL,SUM,0,0,0,0,0,60,18,26.182717084884644 +152,CUP,SUM,0,0,0,0,0,16,2,10.243320941925049 +152,SPOON,SUM,0,0,0,0,2,6,9,22.562180042266846 +152,,SUM,0,0,0,0,2,82,29,58.98821806907654 +152,, +153,, +153,BOWL,SUM,0,0,0,0,2,33,2,14.602555990219116 +153,CUP,SUM,0,0,0,0,0,13,6,10.749145030975342 +153,SPOON,SUM,0,0,0,0,0,208,0,26.286100149154663 +153,,SUM,0,0,0,0,2,254,8,51.63780117034912 +153,, +154,, +154,BOWL,SUM,0,0,0,0,2,49,0,13.499479055404663 +154,CUP,SUM,0,0,0,0,2,39,5,11.652108192443848 +154,SPOON,SUM,0,0,0,0,0,164,0,25.397688150405884 +154,,SUM,0,0,0,0,4,252,5,50.549275398254395 +154,, +155,, +155,BOWL,SUM,0,0,0,0,6,58,3,17.715280055999756 +155,CUP,SUM,0,0,0,0,26,30,13,27.27844500541687 +155,SPOON,SUM,0,0,0,0,0,991,0,78.09870910644531 +155,,SUM,0,0,0,0,32,1079,16,123.09243416786194 +155,, +156,, +156,BOWL,SUM,0,0,0,0,0,14,6,15.793474912643433 +156,CUP,SUM,1,0,0,1,2,352,53,0.0 +156,SPOON,SUM,0,0,0,0,0,466,0,42.50391888618469 +156,,SUM,1,0,0,1,2,832,59,58.297393798828125 +156,, +157,, +157,BOWL,SUM,0,0,0,0,0,35,0,12.367875099182129 +157,CUP,SUM,0,0,0,0,0,31,11,13.074456930160522 +157,SPOON,SUM,0,0,0,0,0,391,0,39.5691499710083 +157,,SUM,0,0,0,0,0,457,11,65.01148200035095 +157,, +158,, +158,BOWL,SUM,1,1,0,0,392,137,0,0.0 +158,CUP,SUM,0,0,0,0,0,53,9,20.23385000228882 +158,SPOON,SUM,0,0,0,0,0,137,0,22.402831077575684 +158,,SUM,1,1,0,0,392,327,9,42.6366810798645 +158,, +159,, +159,BOWL,SUM,0,0,0,0,0,14,2,11.963004112243652 +159,CUP,SUM,0,0,0,0,0,12,0,10.056885004043579 +159,SPOON,SUM,0,0,0,0,0,5,1,16.93412208557129 +159,,SUM,0,0,0,0,0,31,3,38.95401120185852 +159,, +160,, +160,BOWL,SUM,0,0,0,0,0,78,6,18.210904836654663 +160,CUP,SUM,0,0,0,0,8,12,9,14.623870134353638 +160,SPOON,SUM,0,0,0,0,6,126,1,25.196789979934692 +160,,SUM,0,0,0,0,14,216,16,58.03156495094299 +160,, +161,, +161,BOWL,SUM,0,0,0,0,0,185,0,22.620113134384155 +161,CUP,SUM,1,0,0,1,0,368,57,0.0 +161,SPOON,SUM,0,0,0,0,0,110,1,23.30561900138855 +161,,SUM,1,0,0,1,0,663,58,45.925732135772705 +161,, +162,, +162,BOWL,SUM,0,0,0,0,0,19,0,12.02687692642212 +162,CUP,SUM,1,0,0,1,0,390,54,0.0 +162,SPOON,SUM,0,0,0,0,0,24,2,15.74793004989624 +162,,SUM,1,0,0,1,0,433,56,27.77480697631836 +162,, +163,, +163,BOWL,SUM,0,0,0,0,2,47,0,14.456494092941284 +163,CUP,SUM,1,0,0,1,0,296,57,0.0 +163,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +163,,SUM,2,0,1,1,2,1924,57,14.456494092941284 +163,, +164,, +164,BOWL,SUM,0,0,0,0,2,6,0,12.682980060577393 +164,CUP,SUM,1,0,0,1,0,463,53,0.0 +164,SPOON,SUM,0,0,0,0,4,31,0,18.378522157669067 +164,,SUM,1,0,0,1,6,500,53,31.06150221824646 +164,, +165,, +165,BOWL,SUM,0,0,0,0,0,200,0,24.728469133377075 +165,CUP,SUM,0,0,0,0,0,3,4,10.92294692993164 +165,SPOON,SUM,0,0,0,0,0,106,0,21.721014976501465 +165,,SUM,0,0,0,0,0,309,4,57.37243103981018 +165,, +166,, +166,BOWL,SUM,0,0,0,0,58,75,0,40.825114011764526 +166,CUP,SUM,1,0,0,1,0,270,51,0.0 +166,SPOON,SUM,0,0,0,0,4,60,3,21.024516105651855 +166,,SUM,1,0,0,1,62,405,54,61.84963011741638 +166,, +167,, +167,BOWL,SUM,0,0,0,0,10,27,0,16.73873209953308 +167,CUP,SUM,0,0,0,0,0,10,4,10.609636068344116 +167,SPOON,SUM,0,0,0,0,4,77,1,22.679484128952026 +167,,SUM,0,0,0,0,14,114,5,50.027852296829224 +167,, +168,, +168,BOWL,SUM,0,0,0,0,0,46,0,13.953296899795532 +168,CUP,SUM,0,0,0,0,2,5,4,11.003092050552368 +168,SPOON,SUM,0,0,0,0,0,299,0,33.275604009628296 +168,,SUM,0,0,0,0,2,350,4,58.231992959976196 +168,, +169,, +169,BOWL,SUM,0,0,0,0,0,7,1,11.761155843734741 +169,CUP,SUM,0,0,0,0,0,70,12,24.641326904296875 +169,SPOON,SUM,1,0,1,0,32,1414,0,0.0 +169,,SUM,1,0,1,0,32,1491,13,36.402482748031616 +169,, +170,, +170,BOWL,SUM,0,0,0,0,2,18,2,13.269374132156372 +170,CUP,SUM,0,0,0,0,0,26,4,10.832558155059814 +170,SPOON,SUM,0,0,0,0,0,104,0,21.23623490333557 +170,,SUM,0,0,0,0,2,148,6,45.33816719055176 +170,, +171,, +171,BOWL,SUM,0,0,0,0,0,16,0,12.161690950393677 +171,CUP,SUM,0,0,0,0,2,27,4,11.589982032775879 +171,SPOON,SUM,1,0,1,0,0,1590,0,0.0 +171,,SUM,1,0,1,0,2,1633,4,23.751672983169556 +171,, +172,, +172,BOWL,SUM,0,0,0,0,2,54,4,15.501968145370483 +172,CUP,SUM,0,0,0,0,0,21,7,10.71812915802002 +172,SPOON,SUM,0,0,0,0,72,220,0,58.80133509635925 +172,,SUM,0,0,0,0,74,295,11,85.02143239974976 +172,, +173,, +173,BOWL,SUM,0,0,0,0,2,16,4,15.029282808303833 +173,CUP,SUM,1,0,0,1,0,319,59,0.0 +173,SPOON,SUM,0,0,0,0,2,47,21,34.46365284919739 +173,,SUM,1,0,0,1,4,382,84,49.49293565750122 +173,, +174,, +174,BOWL,SUM,0,0,0,0,0,27,0,12.547150135040283 +174,CUP,SUM,0,0,0,0,2,33,1,11.420753002166748 +174,SPOON,SUM,0,0,0,0,0,86,4,22.6337890625 +174,,SUM,0,0,0,0,2,146,5,46.60169219970703 +174,, +175,, +175,BOWL,SUM,0,0,0,0,2,4,0,12.657434940338135 +175,CUP,SUM,0,0,0,0,0,8,4,10.215267896652222 +175,SPOON,SUM,0,0,0,0,0,262,1,30.864511013031006 +175,,SUM,0,0,0,0,2,274,5,53.73721385002136 +175,, +176,, +176,BOWL,SUM,0,0,0,0,0,17,0,12.379103183746338 +176,CUP,SUM,0,0,0,0,0,3,0,9.740748882293701 +176,SPOON,SUM,0,0,0,0,0,55,3,19.302962064743042 +176,,SUM,0,0,0,0,0,75,3,41.42281413078308 +176,, +177,, +177,BOWL,SUM,0,0,0,0,2,28,1,13.634679079055786 +177,CUP,SUM,0,0,0,0,2,22,3,13.15011191368103 +177,SPOON,SUM,0,0,0,0,0,4,0,14.827833890914917 +177,,SUM,0,0,0,0,4,54,4,41.61262488365173 +177,, +178,, +178,BOWL,SUM,0,0,0,0,0,21,0,13.265253067016602 +178,CUP,SUM,1,0,1,0,0,250,108,0.0 +178,SPOON,SUM,0,0,0,0,10,56,0,22.843289852142334 +178,,SUM,1,0,1,0,10,327,108,36.108542919158936 +178,, +179,, +179,BOWL,SUM,0,0,0,0,0,15,0,11.969815969467163 +179,CUP,SUM,0,0,0,0,0,45,4,12.236590147018433 +179,SPOON,SUM,0,0,0,0,0,305,0,34.55338788032532 +179,,SUM,0,0,0,0,0,365,4,58.75979399681091 +179,, +180,, +180,BOWL,SUM,0,0,0,0,0,18,1,13.940262079238892 +180,CUP,SUM,0,0,0,0,0,4,4,10.294128179550171 +180,SPOON,SUM,0,0,0,0,0,222,2,29.08498787879944 +180,,SUM,0,0,0,0,0,244,7,53.3193781375885 +180,, +181,, +181,BOWL,SUM,0,0,0,0,24,23,0,23.304164171218872 +181,CUP,SUM,0,0,0,0,30,24,0,24.04183006286621 +181,SPOON,SUM,0,0,0,0,2,154,0,24.50091004371643 +181,,SUM,0,0,0,0,56,201,0,71.84690427780151 +181,, +182,, +182,BOWL,SUM,0,0,0,0,0,15,0,11.913676023483276 +182,CUP,SUM,0,0,0,0,0,22,2,10.861221075057983 +182,SPOON,SUM,0,0,0,0,0,209,3,32.82811903953552 +182,,SUM,0,0,0,0,0,246,5,55.60301613807678 +182,, +183,, +183,BOWL,SUM,1,0,1,0,0,1418,22,0.0 +183,CUP,SUM,0,0,0,0,0,27,3,11.007201910018921 +183,SPOON,SUM,0,0,0,0,0,198,0,27.870795011520386 +183,,SUM,1,0,1,0,0,1643,25,38.87799692153931 +183,, +184,, +184,BOWL,SUM,0,0,0,0,0,207,6,26.51952815055847 +184,CUP,SUM,0,0,0,0,4,10,5,12.070653915405273 +184,SPOON,SUM,0,0,0,0,6,115,0,22.50615406036377 +184,,SUM,0,0,0,0,10,332,11,61.096336126327515 +184,, +185,, +185,BOWL,SUM,0,0,0,0,0,37,0,14.345582962036133 +185,CUP,SUM,0,0,0,0,0,20,2,10.788301944732666 +185,SPOON,SUM,0,0,0,0,0,549,1,50.40194892883301 +185,,SUM,0,0,0,0,0,606,3,75.5358338356018 +185,, +186,, +186,BOWL,SUM,0,0,0,0,2,5,2,12.624717950820923 +186,CUP,SUM,0,0,0,0,2,7,1,10.953987836837769 +186,SPOON,SUM,0,0,0,0,0,21,2,16.132928133010864 +186,,SUM,0,0,0,0,4,33,5,39.711633920669556 +186,, +187,, +187,BOWL,SUM,0,0,0,0,0,55,0,14.19918704032898 +187,CUP,SUM,0,0,0,0,0,21,0,10.423296928405762 +187,SPOON,SUM,1,0,1,0,0,1586,0,0.0 +187,,SUM,1,0,1,0,0,1662,0,24.62248396873474 +187,, +188,, +188,BOWL,SUM,0,0,0,0,0,27,1,12.837723970413208 +188,CUP,SUM,0,0,0,0,0,16,2,10.639946937561035 +188,SPOON,SUM,0,0,0,0,0,443,0,41.291576862335205 +188,,SUM,0,0,0,0,0,486,3,64.76924777030945 +188,, +189,, +189,BOWL,SUM,0,0,0,0,0,50,2,14.693984031677246 +189,CUP,SUM,0,0,0,0,0,9,2,10.251981973648071 +189,SPOON,SUM,0,0,0,0,6,110,1,23.712196111679077 +189,,SUM,0,0,0,0,6,169,5,48.658162117004395 +189,, +190,, +190,BOWL,SUM,0,0,0,0,2,27,1,13.803776025772095 +190,CUP,SUM,0,0,0,0,0,21,9,11.678873062133789 +190,SPOON,SUM,0,0,0,0,0,211,0,28.288860082626343 +190,,SUM,0,0,0,0,2,259,10,53.77150917053223 +190,, +191,, +191,BOWL,SUM,0,0,0,0,2,32,0,13.2031090259552 +191,CUP,SUM,0,0,0,0,4,35,2,12.349803924560547 +191,SPOON,SUM,0,0,0,0,0,84,0,19.841108083724976 +191,,SUM,0,0,0,0,6,151,2,45.39402103424072 +191,, +192,, +192,BOWL,SUM,0,0,0,0,0,6,0,11.649395942687988 +192,CUP,SUM,1,0,0,1,0,416,51,0.0 +192,SPOON,SUM,0,0,0,0,0,842,0,69.2507529258728 +192,,SUM,1,0,0,1,0,1264,51,80.90014886856079 +192,, +193,, +193,BOWL,SUM,0,0,0,0,0,16,0,12.435617923736572 +193,CUP,SUM,0,0,0,0,0,6,1,10.384875059127808 +193,SPOON,SUM,0,0,0,0,0,3,0,15.035614013671875 +193,,SUM,0,0,0,0,0,25,1,37.856106996536255 +193,, +194,, +194,BOWL,SUM,1,0,1,0,0,877,80,0.0 +194,CUP,SUM,0,0,0,0,0,13,4,10.169881105422974 +194,SPOON,SUM,0,0,0,0,0,114,0,21.566416025161743 +194,,SUM,1,0,1,0,0,1004,84,31.736297130584717 +194,, +195,, +195,BOWL,SUM,0,0,0,0,0,17,0,12.540690898895264 +195,CUP,SUM,0,0,0,0,0,34,2,10.86382794380188 +195,SPOON,SUM,0,0,0,0,0,12,0,15.340126037597656 +195,,SUM,0,0,0,0,0,63,2,38.7446448802948 +195,, +196,, +196,BOWL,SUM,0,0,0,0,2,18,0,13.13484001159668 +196,CUP,SUM,0,0,0,0,0,27,0,10.709887027740479 +196,SPOON,SUM,1,0,1,0,2,1581,0,0.0 +196,,SUM,1,0,1,0,4,1626,0,23.844727039337158 +196,, +197,, +197,BOWL,SUM,0,0,0,0,0,19,0,12.362322092056274 +197,CUP,SUM,0,0,0,0,0,52,20,18.117652893066406 +197,SPOON,SUM,0,0,0,0,0,16,2,18.58134388923645 +197,,SUM,0,0,0,0,0,87,22,49.06131887435913 +197,, +198,, +198,BOWL,SUM,0,0,0,0,0,12,0,11.835798025131226 +198,CUP,SUM,0,0,0,0,2,22,7,13.12182092666626 +198,SPOON,SUM,1,0,1,0,2,1581,0,0.0 +198,,SUM,1,0,1,0,4,1615,7,24.957618951797485 +198,, +199,, +199,BOWL,SUM,0,0,0,0,6,62,8,23.49095606803894 +199,CUP,SUM,1,0,0,1,0,480,53,0.0 +199,SPOON,SUM,0,0,0,0,0,298,1,34.50297999382019 +199,,SUM,1,0,0,1,6,840,62,57.99393606185913 +199,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_18.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_18.csv new file mode 100644 index 0000000000..8867948906 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_18.csv @@ -0,0 +1,603 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,4,4,16.2374560833 +0,CUP,SUM,0,0,0,0,0,15,4,10.4704999924 +0,SPOON,SUM,0,0,0,0,0,60,0,16.8444399834 +0,,SUM,0,0,0,0,0,79,8,43.552396059 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,0,30,0,12.9731559753 +1,CUP,SUM,0,0,0,0,0,27,4,10.981454134 +1,SPOON,SUM,1,0,1,0,2,1581,0,0 +1,,SUM,1,0,1,0,2,1638,4,23.9546101093 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,0,83,15,24.8656001091 +2,CUP,SUM,0,0,0,0,0,19,0,10.3542590141 +2,SPOON,SUM,0,0,0,0,0,33,12,23.5872950554 +2,,SUM,0,0,0,0,0,135,27,58.8071541786 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,154,269,0,88.7595710754 +3,CUP,SUM,1,0,0,1,0,324,50,0 +3,SPOON,SUM,0,0,0,0,18,8,2,24.045830965 +3,,SUM,1,0,0,1,172,601,52,112.8054020405 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,73,0,13.8756568432 +4,CUP,SUM,0,0,0,0,0,352,54,94.8304069042 +4,SPOON,SUM,0,0,0,0,2,120,0,22.5897541046 +4,,SUM,0,0,0,0,2,545,54,131.295817852 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,6,35,6,17.7312710285 +5,CUP,SUM,0,0,0,0,0,5,4,9.8395249844 +5,SPOON,SUM,0,0,0,0,0,203,0,26.4007291794 +5,,SUM,0,0,0,0,6,243,10,53.9715251923 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,0,17,0,12.0082089901 +6,CUP,SUM,0,0,0,0,0,27,4,13.9392368793 +6,SPOON,SUM,0,0,0,0,0,180,0,25.2282660007 +6,,SUM,0,0,0,0,0,224,4,51.1757118702 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,2,42,0,12.4368000031 +7,CUP,SUM,1,0,0,1,0,427,53,0 +7,SPOON,SUM,0,0,0,0,0,1,0,14.1555950642 +7,,SUM,1,0,0,1,2,470,53,26.5923950672 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,0,18,6,15.1125099659 +8,CUP,SUM,0,0,0,0,0,9,4,9.7542798519 +8,SPOON,SUM,0,0,0,0,0,11,12,25.7450909615 +8,,SUM,0,0,0,0,0,38,22,50.6118807793 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,53,12,21.1743578911 +9,CUP,SUM,0,0,0,0,0,23,9,10.7179811001 +9,SPOON,SUM,0,0,0,0,0,33,0,16.3625621796 +9,,SUM,0,0,0,0,0,109,21,48.2549011707 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,10,0,11.1054830551 +10,CUP,SUM,1,0,0,1,2,411,49,0 +10,SPOON,SUM,0,0,0,0,0,103,0,20.2846729755 +10,,SUM,1,0,0,1,2,524,49,31.3901560307 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,0,191,6,23.9124879837 +11,CUP,SUM,0,0,0,0,4,16,4,12.6119918823 +11,SPOON,SUM,0,0,0,0,0,571,0,49.5138950348 +11,,SUM,0,0,0,0,4,778,10,86.0383749008 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,0,253,14,31.7356081009 +12,CUP,SUM,0,0,0,0,2,20,9,11.1459069252 +12,SPOON,SUM,0,0,0,0,0,7,1,16.2117760181 +12,,SUM,0,0,0,0,2,280,24,59.0932910442 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,0,70,10,19.3543839455 +13,CUP,SUM,0,0,0,0,0,19,8,10.3080780506 +13,SPOON,SUM,0,0,0,0,0,198,1,28.0457658768 +13,,SUM,0,0,0,0,0,287,19,57.7082278728 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,2,16,1,13.5848810673 +14,CUP,SUM,0,0,0,0,0,16,2,9.7371160984 +14,SPOON,SUM,0,0,0,0,0,145,10,29.6244370937 +14,,SUM,0,0,0,0,2,177,13,52.9464342594 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,0,30,1,13.5730979443 +15,CUP,SUM,0,0,0,0,0,89,9,19.4788131714 +15,SPOON,SUM,0,0,0,0,0,2,0,15.024214983 +15,,SUM,0,0,0,0,0,121,10,48.0761260986 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,12,7,16.3400921822 +16,CUP,SUM,0,0,0,0,0,175,42,65.7051961422 +16,SPOON,SUM,0,0,0,0,2,291,0,33.3701329231 +16,,SUM,0,0,0,0,2,478,49,115.4154212475 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,6,102,0,17.8081469536 +17,CUP,SUM,1,0,0,1,0,266,57,0 +17,SPOON,SUM,0,0,0,0,0,11,0,14.9254369736 +17,,SUM,1,0,0,1,6,379,57,32.7335839272 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,160,193,12,98.3077709675 +18,CUP,SUM,1,0,0,1,0,349,55,0 +18,SPOON,SUM,0,0,0,0,0,25,1,16.5119080544 +18,,SUM,1,0,0,1,160,567,68,114.8196790218 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,2,26,0,12.4725220203 +19,CUP,SUM,1,0,1,0,0,161,104,0 +19,SPOON,SUM,0,0,0,0,0,4,0,14.7226011753 +19,,SUM,1,0,1,0,2,191,104,27.1951231956 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,10,44,0,16.4484810829 +20,CUP,SUM,0,0,0,0,2,10,3,10.7196969986 +20,SPOON,SUM,0,0,0,0,0,25,1,17.1095900536 +20,,SUM,0,0,0,0,12,79,4,44.2777681351 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,2,9,0,12.1943640709 +21,CUP,SUM,0,0,0,0,0,13,8,10.2887029648 +21,SPOON,SUM,0,0,0,0,0,248,0,30.4635629654 +21,,SUM,0,0,0,0,2,270,8,52.9466300011 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,6,27,0,13.9284589291 +22,CUP,SUM,0,0,0,0,0,11,4,10.2358520031 +22,SPOON,SUM,0,0,0,0,0,37,1,18.4567949772 +22,,SUM,0,0,0,0,6,75,5,42.6211059093 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,25,6,15.6216650009 +23,CUP,SUM,1,0,0,1,2,403,53,0 +23,SPOON,SUM,0,0,0,0,0,4,0,14.6996209621 +23,,SUM,1,0,0,1,2,432,59,30.3212859631 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,1,0,1,0,0,896,74,0 +24,CUP,SUM,0,0,0,0,30,42,7,29.2580490112 +24,SPOON,SUM,0,0,0,0,0,27,0,15.8645489216 +24,,SUM,1,0,1,0,30,965,81,45.1225979328 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,1,0,1,0,4,995,74,0 +25,CUP,SUM,1,0,0,1,0,393,52,0 +25,SPOON,SUM,0,0,0,0,0,20,0,16.2483501434 +25,,SUM,2,0,1,1,4,1408,126,16.2483501434 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,2,7,0,12.1554951668 +26,CUP,SUM,1,0,0,1,0,319,52,0 +26,SPOON,SUM,0,0,0,0,0,177,16,38.5624678135 +26,,SUM,1,0,0,1,2,503,68,50.7179629803 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,56,32,0,37.8487071991 +27,CUP,SUM,0,0,0,0,0,285,33,66.5630130768 +27,SPOON,SUM,0,0,0,0,0,4,9,22.527479887 +27,,SUM,0,0,0,0,56,321,42,126.9392001629 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,0,28,0,12.4981989861 +28,CUP,SUM,0,0,0,0,0,11,11,13.0419418812 +28,SPOON,SUM,1,0,1,0,24,1411,0,0 +28,,SUM,1,0,1,0,24,1450,11,25.5401408672 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,0,103,0,17.1110711098 +29,CUP,SUM,0,0,0,0,2,38,0,11.3882250786 +29,SPOON,SUM,0,0,0,0,0,42,1,18.783411026 +29,,SUM,0,0,0,0,2,183,1,47.2827072144 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,0,41,0,12.430866003 +30,CUP,SUM,0,0,0,0,0,43,13,15.4557409286 +30,SPOON,SUM,0,0,0,0,2,2,2,15.4752819538 +30,,SUM,0,0,0,0,2,86,15,43.3618888855 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,0,27,0,11.9051709175 +31,CUP,SUM,0,0,0,0,0,51,26,25.7956399918 +31,SPOON,SUM,0,0,0,0,0,397,1,41.2874360085 +31,,SUM,0,0,0,0,0,475,27,78.9882469177 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,0,42,6,15.8033201694 +32,CUP,SUM,0,0,0,0,0,35,7,12.6697258949 +32,SPOON,SUM,1,0,1,0,2,1338,40,0 +32,,SUM,1,0,1,0,2,1415,53,28.4730460644 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,8,0,11.5719320774 +33,CUP,SUM,0,0,0,0,0,50,0,12.4715149403 +33,SPOON,SUM,0,0,0,0,10,234,0,32.2445089817 +33,,SUM,0,0,0,0,10,292,0,56.2879559994 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,0,21,10,18.4994049072 +34,CUP,SUM,0,0,0,0,2,27,14,17.8062098026 +34,SPOON,SUM,0,0,0,0,0,130,1,24.0736699104 +34,,SUM,0,0,0,0,2,178,25,60.3792846203 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,0,14,0,11.6310968399 +35,CUP,SUM,0,0,0,0,0,7,6,11.8997149467 +35,SPOON,SUM,0,0,0,0,0,617,0,52.650605917 +35,,SUM,0,0,0,0,0,638,6,76.1814177036 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,2,8,0,12.1225569248 +36,CUP,SUM,1,0,0,1,0,428,56,0 +36,SPOON,SUM,0,0,0,0,0,431,0,40.7149500847 +36,,SUM,1,0,0,1,2,867,56,52.8375070095 +36,,,,,,,,,, +37,,,,,,,,,, +37,BOWL,SUM,0,0,0,0,2,54,0,14.4484939575 +37,CUP,SUM,0,0,0,0,0,26,5,10.8243238926 +37,SPOON,SUM,0,0,0,0,0,80,1,21.3485279083 +37,,SUM,0,0,0,0,2,160,6,46.6213457584 +37,,,,,,,,,, +38,,,,,,,,,, +38,BOWL,SUM,0,0,0,0,0,16,0,11.5319139957 +38,CUP,SUM,0,0,0,0,0,26,7,12.1131989956 +38,SPOON,SUM,0,0,0,0,10,59,0,21.7312951088 +38,,SUM,0,0,0,0,10,101,7,45.3764081001 +38,,,,,,,,,, +39,,,,,,,,,, +39,BOWL,SUM,0,0,0,0,0,21,0,11.8917360306 +39,CUP,SUM,0,0,0,0,0,19,10,10.4055240154 +39,SPOON,SUM,0,0,0,0,2,184,0,26.2334270477 +39,,SUM,0,0,0,0,2,224,10,48.5306870937 +39,,,,,,,,,, +40,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,0,48,14,22.8808338642 +40,CUP,SUM,0,0,0,0,0,47,0,11.1947181225 +40,SPOON,SUM,0,0,0,0,2,0,5,18.6999690533 +40,,SUM,0,0,0,0,2,95,19,52.77552104 +40,,,,,,,,,, +41,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,0,36,1,13.8424470425 +41,CUP,SUM,0,0,0,0,0,50,2,12.3527231216 +41,SPOON,SUM,0,0,0,0,0,155,1,24.4944059849 +41,,SUM,0,0,0,0,0,241,4,50.689576149 +41,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,0,7,2,11.4791080952 +42,CUP,SUM,0,0,0,0,2,33,6,11.5082781315 +42,SPOON,SUM,0,0,0,0,0,752,0,62.792399168 +42,,SUM,0,0,0,0,2,792,8,85.7797853947 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,2,44,4,14.9074838161 +43,CUP,SUM,0,0,0,0,0,188,31,57.6303720474 +43,SPOON,SUM,0,0,0,0,0,566,0,50.2272160053 +43,,SUM,0,0,0,0,2,798,35,122.7650718689 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,2,54,4,16.3132109642 +44,CUP,SUM,0,0,0,0,0,39,6,12.6680810452 +44,SPOON,SUM,0,0,0,0,0,57,3,21.7122790813 +44,,SUM,0,0,0,0,2,150,13,50.6935710907 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,2,43,0,14.4418501854 +45,CUP,SUM,0,0,0,0,0,38,2,13.8923339844 +45,SPOON,SUM,0,0,0,0,0,235,0,29.1253230572 +45,,SUM,0,0,0,0,2,316,2,57.4595072269 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,0,4,4,17.8793530464 +46,CUP,SUM,0,0,0,0,0,15,4,10.8423290253 +46,SPOON,SUM,0,0,0,0,0,60,0,16.7870910168 +46,,SUM,0,0,0,0,0,79,8,45.5087730885 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,0,0,0,0,0,30,0,12.6920859814 +47,CUP,SUM,0,0,0,0,0,27,4,10.9325151443 +47,SPOON,SUM,1,0,1,0,2,1581,0,0 +47,,SUM,1,0,1,0,2,1638,4,23.6246011257 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,0,83,15,24.7614109516 +48,CUP,SUM,0,0,0,0,0,19,0,10.4242370129 +48,SPOON,SUM,0,0,0,0,0,33,12,23.4025270939 +48,,SUM,0,0,0,0,0,135,27,58.5881750584 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,154,269,0,88.4220490456 +49,CUP,SUM,1,0,0,1,0,324,50,0 +49,SPOON,SUM,0,0,0,0,18,8,2,24.1535410881 +49,,SUM,1,0,0,1,172,601,52,112.5755901337 +49,,,,,,,,,, +50,,,,,,,,,, +50,BOWL,SUM,0,0,0,0,0,73,0,13.7810101509 +50,CUP,SUM,0,0,0,0,0,352,54,94.3111970425 +50,SPOON,SUM,0,0,0,0,2,120,0,22.2922091484 +50,,SUM,0,0,0,0,2,545,54,130.3844163418 +50,,,,,,,,,, +51,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,6,35,6,16.7514798641 +51,CUP,SUM,0,0,0,0,0,5,4,9.4904859066 +51,SPOON,SUM,0,0,0,0,0,203,0,26.2697949409 +51,,SUM,0,0,0,0,6,243,10,52.5117607117 +51,,,,,,,,,, +52,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,0,17,0,11.8372309208 +52,CUP,SUM,0,0,0,0,0,27,4,13.9886760712 +52,SPOON,SUM,0,0,0,0,0,180,0,24.8920230865 +52,,SUM,0,0,0,0,0,224,4,50.7179300785 +52,,,,,,,,,, +53,,,,,,,,,, +53,BOWL,SUM,0,0,0,0,2,42,0,12.5167381763 +53,CUP,SUM,1,0,0,1,0,427,53,0 +53,SPOON,SUM,0,0,0,0,0,1,0,14.1291878223 +53,,SUM,1,0,0,1,2,470,53,26.6459259987 +53,,,,,,,,,, +54,,,,,,,,,, +54,BOWL,SUM,0,0,0,0,0,18,6,14.9566590786 +54,CUP,SUM,0,0,0,0,0,9,4,9.9444282055 +54,SPOON,SUM,0,0,0,0,0,11,12,25.9281978607 +54,,SUM,0,0,0,0,0,38,22,50.8292851448 +54,,,,,,,,,, +55,,,,,,,,,, +55,BOWL,SUM,0,0,0,0,0,53,12,21.0184681416 +55,CUP,SUM,0,0,0,0,0,23,9,10.6439828873 +55,SPOON,SUM,0,0,0,0,0,33,0,16.5439109802 +55,,SUM,0,0,0,0,0,109,21,48.206362009 +55,,,,,,,,,, +56,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,0,10,0,11.3045380116 +56,CUP,SUM,1,0,0,1,2,411,49,0 +56,SPOON,SUM,0,0,0,0,0,103,0,20.2979528904 +56,,SUM,1,0,0,1,2,524,49,31.6024909019 +56,,,,,,,,,, +57,,,,,,,,,, +57,BOWL,SUM,0,0,0,0,0,191,6,23.8236398697 +57,CUP,SUM,0,0,0,0,4,16,4,12.8248479366 +57,SPOON,SUM,0,0,0,0,0,571,0,49.7468731403 +57,,SUM,0,0,0,0,4,778,10,86.3953609467 +57,,,,,,,,,, +58,,,,,,,,,, +58,BOWL,SUM,0,0,0,0,0,253,14,31.620677948 +58,CUP,SUM,0,0,0,0,2,20,9,10.9711649418 +58,SPOON,SUM,0,0,0,0,0,7,1,16.0317130089 +58,,SUM,0,0,0,0,2,280,24,58.6235558987 +58,,,,,,,,,, +59,,,,,,,,,, +59,BOWL,SUM,0,0,0,0,0,70,10,19.3402678967 +59,CUP,SUM,0,0,0,0,0,19,8,10.0810949802 +59,SPOON,SUM,0,0,0,0,0,198,1,27.8355019093 +59,,SUM,0,0,0,0,0,287,19,57.2568647861 +59,,,,,,,,,, +60,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,2,16,1,13.6814711094 +60,CUP,SUM,0,0,0,0,0,16,2,9.8394711018 +60,SPOON,SUM,0,0,0,0,0,145,10,29.4566328526 +60,,SUM,0,0,0,0,2,177,13,52.9775750637 +60,,,,,,,,,, +61,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,0,30,1,13.5182049274 +61,CUP,SUM,0,0,0,0,0,89,9,19.2122871876 +61,SPOON,SUM,0,0,0,0,0,2,0,14.6959400177 +61,,SUM,0,0,0,0,0,121,10,47.4264321327 +61,,,,,,,,,, +62,,,,,,,,,, +62,BOWL,SUM,0,0,0,0,0,12,7,16.4637489319 +62,CUP,SUM,0,0,0,0,0,175,42,65.3243021965 +62,SPOON,SUM,0,0,0,0,2,291,0,33.2289772034 +62,,SUM,0,0,0,0,2,478,49,115.0170283318 +62,,,,,,,,,, +63,,,,,,,,,, +63,BOWL,SUM,0,0,0,0,6,102,0,17.9525821209 +63,CUP,SUM,1,0,0,1,0,266,57,0 +63,SPOON,SUM,0,0,0,0,0,11,0,15.2177460194 +63,,SUM,1,0,0,1,6,379,57,33.1703281403 +63,,,,,,,,,, +64,,,,,,,,,, +64,BOWL,SUM,0,0,0,0,160,193,12,97.3520648479 +64,CUP,SUM,1,0,0,1,0,349,55,0 +64,SPOON,SUM,0,0,0,0,0,25,1,16.7600300312 +64,,SUM,1,0,0,1,160,567,68,114.1120948792 +64,,,,,,,,,, +65,,,,,,,,,, +65,BOWL,SUM,0,0,0,0,2,26,0,12.4528460503 +65,CUP,SUM,1,0,1,0,0,161,104,0 +65,SPOON,SUM,0,0,0,0,0,4,0,14.4461398125 +65,,SUM,1,0,1,0,2,191,104,26.8989858627 +65,,,,,,,,,, +66,,,,,,,,,, +66,BOWL,SUM,0,0,0,0,10,44,0,16.5361349583 +66,CUP,SUM,0,0,0,0,2,10,3,10.5848350525 +66,SPOON,SUM,0,0,0,0,0,25,1,16.6529011726 +66,,SUM,0,0,0,0,12,79,4,43.7738711834 +66,,,,,,,,,, +67,,,,,,,,,, +67,BOWL,SUM,0,0,0,0,2,9,0,12.0693950653 +67,CUP,SUM,0,0,0,0,0,13,8,10.325065136 +67,SPOON,SUM,0,0,0,0,0,248,0,30.4017379284 +67,,SUM,0,0,0,0,2,270,8,52.7961981297 +67,,,,,,,,,, +68,,,,,,,,,, +68,BOWL,SUM,0,0,0,0,6,27,0,13.5110020638 +68,CUP,SUM,0,0,0,0,0,11,4,9.8698658943 +68,SPOON,SUM,0,0,0,0,0,37,1,18.3213400841 +68,,SUM,0,0,0,0,6,75,5,41.7022080421 +68,,,,,,,,,, +69,,,,,,,,,, +69,BOWL,SUM,0,0,0,0,0,25,6,15.3801908493 +69,CUP,SUM,1,0,0,1,2,403,53,0 +69,SPOON,SUM,0,0,0,0,0,4,0,14.6639401913 +69,,SUM,1,0,0,1,2,432,59,30.0441310406 +69,,,,,,,,,, +70,,,,,,,,,, +70,BOWL,SUM,1,0,1,0,0,896,74,0 +70,CUP,SUM,0,0,0,0,30,42,7,29.1665320396 +70,SPOON,SUM,0,0,0,0,0,27,0,15.5546112061 +70,,SUM,1,0,1,0,30,965,81,44.7211432457 +70,,,,,,,,,, +71,,,,,,,,,, +71,BOWL,SUM,1,0,1,0,4,995,74,0 +71,CUP,SUM,1,0,0,1,0,393,52,0 +71,SPOON,SUM,0,0,0,0,0,20,0,15.4341011047 +71,,SUM,2,0,1,1,4,1408,126,15.4341011047 +71,,,,,,,,,, +72,,,,,,,,,, +72,BOWL,SUM,0,0,0,0,2,7,0,12.0778179169 +72,CUP,SUM,1,0,0,1,0,319,52,0 +72,SPOON,SUM,0,0,0,0,0,177,16,37.8959879875 +72,,SUM,1,0,0,1,2,503,68,49.9738059044 +72,,,,,,,,,, +73,,,,,,,,,, +73,BOWL,SUM,0,0,0,0,56,32,0,37.563906908 +73,CUP,SUM,0,0,0,0,0,285,33,66.318805933 +73,SPOON,SUM,0,0,0,0,0,4,9,22.4987170696 +73,,SUM,0,0,0,0,56,321,42,126.3814299107 +73,,,,,,,,,, +74,,,,,,,,,, +74,BOWL,SUM,0,0,0,0,0,28,0,12.1680071354 +74,CUP,SUM,0,0,0,0,0,11,11,13.1461379528 +74,SPOON,SUM,1,0,1,0,24,1411,0,0 +74,,SUM,1,0,1,0,24,1450,11,25.3141450882 +74,,,,,,,,,, +75,,,,,,,,,, +75,BOWL,SUM,0,0,0,0,0,103,0,17.1287541389 +75,CUP,SUM,0,0,0,0,2,38,0,11.0771389008 +75,SPOON,SUM,0,0,0,0,0,42,1,18.4598920345 +75,,SUM,0,0,0,0,2,183,1,46.6657850742 +75,,,,,,,,,, +76,,,,,,,,,, +76,BOWL,SUM,0,0,0,0,0,41,0,12.4701170921 +76,CUP,SUM,0,0,0,0,0,10,9,10.1504859924 +76,SPOON,SUM,0,0,0,0,0,25,8,20.5473971367 +76,,SUM,0,0,0,0,0,76,17,43.1680002213 +76,,,,,,,,,, +77,,,,,,,,,, +77,BOWL,SUM,0,0,0,0,0,57,0,12.7577459812 +77,CUP,SUM,0,0,0,0,2,104,14,27.3339149952 +77,SPOON,SUM,0,0,0,0,6,2,2,16.7994861603 +77,,SUM,0,0,0,0,8,163,16,56.8911471367 +77,,,,,,,,,, +78,,,,,,,,,, +78,BOWL,SUM,0,0,0,0,0,39,0,12.4874441624 +78,CUP,SUM,0,0,0,0,0,20,3,10.5159440041 +78,SPOON,SUM,0,0,0,0,0,812,1,66.6500661373 +78,,SUM,0,0,0,0,0,871,4,89.6534543037 +78,,,,,,,,,, +79,,,,,,,,,, +79,BOWL,SUM,0,0,0,0,0,718,22,65.6877479553 +79,CUP,SUM,0,0,0,0,0,26,0,10.1482510567 +79,SPOON,SUM,0,0,0,0,0,3,0,14.7619140148 +79,,SUM,0,0,0,0,0,747,22,90.5979130268 +79,,,,,,,,,, +80,,,,,,,,,, +80,BOWL,SUM,0,0,0,0,0,56,20,27.7200920582 +80,CUP,SUM,1,0,0,1,0,388,51,0 +80,SPOON,SUM,1,0,1,0,0,1582,0,0 +80,,SUM,2,0,1,1,0,2026,71,27.7200920582 +80,,,,,,,,,, +81,,,,,,,,,, +81,BOWL,SUM,0,0,0,0,0,29,1,13.7535729408 +81,CUP,SUM,1,0,1,0,0,171,91,0 +81,SPOON,SUM,0,0,0,0,0,49,0,17.2417042255 +81,,SUM,1,0,1,0,0,249,92,30.9952771664 +81,,,,,,,,,, +82,,,,,,,,,, +82,BOWL,SUM,0,0,0,0,0,281,34,47.8330280781 +82,CUP,SUM,0,0,0,0,0,369,46,80.648955822 +82,SPOON,SUM,0,0,0,0,0,9,2,17.9789419174 +82,,SUM,0,0,0,0,0,659,82,146.4609258175 +82,,,,,,,,,, +83,,,,,,,,,, +83,BOWL,SUM,0,0,0,0,2,62,8,18.4667298794 +83,CUP,SUM,0,0,0,0,0,16,0,10.0249538422 +83,SPOON,SUM,0,0,0,0,0,30,0,15.3854529858 +83,,SUM,0,0,0,0,2,108,8,43.8771367073 +83,,,,,,,,,, +84,,,,,,,,,, +84,BOWL,SUM,0,0,0,0,0,22,0,11.8543171883 +84,CUP,SUM,0,0,0,0,0,20,12,13.869189024 +84,SPOON,SUM,1,0,1,0,0,1583,0,0 +84,,SUM,1,0,1,0,0,1625,12,25.7235062122 +84,,,,,,,,,, +85,,,,,,,,,, +85,BOWL,SUM,0,0,0,0,0,11,5,14.85709095 +85,CUP,SUM,0,0,0,0,0,4,4,12.7381210327 +85,SPOON,SUM,0,0,0,0,0,74,1,20.5650379658 +85,,SUM,0,0,0,0,0,89,10,48.1602499485 +85,,,,,,,,,, +86,,,,,,,,,, +86,BOWL,SUM,0,0,0,0,2,5,4,13.8542599678 +86,CUP,SUM,0,0,0,0,0,17,2,10.0912680626 +86,SPOON,SUM,0,0,0,0,0,68,1,18.97214818 +86,,SUM,0,0,0,0,2,90,7,42.9176762104 +86,,,,,,,,,, +87,,,,,,,,,, +87,BOWL,SUM,0,0,0,0,6,20,0,13.5779519081 +87,CUP,SUM,1,0,0,1,4,380,53,0 +87,SPOON,SUM,0,0,0,0,0,16,4,16.6922590733 +87,,SUM,1,0,0,1,10,416,57,30.2702109814 +87,,,,,,,,,, +88,,,,,,,,,, +88,BOWL,SUM,1,1,0,0,392,118,0,0 +88,CUP,SUM,0,0,0,0,0,16,3,10.664839983 +88,SPOON,SUM,0,0,0,0,0,8,0,15.1735949516 +88,,SUM,1,1,0,0,392,142,3,25.8384349346 +88,,,,,,,,,, +89,,,,,,,,,, +89,BOWL,SUM,0,0,0,0,0,14,10,18.2631878853 +89,CUP,SUM,0,0,0,0,0,21,4,10.5393879414 +89,SPOON,SUM,0,0,0,0,0,113,0,19.9886269569 +89,,SUM,0,0,0,0,0,148,14,48.7912027836 +89,,,,,,,,,, +90,,,,,,,,,, +90,BOWL,SUM,0,0,0,0,0,22,0,11.7622880936 +90,CUP,SUM,1,0,0,1,0,362,53,0 +90,SPOON,SUM,1,0,1,0,48,1583,0,0 +90,,SUM,2,0,1,1,48,1967,53,11.7622880936 +90,,,,,,,,,, +91,,,,,,,,,, +91,BOWL,SUM,0,0,0,0,2,7,0,12.0714390278 +91,CUP,SUM,1,0,1,0,0,854,94,0 +91,SPOON,SUM,0,0,0,0,0,514,0,46.3303291798 +91,,SUM,1,0,1,0,2,1375,94,58.4017682076 +91,,,,,,,,,, +92,,,,,,,,,, +92,BOWL,SUM,0,0,0,0,2,27,4,14.4192049503 +92,CUP,SUM,0,0,0,0,0,12,8,10.3684670925 +92,SPOON,SUM,1,0,1,0,0,1582,0,0 +92,,SUM,1,0,1,0,2,1621,12,24.7876720428 +92,,,,,,,,,, +93,,,,,,,,,, +93,BOWL,SUM,0,0,0,0,0,99,0,17.5285770893 +93,CUP,SUM,0,0,0,0,0,19,12,11.0180289745 +93,SPOON,SUM,0,0,0,0,6,136,2,26.1282548904 +93,,SUM,0,0,0,0,6,254,14,54.6748609543 +93,,,,,,,,,, +94,,,,,,,,,, +94,BOWL,SUM,0,0,0,0,0,17,1,13.4434289932 +94,CUP,SUM,0,0,0,0,0,25,4,10.4934990406 +94,SPOON,SUM,0,0,0,0,0,54,1,18.3367888927 +94,,SUM,0,0,0,0,0,96,6,42.2737169266 +94,,,,,,,,,, +95,,,,,,,,,, +95,BOWL,SUM,0,0,0,0,0,18,10,18.3626089096 +95,CUP,SUM,0,0,0,0,56,26,8,37.748789072 +95,SPOON,SUM,0,0,0,0,0,187,0,26.9713490009 +95,,SUM,0,0,0,0,56,231,18,83.0827469826 +95,,,,,,,,,, +96,,,,,,,,,, +96,BOWL,SUM,0,0,0,0,0,48,2,16.8780009747 +96,CUP,SUM,0,0,0,0,6,42,2,14.407148838 +96,SPOON,SUM,1,1,0,0,64,1382,0,0 +96,,SUM,1,1,0,0,70,1472,4,31.2851498127 +96,,,,,,,,,, +97,,,,,,,,,, +97,BOWL,SUM,0,0,0,0,2,56,0,14.6934490204 +97,CUP,SUM,1,0,0,1,2,349,51,0 +97,SPOON,SUM,0,0,0,0,0,3,0,14.8656110764 +97,,SUM,1,0,0,1,4,408,51,29.5590600967 +97,,,,,,,,,, +98,,,,,,,,,, +98,BOWL,SUM,0,0,0,0,0,14,0,11.61181283 +98,CUP,SUM,0,0,0,0,8,39,3,16.1233708858 +98,SPOON,SUM,0,0,0,0,0,70,0,18.992606163 +98,,SUM,0,0,0,0,8,123,3,46.7277898788 +98,,,,,,,,,, +99,,,,,,,,,, +99,BOWL,SUM,0,0,0,0,0,99,0,16.0504419804 +99,CUP,SUM,0,0,0,0,0,13,5,10.4515740871 +99,SPOON,SUM,0,0,0,0,0,0,0,14.6150789261 +99,,SUM,0,0,0,0,0,112,5,41.1170949936 +99,,,,,,,,,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_20_part1.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_20_part1.csv new file mode 100644 index 0000000000..6558d2cf6f --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_20_part1.csv @@ -0,0 +1,603 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,4,4,16.6611688137 +0,CUP,SUM,1,0,0,1,0,376,64,0 +0,SPOON,SUM,0,0,0,0,0,2,0,14.2656438351 +0,,SUM,1,0,0,1,0,382,68,30.9268126488 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,0,44,6,15.6040220261 +1,CUP,SUM,0,0,0,0,6,50,3,15.0284740925 +1,SPOON,SUM,0,0,0,0,0,134,0,22.4367809296 +1,,SUM,0,0,0,0,6,228,9,53.0692770481 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,0,68,6,16.059442997 +2,CUP,SUM,1,0,0,1,10,286,76,0 +2,SPOON,SUM,1,0,1,0,0,1582,0,0 +2,,SUM,2,0,1,1,10,1936,82,16.059442997 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,0,64,0,13.6509919167 +3,CUP,SUM,0,0,0,0,2,147,36,59.9504561424 +3,SPOON,SUM,0,0,0,0,0,191,0,26.6098048687 +3,,SUM,0,0,0,0,2,402,36,100.2112529278 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,8,0,11.4069199562 +4,CUP,SUM,1,0,1,0,6,180,112,0 +4,SPOON,SUM,0,0,0,0,0,92,1,21.0085101128 +4,,SUM,1,0,1,0,6,280,113,32.415430069 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,0,20,1,13.3517050743 +5,CUP,SUM,0,0,0,0,6,19,2,11.8665590286 +5,SPOON,SUM,0,0,0,0,0,18,5,19.0119829178 +5,,SUM,0,0,0,0,6,57,8,44.2302470207 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,2,17,6,15.8551669121 +6,CUP,SUM,0,0,0,0,2,118,24,35.0843789577 +6,SPOON,SUM,0,0,0,0,0,11,6,21.1344740391 +6,,SUM,0,0,0,0,4,146,36,72.0740199089 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,0,18,1,13.1944510937 +7,CUP,SUM,0,0,0,0,0,124,32,32.0474119186 +7,SPOON,SUM,0,0,0,0,0,81,0,18.9029319286 +7,,SUM,0,0,0,0,0,223,33,64.1447949409 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,0,13,1,13.0761699677 +8,CUP,SUM,0,0,0,0,0,328,45,82.1692798138 +8,SPOON,SUM,0,0,0,0,112,127,2,69.3269569874 +8,,SUM,0,0,0,0,112,468,48,164.5724067688 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,31,0,11.8655672073 +9,CUP,SUM,0,0,0,0,2,297,41,67.8181140423 +9,SPOON,SUM,0,0,0,0,0,248,0,30.8386969566 +9,,SUM,0,0,0,0,2,576,41,110.5223782063 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,10,112,4,22.2252421379 +10,CUP,SUM,0,0,0,0,0,119,29,42.3396708965 +10,SPOON,SUM,0,0,0,0,0,92,1,20.9530918598 +10,,SUM,0,0,0,0,10,323,34,85.5180048943 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,0,200,18,32.9634809494 +11,CUP,SUM,1,0,0,1,0,313,69,0 +11,SPOON,SUM,0,0,0,0,0,19,8,20.3254811764 +11,,SUM,1,0,0,1,0,532,95,53.2889621258 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,2,7,0,11.9377830029 +12,CUP,SUM,1,0,0,1,2,351,76,0 +12,SPOON,SUM,0,0,0,0,0,12,10,24.3452110291 +12,,SUM,1,0,0,1,4,370,86,36.2829940319 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,48,47,6,37.1727209091 +13,CUP,SUM,0,0,0,0,0,94,19,22.3221919537 +13,SPOON,SUM,0,0,0,0,0,0,3,16.1863930225 +13,,SUM,0,0,0,0,48,141,28,75.6813058853 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,18,39,0,20.1851799488 +14,CUP,SUM,1,0,1,0,0,141,112,0 +14,SPOON,SUM,0,0,0,0,0,579,0,49.4066720009 +14,,SUM,1,0,1,0,18,759,112,69.5918519497 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,0,130,45,51.4853289127 +15,CUP,SUM,0,0,0,0,0,16,1,9.9442520142 +15,SPOON,SUM,0,0,0,0,2,565,0,49.3201470375 +15,,SUM,0,0,0,0,2,711,46,110.7497279644 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,46,1,13.8750658035 +16,CUP,SUM,0,0,0,0,0,19,4,10.1693480015 +16,SPOON,SUM,0,0,0,0,0,10,3,16.7572901249 +16,,SUM,0,0,0,0,0,75,8,40.8017039299 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,0,118,12,22.6210010052 +17,CUP,SUM,0,0,0,0,0,23,1,12.0943498611 +17,SPOON,SUM,0,0,0,0,2,75,1,19.9229140282 +17,,SUM,0,0,0,0,2,216,14,54.6382648945 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,0,20,1,13.7347929478 +18,CUP,SUM,1,0,0,1,0,350,63,0 +18,SPOON,SUM,0,0,0,0,6,21,3,21.4513750076 +18,,SUM,1,0,0,1,6,391,67,35.1861679554 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,312,38,53.4902670383 +19,CUP,SUM,0,0,0,0,0,29,0,10.0312960148 +19,SPOON,SUM,0,0,0,0,0,253,1,30.7723119259 +19,,SUM,0,0,0,0,0,594,39,94.293874979 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,0,20,0,11.9693138599 +20,CUP,SUM,0,0,0,0,0,16,1,10.104501009 +20,SPOON,SUM,0,0,0,0,0,20,0,15.5127840042 +20,,SUM,0,0,0,0,0,56,1,37.5865988731 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,24,0,11.8839871883 +21,CUP,SUM,0,0,0,0,0,113,19,35.945374012 +21,SPOON,SUM,1,0,1,0,6,1620,0,0 +21,,SUM,1,0,1,0,6,1757,19,47.8293612003 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,0,3,2,12.2427031994 +22,CUP,SUM,1,0,1,0,6,187,92,0 +22,SPOON,SUM,0,0,0,0,0,180,1,27.0785560608 +22,,SUM,1,0,1,0,6,370,95,39.3212592602 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,1,0,1,0,0,1050,66,0 +23,CUP,SUM,0,0,0,0,0,3,1,10.0064001083 +23,SPOON,SUM,0,0,0,0,0,598,0,50.8959519863 +23,,SUM,1,0,1,0,0,1651,67,60.9023520947 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,60,29,8,43.8205649853 +24,CUP,SUM,0,0,0,0,0,1,0,9.779624939 +24,SPOON,SUM,0,0,0,0,0,300,12,39.2256288528 +24,,SUM,0,0,0,0,60,330,20,92.8258187771 +24,,,,,,,,,, +25,, +25,BOWL,SUM,0,0,0,0,0,4,4,16.949599981307983 +25,CUP,SUM,1,0,0,1,0,376,64,0.0 +25,SPOON,SUM,0,0,0,0,0,2,0,14.100968837738037 +25,,SUM,1,0,0,1,0,382,68,31.05056881904602 +25,, +26,, +26,BOWL,SUM,0,0,0,0,0,44,6,15.65998888015747 +26,CUP,SUM,0,0,0,0,6,50,3,15.335700988769531 +26,SPOON,SUM,0,0,0,0,0,134,0,22.069692850112915 +26,,SUM,0,0,0,0,6,228,9,53.06538271903992 +26,, +27,, +27,BOWL,SUM,0,0,0,0,0,68,6,16.28399085998535 +27,CUP,SUM,1,0,0,1,10,286,76,0.0 +27,SPOON,SUM,1,0,1,0,0,1582,0,0.0 +27,,SUM,2,0,1,1,10,1936,82,16.28399085998535 +27,, +28,, +28,BOWL,SUM,0,0,0,0,0,64,0,13.517240047454834 +28,CUP,SUM,0,0,0,0,2,147,36,60.134156942367554 +28,SPOON,SUM,0,0,0,0,0,191,0,26.186558961868286 +28,,SUM,0,0,0,0,2,402,36,99.83795595169067 +28,, +29,, +29,BOWL,SUM,0,0,0,0,0,8,0,11.17835783958435 +29,CUP,SUM,1,0,1,0,6,180,112,0.0 +29,SPOON,SUM,0,0,0,0,0,92,1,20.609045028686523 +29,,SUM,1,0,1,0,6,280,113,31.787402868270874 +29,, +30,, +30,BOWL,SUM,0,0,0,0,0,20,1,13.012551069259644 +30,CUP,SUM,0,0,0,0,6,19,2,11.9249849319458 +30,SPOON,SUM,0,0,0,0,0,18,5,18.266555070877075 +30,,SUM,0,0,0,0,6,57,8,43.20409107208252 +30,, +31,, +31,BOWL,SUM,0,0,0,0,2,17,6,15.561522006988525 +31,CUP,SUM,0,0,0,0,2,118,24,34.77896308898926 +31,SPOON,SUM,0,0,0,0,0,11,6,20.601846933364868 +31,,SUM,0,0,0,0,4,146,36,70.94233202934265 +31,, +32,, +32,BOWL,SUM,0,0,0,0,0,18,1,13.068078994750977 +32,CUP,SUM,0,0,0,0,0,124,32,32.178666830062866 +32,SPOON,SUM,0,0,0,0,0,81,0,18.410751819610596 +32,,SUM,0,0,0,0,0,223,33,63.65749764442444 +32,, +33,, +33,BOWL,SUM,0,0,0,0,0,13,1,12.907893896102905 +33,CUP,SUM,0,0,0,0,0,328,45,82.39226794242859 +33,SPOON,SUM,0,0,0,0,112,127,2,69.29758095741272 +33,,SUM,0,0,0,0,112,468,48,164.5977427959442 +33,, +34,, +34,BOWL,SUM,0,0,0,0,0,31,0,11.882582187652588 +34,CUP,SUM,0,0,0,0,2,297,41,67.87673902511597 +34,SPOON,SUM,0,0,0,0,0,248,0,30.6933810710907 +34,,SUM,0,0,0,0,2,576,41,110.45270228385925 +34,, +35,, +35,BOWL,SUM,0,0,0,0,10,112,4,21.997658014297485 +35,CUP,SUM,0,0,0,0,0,119,29,42.217774868011475 +35,SPOON,SUM,0,0,0,0,0,92,1,20.550065994262695 +35,,SUM,0,0,0,0,10,323,34,84.76549887657166 +35,, +36,, +36,BOWL,SUM,0,0,0,0,0,200,18,32.60032606124878 +36,CUP,SUM,1,0,0,1,0,313,69,0.0 +36,SPOON,SUM,0,0,0,0,0,19,8,19.977538108825684 +36,,SUM,1,0,0,1,0,532,95,52.57786417007446 +36,, +37,, +37,BOWL,SUM,0,0,0,0,2,7,0,11.67054796218872 +37,CUP,SUM,1,0,0,1,2,351,76,0.0 +37,SPOON,SUM,0,0,0,0,0,12,10,24.11309790611267 +37,,SUM,1,0,0,1,4,370,86,35.78364586830139 +37,, +38,, +38,BOWL,SUM,0,0,0,0,48,47,6,37.62914204597473 +38,CUP,SUM,0,0,0,0,0,94,19,22.68413805961609 +38,SPOON,SUM,0,0,0,0,0,0,3,16.030354976654053 +38,,SUM,0,0,0,0,48,141,28,76.34363508224487 +38,, +39,, +39,BOWL,SUM,0,0,0,0,18,39,0,20.24664282798767 +39,CUP,SUM,1,0,1,0,0,141,112,0.0 +39,SPOON,SUM,0,0,0,0,0,579,0,49.29096794128418 +39,,SUM,1,0,1,0,18,759,112,69.53761076927185 +39,, +40,, +40,BOWL,SUM,0,0,0,0,0,130,45,50.88422203063965 +40,CUP,SUM,0,0,0,0,0,16,1,9.955623865127563 +40,SPOON,SUM,0,0,0,0,2,565,0,49.80317401885986 +40,,SUM,0,0,0,0,2,711,46,110.64301991462708 +40,, +41,, +41,BOWL,SUM,0,0,0,0,0,46,1,13.849168062210083 +41,CUP,SUM,0,0,0,0,0,19,4,10.197440147399902 +41,SPOON,SUM,0,0,0,0,0,10,3,16.281809091567993 +41,,SUM,0,0,0,0,0,75,8,40.32841730117798 +41,, +42,, +42,BOWL,SUM,0,0,0,0,0,118,12,22.725507020950317 +42,CUP,SUM,0,0,0,0,0,23,1,11.918643951416016 +42,SPOON,SUM,0,0,0,0,2,75,1,19.565537929534912 +42,,SUM,0,0,0,0,2,216,14,54.209688901901245 +42,, +43,, +43,BOWL,SUM,0,0,0,0,0,20,1,13.62506914138794 +43,CUP,SUM,1,0,0,1,0,350,63,0.0 +43,SPOON,SUM,0,0,0,0,6,21,3,21.155277013778687 +43,,SUM,1,0,0,1,6,391,67,34.780346155166626 +43,, +44,, +44,BOWL,SUM,0,0,0,0,0,312,38,53.79002404212952 +44,CUP,SUM,0,0,0,0,0,29,0,9.90657901763916 +44,SPOON,SUM,0,0,0,0,0,253,1,30.38852095603943 +44,,SUM,0,0,0,0,0,594,39,94.0851240158081 +44,, +45,, +45,BOWL,SUM,0,0,0,0,0,20,0,11.480844974517822 +45,CUP,SUM,0,0,0,0,0,16,1,9.890897989273071 +45,SPOON,SUM,0,0,0,0,0,20,0,14.797001838684082 +45,,SUM,0,0,0,0,0,56,1,36.168744802474976 +45,, +46,, +46,BOWL,SUM,0,0,0,0,0,24,0,11.840970993041992 +46,CUP,SUM,0,0,0,0,0,113,19,36.04751420021057 +46,SPOON,SUM,1,0,1,0,6,1620,0,0.0 +46,,SUM,1,0,1,0,6,1757,19,47.88848519325256 +46,, +47,, +47,BOWL,SUM,0,0,0,0,0,3,2,11.951558113098145 +47,CUP,SUM,1,0,1,0,6,187,92,0.0 +47,SPOON,SUM,0,0,0,0,0,180,1,26.875808000564575 +47,,SUM,1,0,1,0,6,370,95,38.82736611366272 +47,, +48,, +48,BOWL,SUM,1,0,1,0,0,1050,66,0.0 +48,CUP,SUM,0,0,0,0,0,3,1,9.980646133422852 +48,SPOON,SUM,0,0,0,0,0,598,0,50.41921305656433 +48,,SUM,1,0,1,0,0,1651,67,60.39985918998718 +48,, +49,, +49,BOWL,SUM,0,0,0,0,60,29,8,43.32825803756714 +49,CUP,SUM,0,0,0,0,0,1,0,9.431726932525635 +49,SPOON,SUM,0,0,0,0,0,300,12,38.50713396072388 +49,,SUM,0,0,0,0,60,330,20,91.26711893081665 +49,, +50,, +50,BOWL,SUM,0,0,0,0,0,13,0,11.38477897644043 +50,CUP,SUM,1,0,0,1,0,295,61,0.0 +50,SPOON,SUM,0,0,0,0,0,73,6,21.518126010894775 +50,,SUM,1,0,0,1,0,381,67,32.902904987335205 +50,, +51,, +51,BOWL,SUM,0,0,0,0,0,15,0,11.694031953811646 +51,CUP,SUM,1,0,1,0,10,162,102,0.0 +51,SPOON,SUM,0,0,0,0,0,58,0,18.062873125076294 +51,,SUM,1,0,1,0,10,235,102,29.75690507888794 +51,, +52,, +52,BOWL,SUM,0,0,0,0,0,9,0,11.506785154342651 +52,CUP,SUM,0,0,0,0,4,109,38,55.145254135131836 +52,SPOON,SUM,0,0,0,0,6,38,3,23.178800106048584 +52,,SUM,0,0,0,0,10,156,41,89.83083939552307 +52,, +53,, +53,BOWL,SUM,0,0,0,0,6,14,0,13.980363130569458 +53,CUP,SUM,1,0,1,0,2,301,111,0.0 +53,SPOON,SUM,0,0,0,0,0,68,4,24.582911014556885 +53,,SUM,1,0,1,0,8,383,115,38.56327414512634 +53,, +54,, +54,BOWL,SUM,0,0,0,0,0,28,4,13.442462921142578 +54,CUP,SUM,0,0,0,0,0,15,4,10.218456983566284 +54,SPOON,SUM,0,0,0,0,0,43,2,19.78277015686035 +54,,SUM,0,0,0,0,0,86,10,43.443690061569214 +54,, +55,, +55,BOWL,SUM,0,0,0,0,0,7,4,13.551067113876343 +55,CUP,SUM,1,0,1,0,0,154,110,0.0 +55,SPOON,SUM,0,0,0,0,0,297,1,34.68845200538635 +55,,SUM,1,0,1,0,0,458,115,48.239519119262695 +55,, +56,, +56,BOWL,SUM,0,0,0,0,0,130,30,39.680269956588745 +56,CUP,SUM,0,0,0,0,2,19,2,11.181154012680054 +56,SPOON,SUM,0,0,0,0,0,30,1,17.099341869354248 +56,,SUM,0,0,0,0,2,179,33,67.96076583862305 +56,, +57,, +57,BOWL,SUM,0,0,0,0,0,76,8,20.095587015151978 +57,CUP,SUM,0,0,0,0,0,41,19,20.68276810646057 +57,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +57,,SUM,1,0,1,0,0,1698,27,40.77835512161255 +57,, +58,, +58,BOWL,SUM,0,0,0,0,0,5,2,11.953274965286255 +58,CUP,SUM,0,0,0,0,0,271,41,76.51339817047119 +58,SPOON,SUM,0,0,0,0,0,67,0,18.61331796646118 +58,,SUM,0,0,0,0,0,343,43,107.07999110221863 +58,, +59,, +59,BOWL,SUM,0,0,0,0,0,22,6,15.697566986083984 +59,CUP,SUM,0,0,0,0,2,26,2,14.31882095336914 +59,SPOON,SUM,1,0,1,0,0,1582,0,0.0 +59,,SUM,1,0,1,0,2,1630,8,30.016387939453125 +59,, +60,, +60,BOWL,SUM,0,0,0,0,8,59,8,22.326017141342163 +60,CUP,SUM,0,0,0,0,0,6,0,10.008970975875854 +60,SPOON,SUM,1,0,1,0,0,1042,60,0.0 +60,,SUM,1,0,1,0,8,1107,68,32.33498811721802 +60,, +61,, +61,BOWL,SUM,0,0,0,0,0,15,4,13.868732213973999 +61,CUP,SUM,0,0,0,0,0,8,0,9.934978008270264 +61,SPOON,SUM,0,0,0,0,0,65,3,20.601611137390137 +61,,SUM,0,0,0,0,0,88,7,44.4053213596344 +61,, +62,, +62,BOWL,SUM,0,0,0,0,0,9,0,11.742676019668579 +62,CUP,SUM,0,0,0,0,2,30,10,13.299859046936035 +62,SPOON,SUM,0,0,0,0,0,5,0,15.093966007232666 +62,,SUM,0,0,0,0,2,44,10,40.13650107383728 +62,, +63,, +63,BOWL,SUM,0,0,0,0,0,15,0,11.683734893798828 +63,CUP,SUM,0,0,0,0,0,55,22,22.240396976470947 +63,SPOON,SUM,1,0,1,0,0,1584,0,0.0 +63,,SUM,1,0,1,0,0,1654,22,33.924131870269775 +63,, +64,, +64,BOWL,SUM,1,0,1,0,2,260,104,0.0 +64,CUP,SUM,0,0,0,0,0,4,0,10.045933961868286 +64,SPOON,SUM,0,0,0,0,4,76,1,21.810161113739014 +64,,SUM,1,0,1,0,6,340,105,31.8560950756073 +64,, +65,, +65,BOWL,SUM,0,0,0,0,2,14,2,12.712817907333374 +65,CUP,SUM,1,0,0,1,0,456,79,0.0 +65,SPOON,SUM,0,0,0,0,0,89,0,19.968698024749756 +65,,SUM,1,0,0,1,2,559,81,32.68151593208313 +65,, +66,, +66,BOWL,SUM,0,0,0,0,2,25,2,12.756207942962646 +66,CUP,SUM,0,0,0,0,4,26,2,11.32500696182251 +66,SPOON,SUM,0,0,0,0,0,1,1,16.360666036605835 +66,,SUM,0,0,0,0,6,52,5,40.44188094139099 +66,, +67,, +67,BOWL,SUM,0,0,0,0,2,19,0,12.438632011413574 +67,CUP,SUM,0,0,0,0,0,6,2,9.886150121688843 +67,SPOON,SUM,0,0,0,0,0,32,2,19.113168954849243 +67,,SUM,0,0,0,0,2,57,4,41.43795108795166 +67,, +68,, +68,BOWL,SUM,0,0,0,0,0,377,40,54.36492705345154 +68,CUP,SUM,0,0,0,0,0,24,2,13.402829885482788 +68,SPOON,SUM,0,0,0,0,0,7,4,16.907499074935913 +68,,SUM,0,0,0,0,0,408,46,84.67525601387024 +68,, +69,, +69,BOWL,SUM,1,0,1,0,0,1028,62,0.0 +69,CUP,SUM,0,0,0,0,2,19,14,21.7296199798584 +69,SPOON,SUM,0,0,0,0,0,35,0,16.623223066329956 +69,,SUM,1,0,1,0,2,1082,76,38.352843046188354 +69,, +70,, +70,BOWL,SUM,0,0,0,0,2,40,0,14.365643978118896 +70,CUP,SUM,0,0,0,0,0,4,8,10.447993993759155 +70,SPOON,SUM,0,0,0,0,0,163,0,24.92411208152771 +70,,SUM,0,0,0,0,2,207,8,49.73775005340576 +70,, +71,, +71,BOWL,SUM,0,0,0,0,0,22,0,12.076364994049072 +71,CUP,SUM,0,0,0,0,0,185,40,74.66619396209717 +71,SPOON,SUM,0,0,0,0,0,691,0,57.889281034469604 +71,,SUM,0,0,0,0,0,898,40,144.63183999061584 +71,, +72,, +72,BOWL,SUM,0,0,0,0,0,35,0,12.858017921447754 +72,CUP,SUM,0,0,0,0,0,164,39,64.75081491470337 +72,SPOON,SUM,0,0,0,0,0,1,2,14.921320915222168 +72,,SUM,0,0,0,0,0,200,41,92.53015375137329 +72,, +73,, +73,BOWL,SUM,0,0,0,0,4,24,7,18.015502214431763 +73,CUP,SUM,0,0,0,0,0,65,7,19.476727962493896 +73,SPOON,SUM,1,0,1,0,0,1094,58,0.0 +73,,SUM,1,0,1,0,4,1183,72,37.49223017692566 +73,, +74,, +74,BOWL,SUM,0,0,0,0,0,32,0,12.25517201423645 +74,CUP,SUM,0,0,0,0,0,21,4,10.163872957229614 +74,SPOON,SUM,0,0,0,0,0,93,0,19.643522024154663 +74,,SUM,0,0,0,0,0,146,4,42.06256699562073 +74,, +75,, +75,BOWL,SUM,0,0,0,0,2,45,2,14.877926111221313 +75,CUP,SUM,0,0,0,0,0,10,4,11.792137145996094 +75,SPOON,SUM,1,0,1,0,0,979,66,0.0 +75,,SUM,1,0,1,0,2,1034,72,26.670063257217407 +75,, +76,, +76,BOWL,SUM,0,0,0,0,0,2,0,11.577615022659302 +76,CUP,SUM,0,0,0,0,0,21,0,10.126342058181763 +76,SPOON,SUM,0,0,0,0,0,398,0,39.12458300590515 +76,,SUM,0,0,0,0,0,421,0,60.828540086746216 +76,, +77,, +77,BOWL,SUM,0,0,0,0,4,32,0,13.300072193145752 +77,CUP,SUM,0,0,0,0,4,34,12,18.7345290184021 +77,SPOON,SUM,0,0,0,0,0,242,3,33.12813401222229 +77,,SUM,0,0,0,0,8,308,15,65.16273522377014 +77,, +78,, +78,BOWL,SUM,0,0,0,0,0,41,2,12.813586950302124 +78,CUP,SUM,0,0,0,0,2,36,3,12.960742950439453 +78,SPOON,SUM,0,0,0,0,0,290,1,33.83033990859985 +78,,SUM,0,0,0,0,2,367,6,59.60466980934143 +78,, +79,, +79,BOWL,SUM,0,0,0,0,0,29,0,12.621478080749512 +79,CUP,SUM,0,0,0,0,6,9,6,12.36069393157959 +79,SPOON,SUM,0,0,0,0,0,0,1,16.38251304626465 +79,,SUM,0,0,0,0,6,38,7,41.36468505859375 +79,, +80,, +80,BOWL,SUM,0,0,0,0,6,283,37,52.785454988479614 +80,CUP,SUM,0,0,0,0,2,93,18,35.083172082901 +80,SPOON,SUM,0,0,0,0,0,12,0,15.068411111831665 +80,,SUM,0,0,0,0,8,388,55,102.93703818321228 +80,, +81,, +81,BOWL,SUM,0,0,0,0,2,69,0,14.973819017410278 +81,CUP,SUM,0,0,0,0,0,242,55,80.77224898338318 +81,SPOON,SUM,0,0,0,0,0,0,0,14.69796895980835 +81,,SUM,0,0,0,0,2,311,55,110.4440369606018 +81,, +82,, +82,BOWL,SUM,0,0,0,0,0,334,16,40.01588487625122 +82,CUP,SUM,0,0,0,0,0,14,7,13.48666000366211 +82,SPOON,SUM,0,0,0,0,0,7,1,16.93450903892517 +82,,SUM,0,0,0,0,0,355,24,70.4370539188385 +82,, +83,, +83,BOWL,SUM,0,0,0,0,0,9,0,11.893603086471558 +83,CUP,SUM,0,0,0,0,0,6,6,12.139616966247559 +83,SPOON,SUM,1,0,1,0,0,1583,0,0.0 +83,,SUM,1,0,1,0,0,1598,6,24.033220052719116 +83,, +84,, +84,BOWL,SUM,1,0,1,0,0,879,74,0.0 +84,CUP,SUM,0,0,0,0,0,15,6,10.726776123046875 +84,SPOON,SUM,0,0,0,0,0,5,0,15.17947506904602 +84,,SUM,1,0,1,0,0,899,80,25.906251192092896 +84,, +85,, +85,BOWL,SUM,0,0,0,0,0,12,0,11.57221007347107 +85,CUP,SUM,0,0,0,0,0,226,33,52.7203848361969 +85,SPOON,SUM,0,0,0,0,0,446,1,41.811765909194946 +85,,SUM,0,0,0,0,0,684,34,106.10436081886292 +85,, +86,, +86,BOWL,SUM,0,0,0,0,0,10,1,11.851764917373657 +86,CUP,SUM,0,0,0,0,0,59,3,11.38549017906189 +86,SPOON,SUM,0,0,0,0,0,529,0,48.6758930683136 +86,,SUM,0,0,0,0,0,598,4,71.91314816474915 +86,, +87,, +87,BOWL,SUM,0,0,0,0,0,35,1,13.696624994277954 +87,CUP,SUM,0,0,0,0,0,15,13,15.476176977157593 +87,SPOON,SUM,0,0,0,0,0,660,8,63.22927117347717 +87,,SUM,0,0,0,0,0,710,22,92.40207314491272 +87,, +88,, +88,BOWL,SUM,0,0,0,0,16,28,2,19.939536094665527 +88,CUP,SUM,1,0,0,1,0,198,68,0.0 +88,SPOON,SUM,0,0,0,0,6,221,1,30.573795080184937 +88,,SUM,1,0,0,1,22,447,71,50.513331174850464 +88,, +89,, +89,BOWL,SUM,0,0,0,0,0,15,2,12.052966117858887 +89,CUP,SUM,1,0,0,1,0,330,73,0.0 +89,SPOON,SUM,0,0,0,0,0,0,0,14.74968695640564 +89,,SUM,1,0,0,1,0,345,75,26.802653074264526 +89,, +90,, +90,BOWL,SUM,0,0,0,0,0,11,0,11.736772060394287 +90,CUP,SUM,0,0,0,0,0,29,15,14.072566032409668 +90,SPOON,SUM,0,0,0,0,0,1,0,15.177825927734375 +90,,SUM,0,0,0,0,0,41,15,40.98716402053833 +90,, +91,, +91,BOWL,SUM,0,0,0,0,0,14,0,11.552692174911499 +91,CUP,SUM,0,0,0,0,0,46,7,15.608766794204712 +91,SPOON,SUM,0,0,0,0,0,3,4,16.68530797958374 +91,,SUM,0,0,0,0,0,63,11,43.84676694869995 +91,, +92,, +92,BOWL,SUM,0,0,0,0,0,46,9,19.07302713394165 +92,CUP,SUM,1,0,1,0,0,773,80,0.0 +92,SPOON,SUM,0,0,0,0,0,3,0,14.979291915893555 +92,,SUM,1,0,1,0,0,822,89,34.052319049835205 +92,, +93,, +93,BOWL,SUM,0,0,0,0,2,62,0,15.186089038848877 +93,CUP,SUM,0,0,0,0,0,28,19,20.242428064346313 +93,SPOON,SUM,0,0,0,0,0,26,1,17.479218006134033 +93,,SUM,0,0,0,0,2,116,20,52.907735109329224 +93,, +94,, +94,BOWL,SUM,0,0,0,0,0,12,1,13.495743989944458 +94,CUP,SUM,1,0,1,0,54,604,105,0.0 +94,SPOON,SUM,0,0,0,0,0,166,0,23.900057077407837 +94,,SUM,1,0,1,0,54,782,106,37.395801067352295 +94,, +95,, +95,BOWL,SUM,0,0,0,0,0,10,0,12.004854917526245 +95,CUP,SUM,0,0,0,0,0,22,7,11.12520980834961 +95,SPOON,SUM,0,0,0,0,0,18,2,15.398725986480713 +95,,SUM,0,0,0,0,0,50,9,38.52879071235657 +95,, +96,, +96,BOWL,SUM,0,0,0,0,0,20,1,12.414215803146362 +96,CUP,SUM,0,0,0,0,0,20,4,10.268713235855103 +96,SPOON,SUM,0,0,0,0,0,244,2,32.57254195213318 +96,,SUM,0,0,0,0,0,284,7,55.255470991134644 +96,, +97,, +97,BOWL,SUM,0,0,0,0,0,6,2,11.66205096244812 +97,CUP,SUM,0,0,0,0,0,20,8,15.461537837982178 +97,SPOON,SUM,0,0,0,0,0,100,1,22.097360849380493 +97,,SUM,0,0,0,0,0,126,11,49.22094964981079 +97,, +98,, +98,BOWL,SUM,0,0,0,0,2,4,2,12.723596096038818 +98,CUP,SUM,0,0,0,0,0,11,10,10.682344913482666 +98,SPOON,SUM,0,0,0,0,2,64,40,49.18349289894104 +98,,SUM,0,0,0,0,4,79,52,72.58943390846252 +98,, +99,, +99,BOWL,SUM,0,0,0,0,0,10,1,13.405442953109741 +99,CUP,SUM,0,0,0,0,2,8,3,10.61590313911438 +99,SPOON,SUM,0,0,0,0,4,8,1,18.0188090801239 +99,,SUM,0,0,0,0,6,26,5,42.04015517234802 +99,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_20_part2.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_20_part2.csv new file mode 100644 index 0000000000..e16661bc7b --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_20_part2.csv @@ -0,0 +1,603 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,4,4,16.7406220436 +0,CUP,SUM,1,0,0,1,0,376,64,0 +0,SPOON,SUM,0,0,0,0,0,2,0,14.5872440338 +0,,SUM,1,0,0,1,0,382,68,31.3278660774 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,0,44,6,15.8494539261 +1,CUP,SUM,0,0,0,0,6,50,3,15.7331199646 +1,SPOON,SUM,0,0,0,0,0,134,0,22.3886430264 +1,,SUM,0,0,0,0,6,228,9,53.971216917 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,0,68,6,16.0867450237 +2,CUP,SUM,1,0,0,1,10,286,76,0 +2,SPOON,SUM,1,0,1,0,0,1582,0,0 +2,,SUM,2,0,1,1,10,1936,82,16.0867450237 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,0,64,0,13.8686699867 +3,CUP,SUM,0,0,0,0,2,147,36,61.6210930347 +3,SPOON,SUM,0,0,0,0,0,191,0,27.197562933 +3,,SUM,0,0,0,0,2,402,36,102.6873259544 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,8,0,11.6219861507 +4,CUP,SUM,1,0,1,0,6,180,112,0 +4,SPOON,SUM,0,0,0,0,0,92,1,21.3675892353 +4,,SUM,1,0,1,0,6,280,113,32.989575386 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,0,20,1,13.5166180134 +5,CUP,SUM,0,0,0,0,6,19,2,12.1102340221 +5,SPOON,SUM,0,0,0,0,0,18,5,18.633368969 +5,,SUM,0,0,0,0,6,57,8,44.2602210045 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,2,17,6,15.7516629696 +6,CUP,SUM,0,0,0,0,2,118,24,35.9805560112 +6,SPOON,SUM,0,0,0,0,0,11,6,20.9326739311 +6,,SUM,0,0,0,0,4,146,36,72.6648929119 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,0,18,1,13.5556340218 +7,CUP,SUM,0,0,0,0,0,124,32,32.8481168747 +7,SPOON,SUM,0,0,0,0,0,81,0,18.8586409092 +7,,SUM,0,0,0,0,0,223,33,65.2623918056 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,0,13,1,13.2861740589 +8,CUP,SUM,0,0,0,0,0,328,45,83.6017458439 +8,SPOON,SUM,0,0,0,0,112,127,2,74.6888968945 +8,,SUM,0,0,0,0,112,468,48,171.5768167973 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,31,0,12.0420560837 +9,CUP,SUM,0,0,0,0,2,297,41,69.3607239723 +9,SPOON,SUM,0,0,0,0,0,248,0,30.9776060581 +9,,SUM,0,0,0,0,2,576,41,112.3803861141 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,10,112,4,23.0620281696 +10,CUP,SUM,0,0,0,0,0,119,29,43.5836498737 +10,SPOON,SUM,0,0,0,0,0,92,1,21.318406105 +10,,SUM,0,0,0,0,10,323,34,87.9640841484 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,0,200,18,33.784414053 +11,CUP,SUM,1,0,0,1,0,313,69,0 +11,SPOON,SUM,0,0,0,0,0,22,12,23.5116629601 +11,,SUM,1,0,0,1,0,535,99,57.296077013 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,0,7,0,11.5979888439 +12,CUP,SUM,0,0,0,0,0,23,0,10.375442028 +12,SPOON,SUM,0,0,0,0,0,203,12,32.2585580349 +12,,SUM,0,0,0,0,0,233,12,54.2319889069 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,4,577,14,55.1915140152 +13,CUP,SUM,1,0,1,0,0,404,109,0 +13,SPOON,SUM,0,0,0,0,0,226,0,28.9687600136 +13,,SUM,1,0,1,0,4,1207,123,84.1602740288 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,0,31,2,12.5057330132 +14,CUP,SUM,0,0,0,0,2,159,36,61.9088339806 +14,SPOON,SUM,0,0,0,0,0,6,5,18.6679899693 +14,,SUM,0,0,0,0,2,196,43,93.082556963 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,1,0,1,0,84,700,3,0 +15,CUP,SUM,1,1,0,0,392,115,0,0 +15,SPOON,SUM,1,1,0,0,240,1079,0,0 +15,,SUM,3,2,1,0,716,1894,3,0 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,1,1,0,0,384,485,0,0 +16,CUP,SUM,1,1,0,0,392,325,0,0 +16,SPOON,SUM,1,1,0,0,216,1083,0,0 +16,,SUM,3,3,0,0,992,1893,0,0 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,1,1,0,0,360,509,0,0 +17,CUP,SUM,1,1,0,0,392,221,0,0 +17,SPOON,SUM,1,1,0,0,392,17,0,0 +17,,SUM,3,3,0,0,1144,747,0,0 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,1,1,0,0,392,110,0,0 +18,CUP,SUM,1,1,0,0,392,129,0,0 +18,SPOON,SUM,1,1,0,0,392,14,0,0 +18,,SUM,3,3,0,0,1176,253,0,0 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,1,1,0,0,392,344,0,0 +19,CUP,SUM,1,1,0,0,392,161,0,0 +19,SPOON,SUM,1,1,0,0,392,12,0,0 +19,,SUM,3,3,0,0,1176,517,0,0 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,1,1,0,0,392,156,0,0 +20,CUP,SUM,1,1,0,0,392,209,0,0 +20,SPOON,SUM,1,1,0,0,392,12,0,0 +20,,SUM,3,3,0,0,1176,377,0,0 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,1,1,0,0,392,457,0,0 +21,CUP,SUM,1,1,0,0,392,98,0,0 +21,SPOON,SUM,1,1,0,0,392,4,0,0 +21,,SUM,3,3,0,0,1176,559,0,0 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,1,1,0,0,392,183,0,0 +22,CUP,SUM,1,1,0,0,392,131,0,0 +22,SPOON,SUM,1,1,0,0,392,10,0,0 +22,,SUM,3,3,0,0,1176,324,0,0 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,4,4,17.9865489006 +23,CUP,SUM,1,0,0,1,0,376,64,0 +23,SPOON,SUM,0,0,0,0,0,2,0,14.1593170166 +23,,SUM,1,0,0,1,0,382,68,32.1458659172 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,0,44,6,15.452037096 +24,CUP,SUM,0,0,0,0,6,50,3,15.1019971371 +24,SPOON,SUM,0,0,0,0,0,134,0,22.0074748993 +24,,SUM,0,0,0,0,6,228,9,52.5615091324 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,0,68,6,15.7103970051 +25,CUP,SUM,1,0,0,1,10,286,76,0 +25,SPOON,SUM,1,0,1,0,0,1582,0,0 +25,,SUM,2,0,1,1,10,1936,82,15.7103970051 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,0,64,0,13.6236720085 +26,CUP,SUM,0,0,0,0,2,147,36,60.0867481232 +26,SPOON,SUM,0,0,0,0,0,191,0,26.0148379803 +26,,SUM,0,0,0,0,2,402,36,99.725258112 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,0,8,0,11.2588799 +27,CUP,SUM,1,0,1,0,6,180,112,0 +27,SPOON,SUM,0,0,0,0,0,92,1,20.354765892 +27,,SUM,1,0,1,0,6,280,113,31.613645792 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,0,20,1,13.0638480186 +28,CUP,SUM,0,0,0,0,6,19,2,11.6449949741 +28,SPOON,SUM,0,0,0,0,0,18,5,18.2292051315 +28,,SUM,0,0,0,0,6,57,8,42.9380481243 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,2,17,6,15.7313051224 +29,CUP,SUM,0,0,0,0,2,118,24,35.5965600014 +29,SPOON,SUM,0,0,0,0,0,11,6,20.6853251457 +29,,SUM,0,0,0,0,4,146,36,72.0131902695 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,0,18,1,13.4433190823 +30,CUP,SUM,0,0,0,0,0,124,32,32.0527329445 +30,SPOON,SUM,0,0,0,0,0,81,0,18.9907758236 +30,,SUM,0,0,0,0,0,223,33,64.4868278503 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,0,13,1,13.1712460518 +31,CUP,SUM,0,0,0,0,0,328,45,83.0861899853 +31,SPOON,SUM,0,0,0,0,112,127,2,70.3562550545 +31,,SUM,0,0,0,0,112,468,48,166.6136910915 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,0,31,0,11.7418000698 +32,CUP,SUM,0,0,0,0,2,297,41,68.1956148148 +32,SPOON,SUM,0,0,0,0,0,248,0,30.7879459858 +32,,SUM,0,0,0,0,2,576,41,110.7253608704 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,10,112,4,21.7984280586 +33,CUP,SUM,0,0,0,0,0,119,29,42.7803280354 +33,SPOON,SUM,0,0,0,0,0,92,1,20.5562231541 +33,,SUM,0,0,0,0,10,323,34,85.134979248 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,0,200,18,32.3039708138 +34,CUP,SUM,1,0,0,1,0,313,69,0 +34,SPOON,SUM,0,0,0,0,0,19,8,19.9411849976 +34,,SUM,1,0,0,1,0,532,95,52.2451558113 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,2,7,0,11.8862679005 +35,CUP,SUM,1,0,0,1,2,351,76,0 +35,SPOON,SUM,0,0,0,0,0,12,10,23.8262009621 +35,,SUM,1,0,0,1,4,370,86,35.7124688625 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,48,47,6,37.8070569038 +36,CUP,SUM,0,0,0,0,0,94,19,22.6875069141 +36,SPOON,SUM,0,0,0,0,0,0,3,15.9145350456 +36,,SUM,0,0,0,0,48,141,28,76.4090988636 +36,,,,,,,,,, +37,,,,,,,,,, +37,BOWL,SUM,0,0,0,0,18,39,0,20.365997076 +37,CUP,SUM,1,0,1,0,0,141,112,0 +37,SPOON,SUM,0,0,0,0,0,579,0,49.8291311264 +37,,SUM,1,0,1,0,18,759,112,70.1951282024 +37,,,,,,,,,, +38,,,,,,,,,, +38,BOWL,SUM,0,0,0,0,0,130,45,51.7008810043 +38,CUP,SUM,0,0,0,0,0,16,1,10.2700431347 +38,SPOON,SUM,0,0,0,0,2,565,0,49.912938118 +38,,SUM,0,0,0,0,2,711,46,111.883862257 +38,,,,,,,,,, +39,,,,,,,,,, +39,BOWL,SUM,0,0,0,0,0,46,1,13.852052927 +39,CUP,SUM,0,0,0,0,0,19,4,10.3664059639 +39,SPOON,SUM,0,0,0,0,0,10,3,16.2343409061 +39,,SUM,0,0,0,0,0,75,8,40.4527997971 +39,,,,,,,,,, +40,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,0,118,12,22.6899430752 +40,CUP,SUM,0,0,0,0,0,23,1,12.0853128433 +40,SPOON,SUM,0,0,0,0,2,75,1,19.7222168446 +40,,SUM,0,0,0,0,2,216,14,54.4974727631 +40,,,,,,,,,, +41,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,0,20,1,13.9601690769 +41,CUP,SUM,1,0,0,1,0,350,63,0 +41,SPOON,SUM,0,0,0,0,6,21,3,21.7226090431 +41,,SUM,1,0,0,1,6,391,67,35.68277812 +41,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,0,312,38,54.6649749279 +42,CUP,SUM,0,0,0,0,0,29,0,10.353954792 +42,SPOON,SUM,0,0,0,0,0,253,1,30.5110430717 +42,,SUM,0,0,0,0,0,594,39,95.5299727917 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,0,20,0,11.5362579823 +43,CUP,SUM,0,0,0,0,0,16,1,10.0291600227 +43,SPOON,SUM,0,0,0,0,0,20,0,14.8164579868 +43,,SUM,0,0,0,0,0,56,1,36.3818759918 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,0,24,0,11.6994330883 +44,CUP,SUM,0,0,0,0,0,113,19,36.3832349777 +44,SPOON,SUM,1,0,1,0,6,1620,0,0 +44,,SUM,1,0,1,0,6,1757,19,48.082668066 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,0,3,2,12.0389969349 +45,CUP,SUM,1,0,1,0,6,187,92,0 +45,SPOON,SUM,0,0,0,0,0,180,1,27.3392848969 +45,,SUM,1,0,1,0,6,370,95,39.3782818317 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,1,0,1,0,0,1050,66,0 +46,CUP,SUM,0,0,0,0,0,3,1,10.0686459541 +46,SPOON,SUM,0,0,0,0,0,598,0,51.5216970444 +46,,SUM,1,0,1,0,0,1651,67,61.5903429985 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,0,0,0,0,60,29,8,44.131300211 +47,CUP,SUM,0,0,0,0,0,1,0,9.92821908 +47,SPOON,SUM,0,0,0,0,0,300,12,39.4132671356 +47,,SUM,0,0,0,0,60,330,20,93.4727864265 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,0,13,0,11.6796460152 +48,CUP,SUM,1,0,0,1,0,295,61,0 +48,SPOON,SUM,0,0,0,0,0,73,6,22.0630369186 +48,,SUM,1,0,0,1,0,381,67,33.7426829338 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,0,15,0,11.7228629589 +49,CUP,SUM,1,0,1,0,10,162,102,0 +49,SPOON,SUM,0,0,0,0,0,58,0,17.4301371574 +49,,SUM,1,0,1,0,10,235,102,29.1530001163 +49,,,,,,,,,, +50,,,,,,,,,, +50,BOWL,SUM,0,0,0,0,0,9,0,11.6872999668 +50,CUP,SUM,0,0,0,0,4,109,38,56.6141109467 +50,SPOON,SUM,0,0,0,0,6,38,3,23.4102621078 +50,,SUM,0,0,0,0,10,156,41,91.7116730213 +50,,,,,,,,,, +51,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,0,4,4,17.3841340542 +51,CUP,SUM,1,0,0,1,0,376,64,0 +51,SPOON,SUM,0,0,0,0,0,2,0,14.2543189526 +51,,SUM,1,0,0,1,0,382,68,31.6384530067 +51,,,,,,,,,, +52,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,0,44,6,15.5866780281 +52,CUP,SUM,0,0,0,0,6,50,3,14.9599990845 +52,SPOON,SUM,0,0,0,0,0,134,0,22.1786410809 +52,,SUM,0,0,0,0,6,228,9,52.7253181934 +52,,,,,,,,,, +53,,,,,,,,,, +53,BOWL,SUM,0,0,0,0,0,68,6,16.0156340599 +53,CUP,SUM,1,0,0,1,10,286,76,0 +53,SPOON,SUM,1,0,1,0,0,1582,0,0 +53,,SUM,2,0,1,1,10,1936,82,16.0156340599 +53,,,,,,,,,, +54,,,,,,,,,, +54,BOWL,SUM,0,0,0,0,0,64,0,13.5570189953 +54,CUP,SUM,0,0,0,0,2,147,36,60.5494840145 +54,SPOON,SUM,0,0,0,0,0,191,0,26.0846810341 +54,,SUM,0,0,0,0,2,402,36,100.1911840439 +54,,,,,,,,,, +55,,,,,,,,,, +55,BOWL,SUM,0,0,0,0,0,8,0,11.1465289593 +55,CUP,SUM,1,0,1,0,6,180,112,0 +55,SPOON,SUM,0,0,0,0,0,92,1,20.3713760376 +55,,SUM,1,0,1,0,6,280,113,31.5179049969 +55,,,,,,,,,, +56,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,0,20,1,13.0493268967 +56,CUP,SUM,0,0,0,0,6,19,2,11.6975929737 +56,SPOON,SUM,0,0,0,0,0,18,5,18.6167509556 +56,,SUM,0,0,0,0,6,57,8,43.363670826 +56,,,,,,,,,, +57,,,,,,,,,, +57,BOWL,SUM,0,0,0,0,2,17,6,15.5500879288 +57,CUP,SUM,0,0,0,0,2,118,24,35.1865830421 +57,SPOON,SUM,0,0,0,0,0,11,6,20.6247479916 +57,,SUM,0,0,0,0,4,146,36,71.3614189625 +57,,,,,,,,,, +58,,,,,,,,,, +58,BOWL,SUM,0,0,0,0,0,18,1,13.140832901 +58,CUP,SUM,0,0,0,0,0,124,32,32.2859358788 +58,SPOON,SUM,0,0,0,0,0,81,0,18.570166111 +58,,SUM,0,0,0,0,0,223,33,63.9969348907 +58,,,,,,,,,, +59,,,,,,,,,, +59,BOWL,SUM,0,0,0,0,0,13,1,12.8498818874 +59,CUP,SUM,0,0,0,0,0,328,45,81.9213840961 +59,SPOON,SUM,0,0,0,0,112,127,2,68.3043138981 +59,,SUM,0,0,0,0,112,468,48,163.0755798817 +59,,,,,,,,,, +60,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,0,31,0,11.9613130093 +60,CUP,SUM,0,0,0,0,2,297,41,67.8048081398 +60,SPOON,SUM,0,0,0,0,0,248,0,30.7647359371 +60,,SUM,0,0,0,0,2,576,41,110.5308570862 +60,,,,,,,,,, +61,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,10,112,4,22.0827338696 +61,CUP,SUM,0,0,0,0,0,119,29,42.2728900909 +61,SPOON,SUM,0,0,0,0,0,92,1,20.5719759464 +61,,SUM,0,0,0,0,10,323,34,84.9275999069 +61,,,,,,,,,, +62,,,,,,,,,, +62,BOWL,SUM,0,0,0,0,0,200,18,32.7966039181 +62,CUP,SUM,1,0,0,1,0,313,69,0 +62,SPOON,SUM,0,0,0,0,0,19,8,19.7628009319 +62,,SUM,1,0,0,1,0,532,95,52.55940485 +62,,,,,,,,,, +63,,,,,,,,,, +63,BOWL,SUM,0,0,0,0,2,7,0,11.8288810253 +63,CUP,SUM,1,0,0,1,2,351,76,0 +63,SPOON,SUM,0,0,0,0,0,12,10,23.5689108372 +63,,SUM,1,0,0,1,4,370,86,35.3977918625 +63,,,,,,,,,, +64,,,,,,,,,, +64,BOWL,SUM,0,0,0,0,48,47,6,36.7325410843 +64,CUP,SUM,0,0,0,0,0,94,19,22.491740942 +64,SPOON,SUM,0,0,0,0,0,0,3,15.8402249813 +64,,SUM,0,0,0,0,48,141,28,75.0645070076 +64,,,,,,,,,, +65,,,,,,,,,, +65,BOWL,SUM,0,0,0,0,18,39,0,20.0774309635 +65,CUP,SUM,1,0,1,0,0,141,112,0 +65,SPOON,SUM,0,0,0,0,0,579,0,49.6421210766 +65,,SUM,1,0,1,0,18,759,112,69.7195520401 +65,,,,,,,,,, +66,,,,,,,,,, +66,BOWL,SUM,0,0,0,0,0,130,45,51.0795099735 +66,CUP,SUM,0,0,0,0,0,16,1,10.125426054 +66,SPOON,SUM,0,0,0,0,2,565,0,49.7774579525 +66,,SUM,0,0,0,0,2,711,46,110.98239398 +66,,,,,,,,,, +67,,,,,,,,,, +67,BOWL,SUM,0,0,0,0,0,46,1,13.7035031319 +67,CUP,SUM,0,0,0,0,0,19,4,10.0991280079 +67,SPOON,SUM,0,0,0,0,0,10,3,16.2029130459 +67,,SUM,0,0,0,0,0,75,8,40.0055441856 +67,,,,,,,,,, +68,,,,,,,,,, +68,BOWL,SUM,0,0,0,0,0,118,12,22.5693049431 +68,CUP,SUM,0,0,0,0,0,23,1,12.1700339317 +68,SPOON,SUM,0,0,0,0,2,75,1,19.6486999989 +68,,SUM,0,0,0,0,2,216,14,54.3880388737 +68,,,,,,,,,, +69,,,,,,,,,, +69,BOWL,SUM,0,0,0,0,0,20,1,13.6157560349 +69,CUP,SUM,1,0,0,1,0,350,63,0 +69,SPOON,SUM,0,0,0,0,6,21,3,21.1453659534 +69,,SUM,1,0,0,1,6,391,67,34.7611219883 +69,,,,,,,,,, +70,,,,,,,,,, +70,BOWL,SUM,0,0,0,0,0,312,38,53.6612739563 +70,CUP,SUM,0,0,0,0,0,29,0,10.0412979126 +70,SPOON,SUM,0,0,0,0,0,253,1,30.0328860283 +70,,SUM,0,0,0,0,0,594,39,93.7354578972 +70,,,,,,,,,, +71,,,,,,,,,, +71,BOWL,SUM,0,0,0,0,0,20,0,11.5580618382 +71,CUP,SUM,0,0,0,0,0,16,1,9.698374033 +71,SPOON,SUM,0,0,0,0,0,20,0,14.6347260475 +71,,SUM,0,0,0,0,0,56,1,35.8911619186 +71,,,,,,,,,, +72,,,,,,,,,, +72,BOWL,SUM,0,0,0,0,0,24,0,11.6807029247 +72,CUP,SUM,0,0,0,0,0,113,19,35.953081131 +72,SPOON,SUM,1,0,1,0,6,1620,0,0 +72,,SUM,1,0,1,0,6,1757,19,47.6337840557 +72,,,,,,,,,, +73,,,,,,,,,, +73,BOWL,SUM,0,0,0,0,0,3,2,12.0411849022 +73,CUP,SUM,1,0,1,0,6,187,92,0 +73,SPOON,SUM,0,0,0,0,0,180,1,26.650220871 +73,,SUM,1,0,1,0,6,370,95,38.6914057732 +73,,,,,,,,,, +74,,,,,,,,,, +74,BOWL,SUM,1,0,1,0,0,1050,66,0 +74,CUP,SUM,0,0,0,0,0,3,1,10.1005499363 +74,SPOON,SUM,0,0,0,0,0,598,0,50.000524044 +74,,SUM,1,0,1,0,0,1651,67,60.1010739803 +74,,,,,,,,,, +75,,,,,,,,,, +75,BOWL,SUM,0,0,0,0,60,29,8,43.5099589825 +75,CUP,SUM,0,0,0,0,0,1,0,9.5015499592 +75,SPOON,SUM,0,0,0,0,0,300,12,38.5782210827 +75,,SUM,0,0,0,0,60,330,20,91.5897300243 +75,,,,,,,,,, +76,,,,,,,,,, +76,BOWL,SUM,0,0,0,0,0,13,0,11.6303219795 +76,CUP,SUM,1,0,0,1,0,295,61,0 +76,SPOON,SUM,0,0,0,0,0,73,6,20.9358510971 +76,,SUM,1,0,0,1,0,381,67,32.5661730766 +76,,,,,,,,,, +77,,,,,,,,,, +77,BOWL,SUM,0,0,0,0,0,15,0,11.3443331718 +77,CUP,SUM,1,0,1,0,10,162,102,0 +77,SPOON,SUM,0,0,0,0,0,58,0,17.7285609245 +77,,SUM,1,0,1,0,10,235,102,29.0728940964 +77,,,,,,,,,, +78,,,,,,,,,, +78,BOWL,SUM,0,0,0,0,0,9,0,11.5396409035 +78,CUP,SUM,0,0,0,0,4,109,38,55.0072579384 +78,SPOON,SUM,0,0,0,0,6,38,3,23.7666709423 +78,,SUM,0,0,0,0,10,156,41,90.3135697842 +78,,,,,,,,,, +79,,,,,,,,,, +79,BOWL,SUM,0,0,0,0,6,14,0,14.0032999516 +79,CUP,SUM,1,0,1,0,2,301,111,0 +79,SPOON,SUM,0,0,0,0,0,68,4,24.7084000111 +79,,SUM,1,0,1,0,8,383,115,38.7116999626 +79,,,,,,,,,, +80,,,,,,,,,, +80,BOWL,SUM,0,0,0,0,0,28,4,13.6302731037 +80,CUP,SUM,0,0,0,0,0,15,4,10.0951089859 +80,SPOON,SUM,0,0,0,0,0,43,2,19.6711711884 +80,,SUM,0,0,0,0,0,86,10,43.396553278 +80,,,,,,,,,, +81,,,,,,,,,, +81,BOWL,SUM,0,0,0,0,0,7,4,13.3311481476 +81,CUP,SUM,1,0,1,0,0,154,110,0 +81,SPOON,SUM,0,0,0,0,0,297,1,33.920386076 +81,,SUM,1,0,1,0,0,458,115,47.2515342236 +81,,,,,,,,,, +82,,,,,,,,,, +82,BOWL,SUM,0,0,0,0,0,130,30,38.7266860008 +82,CUP,SUM,0,0,0,0,2,19,2,10.9589951038 +82,SPOON,SUM,0,0,0,0,0,30,1,16.7482089996 +82,,SUM,0,0,0,0,2,179,33,66.4338901043 +82,,,,,,,,,, +83,,,,,,,,,, +83,BOWL,SUM,0,0,0,0,0,76,8,19.6981830597 +83,CUP,SUM,0,0,0,0,0,41,19,20.0599150658 +83,SPOON,SUM,1,0,1,0,0,1581,0,0 +83,,SUM,1,0,1,0,0,1698,27,39.7580981255 +83,,,,,,,,,, +84,,,,,,,,,, +84,BOWL,SUM,0,0,0,0,0,5,2,11.6427268982 +84,CUP,SUM,0,0,0,0,0,271,41,75.4236929417 +84,SPOON,SUM,0,0,0,0,0,67,0,18.880302906 +84,,SUM,0,0,0,0,0,343,43,105.9467227459 +84,,,,,,,,,, +85,,,,,,,,,, +85,BOWL,SUM,0,0,0,0,0,22,6,15.3808031082 +85,CUP,SUM,0,0,0,0,2,26,2,14.3806319237 +85,SPOON,SUM,1,0,1,0,0,1582,0,0 +85,,SUM,1,0,1,0,2,1630,8,29.7614350319 +85,,,,,,,,,, +86,,,,,,,,,, +86,BOWL,SUM,0,0,0,0,8,59,8,21.2834498882 +86,CUP,SUM,0,0,0,0,0,6,0,9.8115348816 +86,SPOON,SUM,1,0,1,0,0,1042,60,0 +86,,SUM,1,0,1,0,8,1107,68,31.0949847698 +86,,,,,,,,,, +87,,,,,,,,,, +87,BOWL,SUM,0,0,0,0,0,15,4,13.3078758717 +87,CUP,SUM,0,0,0,0,0,8,0,9.9234580994 +87,SPOON,SUM,0,0,0,0,0,65,3,19.988658905 +87,,SUM,0,0,0,0,0,88,7,43.2199928761 +87,,,,,,,,,, +88,,,,,,,,,, +88,BOWL,SUM,0,0,0,0,0,9,0,11.4870281219 +88,CUP,SUM,0,0,0,0,2,30,10,12.8836419582 +88,SPOON,SUM,0,0,0,0,0,5,0,14.8380680084 +88,,SUM,0,0,0,0,2,44,10,39.2087380886 +88,,,,,,,,,, +89,,,,,,,,,, +89,BOWL,SUM,0,0,0,0,0,15,0,11.5031869411 +89,CUP,SUM,0,0,0,0,0,55,22,22.2671821117 +89,SPOON,SUM,1,0,1,0,0,1584,0,0 +89,,SUM,1,0,1,0,0,1654,22,33.7703690529 +89,,,,,,,,,, +90,,,,,,,,,, +90,BOWL,SUM,1,0,1,0,2,260,104,0 +90,CUP,SUM,0,0,0,0,0,4,0,9.6719558239 +90,SPOON,SUM,0,0,0,0,4,76,1,21.8535609245 +90,,SUM,1,0,1,0,6,340,105,31.5255167484 +90,,,,,,,,,, +91,,,,,,,,,, +91,BOWL,SUM,0,0,0,0,2,14,2,12.7860460281 +91,CUP,SUM,1,0,0,1,0,456,79,0 +91,SPOON,SUM,0,0,0,0,0,89,0,19.4682331085 +91,,SUM,1,0,0,1,2,559,81,32.2542791367 +91,,,,,,,,,, +92,,,,,,,,,, +92,BOWL,SUM,0,0,0,0,2,25,2,12.8219339848 +92,CUP,SUM,0,0,0,0,4,26,2,11.4828989506 +92,SPOON,SUM,0,0,0,0,0,1,1,16.220539093 +92,,SUM,0,0,0,0,6,52,5,40.5253720284 +92,,,,,,,,,, +93,,,,,,,,,, +93,BOWL,SUM,0,0,0,0,2,19,0,12.5811200142 +93,CUP,SUM,0,0,0,0,0,6,2,9.893362999 +93,SPOON,SUM,0,0,0,0,0,32,2,19.3086969852 +93,,SUM,0,0,0,0,2,57,4,41.7831799984 +93,,,,,,,,,, +94,,,,,,,,,, +94,BOWL,SUM,0,0,0,0,0,377,40,54.689013958 +94,CUP,SUM,0,0,0,0,0,24,2,13.335709095 +94,SPOON,SUM,0,0,0,0,0,7,4,16.8083639145 +94,,SUM,0,0,0,0,0,408,46,84.8330869675 +94,,,,,,,,,, +95,,,,,,,,,, +95,BOWL,SUM,1,0,1,0,0,1028,62,0 +95,CUP,SUM,0,0,0,0,2,19,14,22.0061190128 +95,SPOON,SUM,0,0,0,0,0,35,0,16.6488230228 +95,,SUM,1,0,1,0,2,1082,76,38.6549420357 +95,,,,,,,,,, +96,,,,,,,,,, +96,BOWL,SUM,0,0,0,0,2,40,0,14.2357728481 +96,CUP,SUM,0,0,0,0,0,4,8,10.4265677929 +96,SPOON,SUM,0,0,0,0,0,163,0,25.0902500153 +96,,SUM,0,0,0,0,2,207,8,49.7525906563 +96,,,,,,,,,, +97,,,,,,,,,, +97,BOWL,SUM,0,0,0,0,0,22,0,11.6213419437 +97,CUP,SUM,0,0,0,0,0,185,40,74.6403999329 +97,SPOON,SUM,0,0,0,0,0,691,0,58.1181781292 +97,,SUM,0,0,0,0,0,898,40,144.3799200058 +97,,,,,,,,,, +98,,,,,,,,,, +98,BOWL,SUM,0,0,0,0,0,35,0,12.4847381115 +98,CUP,SUM,0,0,0,0,0,164,39,64.7407109737 +98,SPOON,SUM,0,0,0,0,0,1,2,15.3070251942 +98,,SUM,0,0,0,0,0,200,41,92.5324742794 +98,,,,,,,,,, +99,,,,,,,,,, +99,BOWL,SUM,0,0,0,0,4,24,7,17.9536929131 +99,CUP,SUM,0,0,0,0,0,65,7,19.4106550217 +99,SPOON,SUM,1,0,1,0,0,1094,58,0 +99,,SUM,1,0,1,0,4,1183,72,37.3643479347 +99,,,,,,,,,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_20_part3.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_20_part3.csv new file mode 100644 index 0000000000..82540aebab --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_20_part3.csv @@ -0,0 +1,603 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,4,4,17.9665620327 +0,CUP,SUM,1,0,0,1,0,376,64,0 +0,SPOON,SUM,0,0,0,0,0,2,0,14.3398399353 +0,,SUM,1,0,0,1,0,382,68,32.306401968 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,0,4,4,18.0704648495 +1,CUP,SUM,1,0,0,1,0,376,64,0 +1,SPOON,SUM,0,0,0,0,0,2,0,14.2434160709 +1,,SUM,1,0,0,1,0,382,68,32.3138809204 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,0,44,6,15.5472581387 +2,CUP,SUM,0,0,0,0,6,50,3,15.3551590443 +2,SPOON,SUM,0,0,0,0,0,134,0,22.173304081 +2,,SUM,0,0,0,0,6,228,9,53.0757212639 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,0,68,6,15.6670660973 +3,CUP,SUM,1,0,0,1,10,286,76,0 +3,SPOON,SUM,1,0,1,0,0,1582,0,0 +3,,SUM,2,0,1,1,10,1936,82,15.6670660973 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,64,0,13.6086158752 +4,CUP,SUM,0,0,0,0,2,147,36,59.9895100594 +4,SPOON,SUM,0,0,0,0,0,191,0,26.1012909412 +4,,SUM,0,0,0,0,2,402,36,99.6994168758 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,0,8,0,11.1851658821 +5,CUP,SUM,1,0,1,0,6,180,112,0 +5,SPOON,SUM,0,0,0,0,0,92,1,20.518089056 +5,,SUM,1,0,1,0,6,280,113,31.7032549381 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,0,20,1,12.8781359196 +6,CUP,SUM,0,0,0,0,6,19,2,11.8152139187 +6,SPOON,SUM,0,0,0,0,0,18,5,18.1728470325 +6,,SUM,0,0,0,0,6,57,8,42.8661968708 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,2,17,6,15.5055339336 +7,CUP,SUM,0,0,0,0,2,118,24,34.7202310562 +7,SPOON,SUM,0,0,0,0,0,11,6,20.7458629608 +7,,SUM,0,0,0,0,4,146,36,70.9716279507 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,0,18,1,13.0994749069 +8,CUP,SUM,0,0,0,0,0,124,32,31.9348919392 +8,SPOON,SUM,0,0,0,0,0,81,0,18.4419300556 +8,,SUM,0,0,0,0,0,223,33,63.4762969017 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,13,1,12.9750478268 +9,CUP,SUM,0,0,0,0,0,328,45,83.051473856 +9,SPOON,SUM,0,0,0,0,112,127,2,69.0299181938 +9,,SUM,0,0,0,0,112,468,48,165.0564398766 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,31,0,11.8930721283 +10,CUP,SUM,0,0,0,0,2,297,41,67.9703400135 +10,SPOON,SUM,0,0,0,0,0,248,0,30.6539649963 +10,,SUM,0,0,0,0,2,576,41,110.5173771381 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,10,112,4,22.0520939827 +11,CUP,SUM,0,0,0,0,0,119,29,42.6874620914 +11,SPOON,SUM,0,0,0,0,0,92,1,20.8660700321 +11,,SUM,0,0,0,0,10,323,34,85.6056261063 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,0,200,18,32.4629518986 +12,CUP,SUM,1,0,0,1,0,313,69,0 +12,SPOON,SUM,0,0,0,0,0,19,8,19.6082561016 +12,,SUM,1,0,0,1,0,532,95,52.0712080002 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,2,7,0,11.7631111145 +13,CUP,SUM,1,0,0,1,2,351,76,0 +13,SPOON,SUM,0,0,0,0,0,12,10,24.1530570984 +13,,SUM,1,0,0,1,4,370,86,35.9161682129 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,48,47,6,37.3584079742 +14,CUP,SUM,0,0,0,0,0,94,19,22.3555748463 +14,SPOON,SUM,0,0,0,0,0,0,3,16.2058889866 +14,,SUM,0,0,0,0,48,141,28,75.9198718071 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,18,39,0,20.4042069912 +15,CUP,SUM,1,0,1,0,0,141,112,0 +15,SPOON,SUM,0,0,0,0,0,579,0,49.8579838276 +15,,SUM,1,0,1,0,18,759,112,70.2621908188 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,130,45,51.4544239044 +16,CUP,SUM,0,0,0,0,0,16,1,9.9946908951 +16,SPOON,SUM,0,0,0,0,2,565,0,49.6814899445 +16,,SUM,0,0,0,0,2,711,46,111.130604744 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,0,46,1,13.6167509556 +17,CUP,SUM,0,0,0,0,0,19,4,10.2848551273 +17,SPOON,SUM,0,0,0,0,0,10,3,16.5248339176 +17,,SUM,0,0,0,0,0,75,8,40.4264400005 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,0,118,12,22.6713988781 +18,CUP,SUM,0,0,0,0,0,23,1,12.0091910362 +18,SPOON,SUM,0,0,0,0,2,75,1,19.7313740253 +18,,SUM,0,0,0,0,2,216,14,54.4119639397 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,20,1,13.6122250557 +19,CUP,SUM,1,0,0,1,0,350,63,0 +19,SPOON,SUM,0,0,0,0,6,21,3,21.4678518772 +19,,SUM,1,0,0,1,6,391,67,35.0800769329 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,0,312,38,54.0403628349 +20,CUP,SUM,0,0,0,0,0,29,0,10.1752541065 +20,SPOON,SUM,0,0,0,0,0,253,1,30.9475231171 +20,,SUM,0,0,0,0,0,594,39,95.1631400585 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,20,0,11.6307239532 +21,CUP,SUM,0,0,0,0,0,16,1,9.8498439789 +21,SPOON,SUM,0,0,0,0,0,20,0,14.8512179852 +21,,SUM,0,0,0,0,0,56,1,36.3317859173 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,0,24,0,11.802421093 +22,CUP,SUM,0,0,0,0,0,113,19,36.2593369484 +22,SPOON,SUM,1,0,1,0,6,1620,0,0 +22,,SUM,1,0,1,0,6,1757,19,48.0617580414 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,3,2,12.0586130619 +23,CUP,SUM,1,0,1,0,6,187,92,0 +23,SPOON,SUM,0,0,0,0,0,180,1,26.9703068733 +23,,SUM,1,0,1,0,6,370,95,39.0289199352 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,1,0,1,0,0,1050,66,0 +24,CUP,SUM,0,0,0,0,0,3,1,10.1964111328 +24,SPOON,SUM,0,0,0,0,0,598,0,50.8387510777 +24,,SUM,1,0,1,0,0,1651,67,61.0351622105 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,60,29,8,43.481495142 +25,CUP,SUM,0,0,0,0,0,1,0,9.5833201408 +25,SPOON,SUM,0,0,0,0,0,300,12,38.475921154 +25,,SUM,0,0,0,0,60,330,20,91.5407364368 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,0,13,0,11.4925649166 +26,CUP,SUM,1,0,0,1,0,295,61,0 +26,SPOON,SUM,0,0,0,0,0,73,6,21.0923130512 +26,,SUM,1,0,0,1,0,381,67,32.5848779678 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,0,15,0,11.6437530518 +27,CUP,SUM,1,0,1,0,10,162,102,0 +27,SPOON,SUM,0,0,0,0,0,58,0,18.384898901 +27,,SUM,1,0,1,0,10,235,102,30.0286519527 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,0,9,0,11.7749979496 +28,CUP,SUM,0,0,0,0,4,109,38,54.5871119499 +28,SPOON,SUM,0,0,0,0,6,38,3,23.5913779736 +28,,SUM,0,0,0,0,10,156,41,89.9534878731 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,6,14,0,13.9990770817 +29,CUP,SUM,1,0,1,0,2,301,111,0 +29,SPOON,SUM,0,0,0,0,0,68,4,25.1744601727 +29,,SUM,1,0,1,0,8,383,115,39.1735372543 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,0,28,4,13.9778909683 +30,CUP,SUM,0,0,0,0,0,15,4,9.9677500725 +30,SPOON,SUM,0,0,0,0,0,43,2,20.0747950077 +30,,SUM,0,0,0,0,0,86,10,44.0204360485 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,0,7,4,13.2962901592 +31,CUP,SUM,1,0,1,0,0,154,110,0 +31,SPOON,SUM,0,0,0,0,0,297,1,34.2360138893 +31,,SUM,1,0,1,0,0,458,115,47.5323040485 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,0,130,30,38.6352977753 +32,CUP,SUM,0,0,0,0,2,19,2,10.7413878441 +32,SPOON,SUM,0,0,0,0,0,30,1,16.8208289146 +32,,SUM,0,0,0,0,2,179,33,66.197514534 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,76,8,19.8660299778 +33,CUP,SUM,0,0,0,0,0,41,19,19.8795149326 +33,SPOON,SUM,1,0,1,0,0,1581,0,0 +33,,SUM,1,0,1,0,0,1698,27,39.7455449104 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,0,5,2,11.6120948792 +34,CUP,SUM,0,0,0,0,0,271,41,75.6681790352 +34,SPOON,SUM,0,0,0,0,0,67,0,18.5806698799 +34,,SUM,0,0,0,0,0,343,43,105.8609437943 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,0,22,6,14.9572758675 +35,CUP,SUM,0,0,0,0,2,26,2,14.1076500416 +35,SPOON,SUM,1,0,1,0,0,1582,0,0 +35,,SUM,1,0,1,0,2,1630,8,29.064925909 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,8,59,8,21.3512420654 +36,CUP,SUM,0,0,0,0,0,6,0,9.497426033 +36,SPOON,SUM,1,0,1,0,0,1042,60,0 +36,,SUM,1,0,1,0,8,1107,68,30.8486680984 +36,,,,,,,,,, +37,,,,,,,,,, +37,BOWL,SUM,0,0,0,0,0,15,4,13.649189949 +37,CUP,SUM,0,0,0,0,0,8,0,9.9583148956 +37,SPOON,SUM,0,0,0,0,0,65,3,20.3759460449 +37,,SUM,0,0,0,0,0,88,7,43.9834508896 +37,,,,,,,,,, +38,,,,,,,,,, +38,BOWL,SUM,0,0,0,0,0,9,0,11.4634721279 +38,CUP,SUM,0,0,0,0,2,30,10,12.9098501205 +38,SPOON,SUM,0,0,0,0,0,5,0,14.8684310913 +38,,SUM,0,0,0,0,2,44,10,39.2417533398 +38,,,,,,,,,, +39,,,,,,,,,, +39,BOWL,SUM,0,0,0,0,0,15,0,11.548500061 +39,CUP,SUM,0,0,0,0,0,55,22,22.106115818 +39,SPOON,SUM,1,0,1,0,0,1584,0,0 +39,,SUM,1,0,1,0,0,1654,22,33.6546158791 +39,,,,,,,,,, +40,,,,,,,,,, +40,BOWL,SUM,1,0,1,0,2,260,104,0 +40,CUP,SUM,0,0,0,0,0,4,0,9.9318370819 +40,SPOON,SUM,0,0,0,0,4,76,1,21.5294780731 +40,,SUM,1,0,1,0,6,340,105,31.461315155 +40,,,,,,,,,, +41,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,2,14,2,12.6338479519 +41,CUP,SUM,1,0,0,1,0,456,79,0 +41,SPOON,SUM,0,0,0,0,0,89,0,19.801060915 +41,,SUM,1,0,0,1,2,559,81,32.4349088669 +41,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,2,25,2,12.8060359955 +42,CUP,SUM,0,0,0,0,4,26,2,11.5698111057 +42,SPOON,SUM,0,0,0,0,0,1,1,16.0264339447 +42,,SUM,0,0,0,0,6,52,5,40.4022810459 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,2,19,0,12.4208700657 +43,CUP,SUM,0,0,0,0,0,6,2,9.8352777958 +43,SPOON,SUM,0,0,0,0,0,32,2,19.2077829838 +43,,SUM,0,0,0,0,2,57,4,41.4639308453 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,0,377,40,54.6933209896 +44,CUP,SUM,0,0,0,0,0,24,2,13.6135640144 +44,SPOON,SUM,0,0,0,0,0,7,4,16.8292071819 +44,,SUM,0,0,0,0,0,408,46,85.136092186 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,1,0,1,0,0,1028,62,0 +45,CUP,SUM,0,0,0,0,2,19,14,21.8966228962 +45,SPOON,SUM,0,0,0,0,0,35,0,16.8442909718 +45,,SUM,1,0,1,0,2,1082,76,38.740913868 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,2,40,0,14.4304690361 +46,CUP,SUM,0,0,0,0,0,4,8,10.4147460461 +46,SPOON,SUM,0,0,0,0,0,163,0,24.7370789051 +46,,SUM,0,0,0,0,2,207,8,49.5822939873 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,0,0,0,0,0,22,0,12.0959239006 +47,CUP,SUM,0,0,0,0,0,185,40,75.3007900715 +47,SPOON,SUM,0,0,0,0,0,691,0,57.7562820911 +47,,SUM,0,0,0,0,0,898,40,145.1529960632 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,0,35,0,12.8956489563 +48,CUP,SUM,0,0,0,0,0,164,39,64.4695019722 +48,SPOON,SUM,0,0,0,0,0,1,2,15.2887618542 +48,,SUM,0,0,0,0,0,200,41,92.6539127827 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,4,24,7,17.9779088497 +49,CUP,SUM,0,0,0,0,0,65,7,19.5386629105 +49,SPOON,SUM,1,0,1,0,0,1094,58,0 +49,,SUM,1,0,1,0,4,1183,72,37.5165717602 +49,,,,,,,,,, +50,,,,,,,,,, +50,BOWL,SUM,0,0,0,0,0,32,0,12.3107581139 +50,CUP,SUM,0,0,0,0,0,21,4,10.3289299011 +50,SPOON,SUM,0,0,0,0,0,93,0,19.349615097 +50,,SUM,0,0,0,0,0,146,4,41.989303112 +50,,,,,,,,,, +51,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,2,45,2,14.6562719345 +51,CUP,SUM,0,0,0,0,0,10,4,12.0897271633 +51,SPOON,SUM,1,0,1,0,0,979,66,0 +51,,SUM,1,0,1,0,2,1034,72,26.7459990978 +51,,,,,,,,,, +52,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,0,2,0,11.5599458218 +52,CUP,SUM,0,0,0,0,0,21,0,10.113188982 +52,SPOON,SUM,0,0,0,0,0,398,0,39.3499240875 +52,,SUM,0,0,0,0,0,421,0,61.0230588913 +52,,,,,,,,,, +53,,,,,,,,,, +53,BOWL,SUM,0,0,0,0,4,32,0,13.4702711105 +53,CUP,SUM,0,0,0,0,4,34,12,18.7248239517 +53,SPOON,SUM,0,0,0,0,0,242,3,33.5070590973 +53,,SUM,0,0,0,0,8,308,15,65.7021541595 +53,,,,,,,,,, +54,,,,,,,,,, +54,BOWL,SUM,0,0,0,0,0,41,2,12.8112750053 +54,CUP,SUM,0,0,0,0,2,36,3,12.6452968121 +54,SPOON,SUM,0,0,0,0,0,290,1,33.940926075 +54,,SUM,0,0,0,0,2,367,6,59.3974978924 +54,,,,,,,,,, +55,,,,,,,,,, +55,BOWL,SUM,0,0,0,0,0,29,0,12.6330690384 +55,CUP,SUM,0,0,0,0,6,9,6,12.5725870132 +55,SPOON,SUM,0,0,0,0,0,0,1,16.3611271381 +55,,SUM,0,0,0,0,6,38,7,41.5667831898 +55,,,,,,,,,, +56,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,6,283,37,52.5904459953 +56,CUP,SUM,0,0,0,0,2,93,18,35.4763438702 +56,SPOON,SUM,0,0,0,0,0,12,0,14.9759747982 +56,,SUM,0,0,0,0,8,388,55,103.0427646637 +56,,,,,,,,,, +57,,,,,,,,,, +57,BOWL,SUM,0,0,0,0,2,69,0,14.5854730606 +57,CUP,SUM,0,0,0,0,0,242,55,81.1201720238 +57,SPOON,SUM,0,0,0,0,0,0,0,14.4985771179 +57,,SUM,0,0,0,0,2,311,55,110.2042222023 +57,,,,,,,,,, +58,,,,,,,,,, +58,BOWL,SUM,0,0,0,0,0,334,16,39.8686649799 +58,CUP,SUM,0,0,0,0,0,14,7,13.4141201973 +58,SPOON,SUM,0,0,0,0,0,7,1,16.8002650738 +58,,SUM,0,0,0,0,0,355,24,70.083050251 +58,,,,,,,,,, +59,,,,,,,,,, +59,BOWL,SUM,0,0,0,0,0,9,0,11.8364992142 +59,CUP,SUM,0,0,0,0,0,6,6,12.0365111828 +59,SPOON,SUM,1,0,1,0,0,1583,0,0 +59,,SUM,1,0,1,0,0,1598,6,23.873010397 +59,,,,,,,,,, +60,,,,,,,,,, +60,BOWL,SUM,1,0,1,0,0,879,74,0 +60,CUP,SUM,0,0,0,0,0,15,6,10.7048430443 +60,SPOON,SUM,0,0,0,0,0,5,0,15.0784928799 +60,,SUM,1,0,1,0,0,899,80,25.7833359241 +60,,,,,,,,,, +61,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,0,12,0,11.7919099331 +61,CUP,SUM,0,0,0,0,0,226,33,53.0148041248 +61,SPOON,SUM,0,0,0,0,0,446,1,42.3760869503 +61,,SUM,0,0,0,0,0,684,34,107.1828010082 +61,,,,,,,,,, +62,,,,,,,,,, +62,BOWL,SUM,0,0,0,0,0,10,1,11.9376859665 +62,CUP,SUM,0,0,0,0,0,59,3,11.4830100536 +62,SPOON,SUM,0,0,0,0,0,529,0,48.136480093 +62,,SUM,0,0,0,0,0,598,4,71.5571761131 +62,,,,,,,,,, +63,,,,,,,,,, +63,BOWL,SUM,0,0,0,0,0,35,1,13.5980269909 +63,CUP,SUM,0,0,0,0,0,15,13,15.5711379051 +63,SPOON,SUM,0,0,0,0,0,660,8,63.087667942 +63,,SUM,0,0,0,0,0,710,22,92.2568328381 +63,,,,,,,,,, +64,,,,,,,,,, +64,BOWL,SUM,0,0,0,0,16,28,2,20.0877521038 +64,CUP,SUM,1,0,0,1,0,198,68,0 +64,SPOON,SUM,0,0,0,0,6,221,1,30.5904140472 +64,,SUM,1,0,0,1,22,447,71,50.678166151 +64,,,,,,,,,, +65,,,,,,,,,, +65,BOWL,SUM,0,0,0,0,0,15,2,11.9659068584 +65,CUP,SUM,1,0,0,1,0,330,73,0 +65,SPOON,SUM,0,0,0,0,0,0,0,14.8239898682 +65,,SUM,1,0,0,1,0,345,75,26.7898967266 +65,,,,,,,,,, +66,,,,,,,,,, +66,BOWL,SUM,0,0,0,0,0,11,0,11.7631139755 +66,CUP,SUM,0,0,0,0,0,29,15,14.2454571724 +66,SPOON,SUM,0,0,0,0,0,1,0,15.0633888245 +66,,SUM,0,0,0,0,0,41,15,41.0719599724 +66,,,,,,,,,, +67,,,,,,,,,, +67,BOWL,SUM,0,0,0,0,0,14,0,11.7119889259 +67,CUP,SUM,0,0,0,0,0,46,7,15.6281819344 +67,SPOON,SUM,0,0,0,0,0,3,4,16.647331953 +67,,SUM,0,0,0,0,0,63,11,43.9875028133 +67,,,,,,,,,, +68,,,,,,,,,, +68,BOWL,SUM,0,0,0,0,0,46,9,19.1112270355 +68,CUP,SUM,1,0,1,0,0,773,80,0 +68,SPOON,SUM,0,0,0,0,0,3,0,15.0612370968 +68,,SUM,1,0,1,0,0,822,89,34.1724641323 +68,,,,,,,,,, +69,,,,,,,,,, +69,BOWL,SUM,0,0,0,0,2,62,0,14.9018571377 +69,CUP,SUM,0,0,0,0,0,28,19,20.2483310699 +69,SPOON,SUM,0,0,0,0,0,26,1,17.1401529312 +69,,SUM,0,0,0,0,2,116,20,52.2903411388 +69,,,,,,,,,, +70,,,,,,,,,, +70,BOWL,SUM,0,0,0,0,0,12,1,13.3257579803 +70,CUP,SUM,1,0,1,0,54,604,105,0 +70,SPOON,SUM,0,0,0,0,0,166,0,23.7965209484 +70,,SUM,1,0,1,0,54,782,106,37.1222789288 +70,,,,,,,,,, +71,,,,,,,,,, +71,BOWL,SUM,0,0,0,0,0,10,0,11.9312808514 +71,CUP,SUM,0,0,0,0,0,22,7,11.1102020741 +71,SPOON,SUM,0,0,0,0,0,18,2,15.5092289448 +71,,SUM,0,0,0,0,0,50,9,38.5507118702 +71,,,,,,,,,, +72,,,,,,,,,, +72,BOWL,SUM,0,0,0,0,0,20,1,12.3138968945 +72,CUP,SUM,0,0,0,0,0,20,4,10.3181698322 +72,SPOON,SUM,0,0,0,0,0,244,2,32.6133410931 +72,,SUM,0,0,0,0,0,284,7,55.2454078197 +72,,,,,,,,,, +73,,,,,,,,,, +73,BOWL,SUM,0,0,0,0,0,6,2,11.7295517921 +73,CUP,SUM,0,0,0,0,0,20,8,15.5202109814 +73,SPOON,SUM,0,0,0,0,0,100,1,21.9993929863 +73,,SUM,0,0,0,0,0,126,11,49.2491557598 +73,,,,,,,,,, +74,,,,,,,,,, +74,BOWL,SUM,0,0,0,0,2,4,2,12.5451159477 +74,CUP,SUM,0,0,0,0,0,11,10,10.6562299728 +74,SPOON,SUM,0,0,0,0,2,64,40,48.8181138039 +74,,SUM,0,0,0,0,4,79,52,72.0194597244 +74,,,,,,,,,, +75,,,,,,,,,, +75,BOWL,SUM,0,0,0,0,0,10,1,13.3668880463 +75,CUP,SUM,0,0,0,0,2,8,3,10.6701698303 +75,SPOON,SUM,0,0,0,0,4,8,1,18.5508010387 +75,,SUM,0,0,0,0,6,26,5,42.5878589153 +75,,,,,,,,,, +76,,,,,,,,,, +76,BOWL,SUM,0,0,0,0,0,8,0,11.7406740189 +76,CUP,SUM,0,0,0,0,0,12,4,10.2185790539 +76,SPOON,SUM,0,0,0,0,0,12,0,15.1485340595 +76,,SUM,0,0,0,0,0,32,4,37.1077871323 +76,,,,,,,,,, +77,,,,,,,,,, +77,BOWL,SUM,0,0,0,0,0,19,4,13.9083070755 +77,CUP,SUM,0,0,0,0,2,14,2,10.8441748619 +77,SPOON,SUM,0,0,0,0,6,67,0,21.1733288765 +77,,SUM,0,0,0,0,8,100,6,45.9258108139 +77,,,,,,,,,, +78,,,,,,,,,, +78,BOWL,SUM,0,0,0,0,2,29,0,13.115516901 +78,CUP,SUM,0,0,0,0,0,11,7,10.6264629364 +78,SPOON,SUM,0,0,0,0,0,1,2,18.098692894 +78,,SUM,0,0,0,0,2,41,9,41.8406727314 +78,,,,,,,,,, +79,,,,,,,,,, +79,BOWL,SUM,0,0,0,0,2,12,9,19.3764929771 +79,CUP,SUM,0,0,0,0,0,46,2,11.3849699497 +79,SPOON,SUM,0,0,0,0,0,270,2,34.6294691563 +79,,SUM,0,0,0,0,2,328,13,65.3909320831 +79,,,,,,,,,, +80,,,,,,,,,, +80,BOWL,SUM,0,0,0,0,0,9,0,11.5767068863 +80,CUP,SUM,0,0,0,0,0,33,7,18.4225821495 +80,SPOON,SUM,0,0,0,0,0,827,2,67.2016119957 +80,,SUM,0,0,0,0,0,869,9,97.2009010315 +80,,,,,,,,,, +81,,,,,,,,,, +81,BOWL,SUM,0,0,0,0,0,1,0,11.4335308075 +81,CUP,SUM,0,0,0,0,0,28,6,11.2482221127 +81,SPOON,SUM,0,0,0,0,0,27,1,17.0307819843 +81,,SUM,0,0,0,0,0,56,7,39.7125349045 +81,,,,,,,,,, +82,,,,,,,,,, +82,BOWL,SUM,0,0,0,0,0,23,2,12.3898961544 +82,CUP,SUM,0,0,0,0,10,56,0,15.7824487686 +82,SPOON,SUM,0,0,0,0,0,13,0,14.7514340878 +82,,SUM,0,0,0,0,10,92,2,42.9237790108 +82,,,,,,,,,, +83,,,,,,,,,, +83,BOWL,SUM,0,0,0,0,0,29,0,12.2028250694 +83,CUP,SUM,0,0,0,0,0,25,0,10.3998858929 +83,SPOON,SUM,0,0,0,0,0,403,1,40.6251540184 +83,,SUM,0,0,0,0,0,457,1,63.2278649807 +83,,,,,,,,,, +84,,,,,,,,,, +84,BOWL,SUM,0,0,0,0,0,4,4,16.9721131325 +84,CUP,SUM,1,0,0,1,0,376,64,0 +84,SPOON,SUM,0,0,0,0,0,2,0,14.1363210678 +84,,SUM,1,0,0,1,0,382,68,31.1084342003 +84,,,,,,,,,, +85,,,,,,,,,, +85,BOWL,SUM,0,0,0,0,0,44,6,15.589192152 +85,CUP,SUM,0,0,0,0,6,50,3,15.3233549595 +85,SPOON,SUM,0,0,0,0,0,134,0,22.1685829163 +85,,SUM,0,0,0,0,6,228,9,53.0811300278 +85,,,,,,,,,, +86,,,,,,,,,, +86,BOWL,SUM,0,0,0,0,0,68,6,16.0662128925 +86,CUP,SUM,1,0,0,1,10,286,76,0 +86,SPOON,SUM,1,0,1,0,0,1582,0,0 +86,,SUM,2,0,1,1,10,1936,82,16.0662128925 +86,,,,,,,,,, +87,,,,,,,,,, +87,BOWL,SUM,0,0,0,0,0,64,0,13.6851501465 +87,CUP,SUM,0,0,0,0,2,147,36,60.5689549446 +87,SPOON,SUM,0,0,0,0,0,191,0,26.4575388432 +87,,SUM,0,0,0,0,2,402,36,100.7116439343 +87,,,,,,,,,, +88,,,,,,,,,, +88,BOWL,SUM,0,0,0,0,0,8,0,11.0679039955 +88,CUP,SUM,1,0,1,0,6,180,112,0 +88,SPOON,SUM,0,0,0,0,0,92,1,20.5594909191 +88,,SUM,1,0,1,0,6,280,113,31.6273949146 +88,,,,,,,,,, +89,,,,,,,,,, +89,BOWL,SUM,0,0,0,0,0,20,1,13.0936729908 +89,CUP,SUM,0,0,0,0,6,19,2,11.66654706 +89,SPOON,SUM,0,0,0,0,0,18,5,18.1729969978 +89,,SUM,0,0,0,0,6,57,8,42.9332170486 +89,,,,,,,,,, +90,,,,,,,,,, +90,BOWL,SUM,0,0,0,0,2,17,6,15.6415879726 +90,CUP,SUM,0,0,0,0,2,118,24,34.7105271816 +90,SPOON,SUM,0,0,0,0,0,11,6,20.910670042 +90,,SUM,0,0,0,0,4,146,36,71.2627851963 +90,,,,,,,,,, +91,,,,,,,,,, +91,BOWL,SUM,0,0,0,0,0,18,1,12.9816060066 +91,CUP,SUM,0,0,0,0,0,124,32,31.8834798336 +91,SPOON,SUM,0,0,0,0,0,81,0,18.4098072052 +91,,SUM,0,0,0,0,0,223,33,63.2748930454 +91,,,,,,,,,, +92,,,,,,,,,, +92,BOWL,SUM,0,0,0,0,0,13,1,13.0251541138 +92,CUP,SUM,0,0,0,0,0,328,45,81.9705181122 +92,SPOON,SUM,0,0,0,0,112,127,2,69.0247840881 +92,,SUM,0,0,0,0,112,468,48,164.0204563141 +92,,,,,,,,,, +93,,,,,,,,,, +93,BOWL,SUM,0,0,0,0,0,31,0,11.6571497917 +93,CUP,SUM,0,0,0,0,2,297,41,68.2016000748 +93,SPOON,SUM,0,0,0,0,0,248,0,30.5981471539 +93,,SUM,0,0,0,0,2,576,41,110.4568970203 +93,,,,,,,,,, +94,,,,,,,,,, +94,BOWL,SUM,0,0,0,0,10,112,4,22.074422121 +94,CUP,SUM,0,0,0,0,0,119,29,42.5735290051 +94,SPOON,SUM,0,0,0,0,0,92,1,20.6939749718 +94,,SUM,0,0,0,0,10,323,34,85.3419260979 +94,,,,,,,,,, +95,,,,,,,,,, +95,BOWL,SUM,0,0,0,0,0,200,18,32.7253510952 +95,CUP,SUM,1,0,0,1,0,313,69,0 +95,SPOON,SUM,0,0,0,0,0,19,8,19.6441230774 +95,,SUM,1,0,0,1,0,532,95,52.3694741726 +95,,,,,,,,,, +96,,,,,,,,,, +96,BOWL,SUM,0,0,0,0,2,7,0,11.8494298458 +96,CUP,SUM,1,0,0,1,2,351,76,0 +96,SPOON,SUM,0,0,0,0,0,12,10,23.7234399319 +96,,SUM,1,0,0,1,4,370,86,35.5728697777 +96,,,,,,,,,, +97,,,,,,,,,, +97,BOWL,SUM,0,0,0,0,48,47,6,37.6059119701 +97,CUP,SUM,0,0,0,0,0,94,19,22.1575489044 +97,SPOON,SUM,0,0,0,0,0,0,3,15.8385570049 +97,,SUM,0,0,0,0,48,141,28,75.6020178795 +97,,,,,,,,,, +98,,,,,,,,,, +98,BOWL,SUM,0,0,0,0,18,39,0,20.4696741104 +98,CUP,SUM,1,0,1,0,0,141,112,0 +98,SPOON,SUM,0,0,0,0,0,579,0,49.3665218353 +98,,SUM,1,0,1,0,18,759,112,69.8361959457 +98,,,,,,,,,, +99,,,,,,,,,, +99,BOWL,SUM,0,0,0,0,0,130,45,50.3411848545 +99,CUP,SUM,0,0,0,0,0,16,1,9.992442131 +99,SPOON,SUM,0,0,0,0,2,565,0,49.2091858387 +99,,SUM,0,0,0,0,2,711,46,109.5428128243 +99,,,,,,,,,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_20_part4.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_20_part4.csv new file mode 100644 index 0000000000..9d0fb01f5a --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_20_part4.csv @@ -0,0 +1,603 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,0,4,4,16.89774799346924 +0,CUP,SUM,1,0,0,1,0,376,64,0.0 +0,SPOON,SUM,0,0,0,0,0,2,0,14.270568132400513 +0,,SUM,1,0,0,1,0,382,68,31.16831612586975 +0,, +1,, +1,BOWL,SUM,0,0,0,0,0,44,6,15.206226110458374 +1,CUP,SUM,0,0,0,0,6,50,3,15.222028017044067 +1,SPOON,SUM,0,0,0,0,0,134,0,22.234689950942993 +1,,SUM,0,0,0,0,6,228,9,52.662944078445435 +1,, +2,, +2,BOWL,SUM,0,0,0,0,0,68,6,15.866705894470215 +2,CUP,SUM,1,0,0,1,10,286,76,0.0 +2,SPOON,SUM,1,0,1,0,0,1582,0,0.0 +2,,SUM,2,0,1,1,10,1936,82,15.866705894470215 +2,, +3,, +3,BOWL,SUM,0,0,0,0,0,64,0,13.707629919052124 +3,CUP,SUM,0,0,0,0,2,147,36,60.25859093666077 +3,SPOON,SUM,0,0,0,0,0,191,0,26.014806032180786 +3,,SUM,0,0,0,0,2,402,36,99.98102688789368 +3,, +4,, +4,BOWL,SUM,0,0,0,0,0,8,0,11.322266101837158 +4,CUP,SUM,1,0,1,0,6,180,112,0.0 +4,SPOON,SUM,0,0,0,0,0,92,1,20.487957000732422 +4,,SUM,1,0,1,0,6,280,113,31.81022310256958 +4,, +5,, +5,BOWL,SUM,0,0,0,0,0,20,1,13.105713844299316 +5,CUP,SUM,0,0,0,0,6,19,2,11.934908866882324 +5,SPOON,SUM,0,0,0,0,0,18,5,18.34707498550415 +5,,SUM,0,0,0,0,6,57,8,43.38769769668579 +5,, +6,, +6,BOWL,SUM,0,0,0,0,2,17,6,15.733175039291382 +6,CUP,SUM,0,0,0,0,2,118,24,35.40230894088745 +6,SPOON,SUM,0,0,0,0,0,11,6,20.50698709487915 +6,,SUM,0,0,0,0,4,146,36,71.64247107505798 +6,, +7,, +7,BOWL,SUM,0,0,0,0,0,18,1,13.045003175735474 +7,CUP,SUM,0,0,0,0,0,124,32,32.49764394760132 +7,SPOON,SUM,0,0,0,0,0,81,0,18.716569185256958 +7,,SUM,0,0,0,0,0,223,33,64.25921630859375 +7,, +8,, +8,BOWL,SUM,0,0,0,0,0,13,1,13.172540187835693 +8,CUP,SUM,0,0,0,0,0,328,45,82.3256368637085 +8,SPOON,SUM,0,0,0,0,112,127,2,69.49931383132935 +8,,SUM,0,0,0,0,112,468,48,164.99749088287354 +8,, +9,, +9,BOWL,SUM,0,0,0,0,0,31,0,11.937978029251099 +9,CUP,SUM,0,0,0,0,2,297,41,68.05152082443237 +9,SPOON,SUM,0,0,0,0,0,248,0,30.65803098678589 +9,,SUM,0,0,0,0,2,576,41,110.64752984046936 +9,, +10,, +10,BOWL,SUM,0,0,0,0,10,112,4,22.21153998374939 +10,CUP,SUM,0,0,0,0,0,119,29,42.734313011169434 +10,SPOON,SUM,0,0,0,0,0,92,1,20.727313995361328 +10,,SUM,0,0,0,0,10,323,34,85.67316699028015 +10,, +11,, +11,BOWL,SUM,0,0,0,0,0,200,18,32.719095945358276 +11,CUP,SUM,1,0,0,1,0,313,69,0.0 +11,SPOON,SUM,0,0,0,0,0,19,8,20.077482223510742 +11,,SUM,1,0,0,1,0,532,95,52.79657816886902 +11,, +12,, +12,BOWL,SUM,0,0,0,0,2,7,0,11.869009017944336 +12,CUP,SUM,1,0,0,1,2,351,76,0.0 +12,SPOON,SUM,0,0,0,0,0,12,10,23.63521409034729 +12,,SUM,1,0,0,1,4,370,86,35.504223108291626 +12,, +13,, +13,BOWL,SUM,0,0,0,0,48,47,6,37.208247900009155 +13,CUP,SUM,0,0,0,0,0,94,19,22.560287952423096 +13,SPOON,SUM,0,0,0,0,0,0,3,16.053761959075928 +13,,SUM,0,0,0,0,48,141,28,75.82229781150818 +13,, +14,, +14,BOWL,SUM,0,0,0,0,18,39,0,20.294800996780396 +14,CUP,SUM,1,0,1,0,0,141,112,0.0 +14,SPOON,SUM,0,0,0,0,0,579,0,49.32585883140564 +14,,SUM,1,0,1,0,18,759,112,69.62065982818604 +14,, +15,, +15,BOWL,SUM,0,0,0,0,0,130,45,51.30858516693115 +15,CUP,SUM,0,0,0,0,0,16,1,10.05887508392334 +15,SPOON,SUM,0,0,0,0,2,565,0,49.49330401420593 +15,,SUM,0,0,0,0,2,711,46,110.86076426506042 +15,, +16,, +16,BOWL,SUM,0,0,0,0,0,46,1,13.87024712562561 +16,CUP,SUM,0,0,0,0,0,19,4,10.47815489768982 +16,SPOON,SUM,0,0,0,0,0,10,3,16.449827909469604 +16,,SUM,0,0,0,0,0,75,8,40.798229932785034 +16,, +17,, +17,BOWL,SUM,0,0,0,0,0,118,12,22.62634301185608 +17,CUP,SUM,0,0,0,0,0,23,1,12.323760986328125 +17,SPOON,SUM,0,0,0,0,2,75,1,19.349663972854614 +17,,SUM,0,0,0,0,2,216,14,54.29976797103882 +17,, +18,, +18,BOWL,SUM,0,0,0,0,0,20,1,14.92102599143982 +18,CUP,SUM,1,0,0,1,0,350,63,0.0 +18,SPOON,SUM,0,0,0,0,6,21,3,21.180729150772095 +18,,SUM,1,0,0,1,6,391,67,36.101755142211914 +18,, +19,, +19,BOWL,SUM,0,0,0,0,0,312,38,53.65482521057129 +19,CUP,SUM,0,0,0,0,0,29,0,10.040655136108398 +19,SPOON,SUM,0,0,0,0,0,253,1,30.447667121887207 +19,,SUM,0,0,0,0,0,594,39,94.1431474685669 +19,, +20,, +20,BOWL,SUM,0,0,0,0,0,20,0,11.645460844039917 +20,CUP,SUM,0,0,0,0,0,16,1,10.032165050506592 +20,SPOON,SUM,0,0,0,0,0,20,0,14.518812894821167 +20,,SUM,0,0,0,0,0,56,1,36.196438789367676 +20,, +21,, +21,BOWL,SUM,0,0,0,0,0,24,0,11.613071918487549 +21,CUP,SUM,0,0,0,0,0,113,19,36.27656602859497 +21,SPOON,SUM,1,0,1,0,6,1620,0,0.0 +21,,SUM,1,0,1,0,6,1757,19,47.88963794708252 +21,, +22,, +22,BOWL,SUM,0,0,0,0,0,3,2,12.128607988357544 +22,CUP,SUM,1,0,1,0,6,187,92,0.0 +22,SPOON,SUM,0,0,0,0,0,180,4,28.503567934036255 +22,,SUM,1,0,1,0,6,370,98,40.6321759223938 +22,, +23,, +23,BOWL,SUM,0,0,0,0,6,244,38,50.612422943115234 +23,CUP,SUM,0,0,0,0,0,30,17,18.04683494567871 +23,SPOON,SUM,0,0,0,0,0,98,0,20.199125051498413 +23,,SUM,0,0,0,0,6,372,55,88.85838294029236 +23,, +24,, +24,BOWL,SUM,0,0,0,0,0,17,6,15.420736074447632 +24,CUP,SUM,1,0,0,1,2,324,55,0.0 +24,SPOON,SUM,0,0,0,0,0,88,3,23.78467106819153 +24,,SUM,1,0,0,1,2,429,64,39.20540714263916 +24,, +25,, +25,BOWL,SUM,0,0,0,0,0,9,0,11.211691856384277 +25,CUP,SUM,1,0,0,1,0,375,70,0.0 +25,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +25,,SUM,2,0,1,1,0,1965,70,11.211691856384277 +25,, +26,, +26,BOWL,SUM,0,0,0,0,2,20,3,14.072450876235962 +26,CUP,SUM,0,0,0,0,0,34,2,13.258051872253418 +26,SPOON,SUM,0,0,0,0,0,14,0,14.627638101577759 +26,,SUM,0,0,0,0,2,68,5,41.95814085006714 +26,, +27,, +27,BOWL,SUM,0,0,0,0,14,34,16,29.07527494430542 +27,CUP,SUM,0,0,0,0,0,21,3,11.811876058578491 +27,SPOON,SUM,0,0,0,0,4,1382,1,102.45393705368042 +27,,SUM,0,0,0,0,18,1437,20,143.34108805656433 +27,, +28,, +28,BOWL,SUM,0,0,0,0,2,10,0,12.439254999160767 +28,CUP,SUM,0,0,0,0,0,50,4,13.01129698753357 +28,SPOON,SUM,1,0,1,0,26,1466,0,0.0 +28,,SUM,1,0,1,0,28,1526,4,25.450551986694336 +28,, +29,, +29,BOWL,SUM,0,0,0,0,0,73,2,14.357088088989258 +29,CUP,SUM,1,0,0,1,0,323,51,0.0 +29,SPOON,SUM,0,0,0,0,0,16,0,15.0658278465271 +29,,SUM,1,0,0,1,0,412,53,29.422915935516357 +29,, +30,, +30,BOWL,SUM,0,0,0,0,0,10,0,11.31629490852356 +30,CUP,SUM,1,0,0,1,0,378,68,0.0 +30,SPOON,SUM,0,0,0,0,2,0,1,16.376227855682373 +30,,SUM,1,0,0,1,2,388,69,27.692522764205933 +30,, +31,, +31,BOWL,SUM,0,0,0,0,2,5,6,15.525475025177002 +31,CUP,SUM,0,0,0,0,2,27,6,11.237319946289063 +31,SPOON,SUM,0,0,0,0,0,60,3,19.17032504081726 +31,,SUM,0,0,0,0,4,92,15,45.933120012283325 +31,, +32,, +32,BOWL,SUM,0,0,0,0,0,52,1,15.229038000106812 +32,CUP,SUM,0,0,0,0,2,38,1,12.868880987167358 +32,SPOON,SUM,0,0,0,0,0,93,2,23.554587841033936 +32,,SUM,0,0,0,0,2,183,4,51.652506828308105 +32,, +33,, +33,BOWL,SUM,0,0,0,0,0,13,6,15.450240135192871 +33,CUP,SUM,1,0,1,0,0,178,112,0.0 +33,SPOON,SUM,0,0,0,0,0,158,1,26.466810941696167 +33,,SUM,1,0,1,0,0,349,119,41.91705107688904 +33,, +34,, +34,BOWL,SUM,0,0,0,0,0,64,8,18.838629007339478 +34,CUP,SUM,0,0,0,0,0,60,20,28.427841901779175 +34,SPOON,SUM,0,0,0,0,2,14,0,16.001606941223145 +34,,SUM,0,0,0,0,2,138,28,63.2680778503418 +34,, +35,, +35,BOWL,SUM,0,0,0,0,0,296,26,42.29925298690796 +35,CUP,SUM,0,0,0,0,0,44,6,10.896663904190063 +35,SPOON,SUM,1,0,1,0,0,780,76,0.0 +35,,SUM,1,0,1,0,0,1120,108,53.19591689109802 +35,, +36,, +36,BOWL,SUM,0,0,0,0,0,39,8,17.23963189125061 +36,CUP,SUM,0,0,0,0,0,281,41,77.9462890625 +36,SPOON,SUM,0,0,0,0,2,57,0,17.876728057861328 +36,,SUM,0,0,0,0,2,377,49,113.06264901161194 +36,, +37,, +37,BOWL,SUM,0,0,0,0,0,16,0,11.473523139953613 +37,CUP,SUM,1,0,1,0,2,502,86,0.0 +37,SPOON,SUM,0,0,0,0,0,150,0,23.007636070251465 +37,,SUM,1,0,1,0,2,668,86,34.48115921020508 +37,, +38,, +38,BOWL,SUM,0,0,0,0,0,9,0,12.375190019607544 +38,CUP,SUM,1,0,0,1,0,302,80,0.0 +38,SPOON,SUM,0,0,0,0,0,68,0,18.595500946044922 +38,,SUM,1,0,0,1,0,379,80,30.970690965652466 +38,, +39,, +39,BOWL,SUM,0,0,0,0,0,14,2,11.774483919143677 +39,CUP,SUM,1,0,0,1,0,296,68,0.0 +39,SPOON,SUM,0,0,0,0,0,203,12,33.0269660949707 +39,,SUM,1,0,0,1,0,513,82,44.80145001411438 +39,, +40,, +40,BOWL,SUM,0,0,0,0,0,72,23,32.450562953948975 +40,CUP,SUM,0,0,0,0,0,12,5,10.174500942230225 +40,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +40,,SUM,1,0,1,0,0,1665,28,42.6250638961792 +40,, +41,, +41,BOWL,SUM,0,0,0,0,2,27,0,12.495486974716187 +41,CUP,SUM,0,0,0,0,0,155,20,41.93481516838074 +41,SPOON,SUM,0,0,0,0,0,32,1,16.798624992370605 +41,,SUM,0,0,0,0,2,214,21,71.22892713546753 +41,, +42,, +42,BOWL,SUM,0,0,0,0,2,7,0,12.192523002624512 +42,CUP,SUM,1,0,0,1,0,330,53,0.0 +42,SPOON,SUM,0,0,0,0,0,17,1,16.508709192276 +42,,SUM,1,0,0,1,2,354,54,28.701232194900513 +42,, +43,, +43,BOWL,SUM,0,0,0,0,0,29,3,13.52344298362732 +43,CUP,SUM,0,0,0,0,0,45,6,12.352437019348145 +43,SPOON,SUM,0,0,0,0,14,92,4,26.886756896972656 +43,,SUM,0,0,0,0,14,166,13,52.76263689994812 +43,, +44,, +44,BOWL,SUM,0,0,0,0,0,12,0,11.454033136367798 +44,CUP,SUM,0,0,0,0,0,26,4,15.301422834396362 +44,SPOON,SUM,0,0,0,0,0,16,0,14.798057079315186 +44,,SUM,0,0,0,0,0,54,4,41.553513050079346 +44,, +45,, +45,BOWL,SUM,1,0,1,0,0,1381,28,0.0 +45,CUP,SUM,0,0,0,0,0,24,1,12.12565803527832 +45,SPOON,SUM,0,0,0,0,0,87,2,19.62248682975769 +45,,SUM,1,0,1,0,0,1492,31,31.74814486503601 +45,, +46,, +46,BOWL,SUM,0,0,0,0,2,2,2,12.124129056930542 +46,CUP,SUM,0,0,0,0,0,21,14,17.31744408607483 +46,SPOON,SUM,0,0,0,0,0,117,0,21.36722421646118 +46,,SUM,0,0,0,0,2,140,16,50.80879735946655 +46,, +47,, +47,BOWL,SUM,0,0,0,0,0,273,38,50.06552195549011 +47,CUP,SUM,0,0,0,0,0,190,31,47.88132691383362 +47,SPOON,SUM,0,0,0,0,10,147,1,29.145249128341675 +47,,SUM,0,0,0,0,10,610,70,127.0920979976654 +47,, +48,, +48,BOWL,SUM,0,0,0,0,0,2,0,11.302216053009033 +48,CUP,SUM,0,0,0,0,0,123,20,30.613614082336426 +48,SPOON,SUM,0,0,0,0,0,72,0,18.910974979400635 +48,,SUM,0,0,0,0,0,197,20,60.826805114746094 +48,, +49,, +49,BOWL,SUM,0,0,0,0,0,18,4,13.878529071807861 +49,CUP,SUM,0,0,0,0,0,24,6,13.656661987304688 +49,SPOON,SUM,0,0,0,0,24,725,0,76.9315071105957 +49,,SUM,0,0,0,0,24,767,10,104.46669816970825 +49,, +50,, +50,BOWL,SUM,0,0,0,0,2,96,14,25.296616077423096 +50,CUP,SUM,0,0,0,0,0,38,6,12.57210397720337 +50,SPOON,SUM,0,0,0,0,0,307,0,33.56952095031738 +50,,SUM,0,0,0,0,2,441,20,71.43824100494385 +50,, +51,, +51,BOWL,SUM,0,0,0,0,0,13,0,11.912140130996704 +51,CUP,SUM,0,0,0,0,0,101,19,35.22865700721741 +51,SPOON,SUM,0,0,0,0,0,433,0,41.487229108810425 +51,,SUM,0,0,0,0,0,547,19,88.62802624702454 +51,, +52,, +52,BOWL,SUM,0,0,0,0,0,81,3,16.507336139678955 +52,CUP,SUM,0,0,0,0,0,27,5,12.295120000839233 +52,SPOON,SUM,0,0,0,0,0,7,4,17.126893997192383 +52,,SUM,0,0,0,0,0,115,12,45.92935013771057 +52,, +53,, +53,BOWL,SUM,0,0,0,0,0,21,0,12.096212148666382 +53,CUP,SUM,0,0,0,0,4,4,10,11.315691947937012 +53,SPOON,SUM,0,0,0,0,0,82,4,25.243852853775024 +53,,SUM,0,0,0,0,4,107,14,48.65575695037842 +53,, +54,, +54,BOWL,SUM,0,0,0,0,14,76,20,35.265400886535645 +54,CUP,SUM,1,0,1,0,0,178,104,0.0 +54,SPOON,SUM,0,0,0,0,0,30,0,15.411163091659546 +54,,SUM,1,0,1,0,14,284,124,50.67656397819519 +54,, +55,, +55,BOWL,SUM,0,0,0,0,0,63,4,20.243112802505493 +55,CUP,SUM,1,0,0,1,2,298,51,0.0 +55,SPOON,SUM,0,0,0,0,4,147,0,23.214406967163086 +55,,SUM,1,0,0,1,6,508,55,43.45751976966858 +55,, +56,, +56,BOWL,SUM,0,0,0,0,6,11,0,14.113319873809814 +56,CUP,SUM,1,0,0,1,0,304,63,0.0 +56,SPOON,SUM,0,0,0,0,114,91,4,72.81201696395874 +56,,SUM,1,0,0,1,120,406,67,86.92533683776855 +56,, +57,, +57,BOWL,SUM,0,0,0,0,0,10,0,11.439369916915894 +57,CUP,SUM,1,0,1,0,8,382,105,0.0 +57,SPOON,SUM,0,0,0,0,2,99,1,23.256818056106567 +57,,SUM,1,0,1,0,10,491,106,34.69618797302246 +57,, +58,, +58,BOWL,SUM,0,0,0,0,0,20,0,12.06305193901062 +58,CUP,SUM,0,0,0,0,0,6,0,9.834437847137451 +58,SPOON,SUM,0,0,0,0,0,0,0,14.92809510231018 +58,,SUM,0,0,0,0,0,26,0,36.82558488845825 +58,, +59,, +59,BOWL,SUM,0,0,0,0,2,22,1,13.901557922363281 +59,CUP,SUM,1,0,1,0,0,106,112,0.0 +59,SPOON,SUM,0,0,0,0,2,6,2,15.506977081298828 +59,,SUM,1,0,1,0,4,134,115,29.40853500366211 +59,, +60,, +60,BOWL,SUM,0,0,0,0,0,15,2,12.551536083221436 +60,CUP,SUM,0,0,0,0,2,15,4,11.155432939529419 +60,SPOON,SUM,0,0,0,0,0,4,2,17.48548197746277 +60,,SUM,0,0,0,0,2,34,8,41.19245100021362 +60,, +61,, +61,BOWL,SUM,0,0,0,0,0,25,1,14.159333944320679 +61,CUP,SUM,1,0,1,0,0,191,108,0.0 +61,SPOON,SUM,0,0,0,0,6,317,1,38.22180104255676 +61,,SUM,1,0,1,0,6,533,110,52.38113498687744 +61,, +62,, +62,BOWL,SUM,0,0,0,0,0,209,6,26.07548999786377 +62,CUP,SUM,0,0,0,0,2,55,9,19.54240393638611 +62,SPOON,SUM,0,0,0,0,0,67,0,19.240396976470947 +62,,SUM,0,0,0,0,2,331,15,64.85829091072083 +62,, +63,, +63,BOWL,SUM,0,0,0,0,6,21,1,15.23078203201294 +63,CUP,SUM,0,0,0,0,0,20,2,10.5054771900177 +63,SPOON,SUM,0,0,0,0,0,97,0,21.426435947418213 +63,,SUM,0,0,0,0,6,138,3,47.16269516944885 +63,, +64,, +64,BOWL,SUM,0,0,0,0,2,11,0,12.6926748752594 +64,CUP,SUM,0,0,0,0,2,69,19,29.685698986053467 +64,SPOON,SUM,0,0,0,0,0,7,2,15.274533033370972 +64,,SUM,0,0,0,0,4,87,21,57.65290689468384 +64,, +65,, +65,BOWL,SUM,0,0,0,0,0,32,0,12.413268089294434 +65,CUP,SUM,0,0,0,0,0,14,4,10.227756023406982 +65,SPOON,SUM,0,0,0,0,0,176,6,28.534167051315308 +65,,SUM,0,0,0,0,0,222,10,51.175191164016724 +65,, +66,, +66,BOWL,SUM,0,0,0,0,0,58,4,16.21407914161682 +66,CUP,SUM,0,0,0,0,2,28,0,11.345011949539185 +66,SPOON,SUM,0,0,0,0,0,159,2,27.98452591896057 +66,,SUM,0,0,0,0,2,245,6,55.54361701011658 +66,, +67,, +67,BOWL,SUM,0,0,0,0,6,5,1,15.138053894042969 +67,CUP,SUM,0,0,0,0,0,28,6,17.485919952392578 +67,SPOON,SUM,0,0,0,0,0,8,0,15.279461145401001 +67,,SUM,0,0,0,0,6,41,7,47.90343499183655 +67,, +68,, +68,BOWL,SUM,0,0,0,0,0,19,0,12.241420984268188 +68,CUP,SUM,0,0,0,0,0,194,37,68.92347002029419 +68,SPOON,SUM,0,0,0,0,0,128,4,26.454724073410034 +68,,SUM,0,0,0,0,0,341,41,107.61961507797241 +68,, +69,, +69,BOWL,SUM,1,0,1,0,0,443,104,0.0 +69,CUP,SUM,1,0,1,0,0,157,112,0.0 +69,SPOON,SUM,0,0,0,0,0,14,3,17.64336395263672 +69,,SUM,2,0,2,0,0,614,219,17.64336395263672 +69,, +70,, +70,BOWL,SUM,0,0,0,0,0,382,42,60.48794484138489 +70,CUP,SUM,0,0,0,0,0,22,6,11.195406913757324 +70,SPOON,SUM,0,0,0,0,0,188,3,31.552561044692993 +70,,SUM,0,0,0,0,0,592,51,103.2359127998352 +70,, +71,, +71,BOWL,SUM,0,0,0,0,0,12,1,12.101758003234863 +71,CUP,SUM,0,0,0,0,0,4,5,12.17224907875061 +71,SPOON,SUM,0,0,0,0,0,19,4,21.755436897277832 +71,,SUM,0,0,0,0,0,35,10,46.029443979263306 +71,, +72,, +72,BOWL,SUM,0,0,0,0,2,14,0,12.8243989944458 +72,CUP,SUM,0,0,0,0,0,36,10,15.855362892150879 +72,SPOON,SUM,0,0,0,0,0,0,1,16.320460081100464 +72,,SUM,0,0,0,0,2,50,11,45.000221967697144 +72,, +73,, +73,BOWL,SUM,0,0,0,0,22,187,20,41.69651389122009 +73,CUP,SUM,0,0,0,0,0,5,0,9.854555130004883 +73,SPOON,SUM,0,0,0,0,0,1,1,16.416150093078613 +73,,SUM,0,0,0,0,22,193,21,67.96721911430359 +73,, +74,, +74,BOWL,SUM,0,0,0,0,0,3,2,11.666733980178833 +74,CUP,SUM,0,0,0,0,0,11,6,10.185492992401123 +74,SPOON,SUM,0,0,0,0,0,33,0,15.816482067108154 +74,,SUM,0,0,0,0,0,47,8,37.66870903968811 +74,, +75,, +75,BOWL,SUM,0,0,0,0,0,30,6,15.886131048202515 +75,CUP,SUM,0,0,0,0,0,46,12,14.609056949615479 +75,SPOON,SUM,0,0,0,0,0,38,3,17.512776136398315 +75,,SUM,0,0,0,0,0,114,21,48.00796413421631 +75,, +76,, +76,BOWL,SUM,0,0,0,0,0,70,0,15.733321905136108 +76,CUP,SUM,0,0,0,0,14,9,0,16.321959018707275 +76,SPOON,SUM,0,0,0,0,6,82,4,27.36274290084839 +76,,SUM,0,0,0,0,20,161,4,59.41802382469177 +76,, +77,, +77,BOWL,SUM,0,0,0,0,2,15,0,12.452088832855225 +77,CUP,SUM,1,0,0,1,2,402,71,0.0 +77,SPOON,SUM,0,0,0,0,0,8,7,21.66339612007141 +77,,SUM,1,0,0,1,4,425,78,34.115484952926636 +77,, +78,, +78,BOWL,SUM,1,0,1,0,2,1036,70,0.0 +78,CUP,SUM,0,0,0,0,0,28,0,10.788306951522827 +78,SPOON,SUM,0,0,0,0,0,20,0,15.255553960800171 +78,,SUM,1,0,1,0,2,1084,70,26.043860912322998 +78,, +79,, +79,BOWL,SUM,0,0,0,0,2,21,0,12.796112060546875 +79,CUP,SUM,1,0,0,1,0,335,60,0.0 +79,SPOON,SUM,0,0,0,0,0,303,6,35.978354930877686 +79,,SUM,1,0,0,1,2,659,66,48.77446699142456 +79,, +80,, +80,BOWL,SUM,0,0,0,0,2,47,4,16.691685914993286 +80,CUP,SUM,0,0,0,0,0,117,35,36.1101131439209 +80,SPOON,SUM,0,0,0,0,0,39,0,17.474251985549927 +80,,SUM,0,0,0,0,2,203,39,70.27605104446411 +80,, +81,, +81,BOWL,SUM,0,0,0,0,2,16,4,14.528042078018188 +81,CUP,SUM,0,0,0,0,0,22,3,12.276241064071655 +81,SPOON,SUM,0,0,0,0,0,16,2,15.294008016586304 +81,,SUM,0,0,0,0,2,54,9,42.09829115867615 +81,, +82,, +82,BOWL,SUM,0,0,0,0,0,28,1,14.056148052215576 +82,CUP,SUM,0,0,0,0,0,36,7,12.559159994125366 +82,SPOON,SUM,0,0,0,0,0,312,0,33.15573287010193 +82,,SUM,0,0,0,0,0,376,8,59.77104091644287 +82,, +83,, +83,BOWL,SUM,0,0,0,0,2,47,0,14.330244064331055 +83,CUP,SUM,0,0,0,0,0,116,33,45.326030015945435 +83,SPOON,SUM,0,0,0,0,0,223,2,32.07507109642029 +83,,SUM,0,0,0,0,2,386,35,91.73134517669678 +83,, +84,, +84,BOWL,SUM,0,0,0,0,0,12,0,11.641963005065918 +84,CUP,SUM,0,0,0,0,2,32,15,17.437639951705933 +84,SPOON,SUM,0,0,0,0,0,2,4,16.657822132110596 +84,,SUM,0,0,0,0,2,46,19,45.737425088882446 +84,, +85,, +85,BOWL,SUM,0,0,0,0,2,16,1,14.023728847503662 +85,CUP,SUM,0,0,0,0,0,14,2,10.213797092437744 +85,SPOON,SUM,0,0,0,0,2,37,4,23.475172996520996 +85,,SUM,0,0,0,0,4,67,7,47.7126989364624 +85,, +86,, +86,BOWL,SUM,0,0,0,0,42,212,22,53.95875096321106 +86,CUP,SUM,1,0,0,1,0,266,67,0.0 +86,SPOON,SUM,0,0,0,0,0,1,0,14.837280035018921 +86,,SUM,1,0,0,1,42,479,89,68.79603099822998 +86,, +87,, +87,BOWL,SUM,1,0,1,0,0,883,84,0.0 +87,CUP,SUM,0,0,0,0,0,23,4,14.07458209991455 +87,SPOON,SUM,0,0,0,0,0,125,2,25.108945846557617 +87,,SUM,1,0,1,0,0,1031,90,39.18352794647217 +87,, +88,, +88,BOWL,SUM,0,0,0,0,0,77,0,14.902122974395752 +88,CUP,SUM,0,0,0,0,0,8,11,10.636124849319458 +88,SPOON,SUM,0,0,0,0,0,47,4,19.4587619304657 +88,,SUM,0,0,0,0,0,132,15,44.99700975418091 +88,, +89,, +89,BOWL,SUM,0,0,0,0,0,14,0,11.935220003128052 +89,CUP,SUM,0,0,0,0,0,40,13,14.658114194869995 +89,SPOON,SUM,0,0,0,0,4,3,5,19.843292951583862 +89,,SUM,0,0,0,0,4,57,18,46.43662714958191 +89,, +90,, +90,BOWL,SUM,0,0,0,0,0,3,0,11.469420194625854 +90,CUP,SUM,1,0,0,1,4,358,73,0.0 +90,SPOON,SUM,0,0,0,0,4,145,0,25.055127143859863 +90,,SUM,1,0,0,1,8,506,73,36.52454733848572 +90,, +91,, +91,BOWL,SUM,0,0,0,0,0,13,0,12.063323020935059 +91,CUP,SUM,0,0,0,0,0,27,7,18.80745792388916 +91,SPOON,SUM,0,0,0,0,0,24,0,15.314384937286377 +91,,SUM,0,0,0,0,0,64,7,46.185165882110596 +91,, +92,, +92,BOWL,SUM,0,0,0,0,2,5,1,13.796027898788452 +92,CUP,SUM,0,0,0,0,0,33,0,10.736528873443604 +92,SPOON,SUM,0,0,0,0,0,130,1,23.608779191970825 +92,,SUM,0,0,0,0,2,168,2,48.14133596420288 +92,, +93,, +93,BOWL,SUM,0,0,0,0,0,12,1,13.672102928161621 +93,CUP,SUM,1,0,1,0,0,210,67,0.0 +93,SPOON,SUM,0,0,0,0,0,169,6,35.093926191329956 +93,,SUM,1,0,1,0,0,391,74,48.76602911949158 +93,, +94,, +94,BOWL,SUM,0,0,0,0,0,24,2,13.32728099822998 +94,CUP,SUM,0,0,0,0,0,32,3,14.131854057312012 +94,SPOON,SUM,0,0,0,0,0,23,5,23.48844885826111 +94,,SUM,0,0,0,0,0,79,10,50.9475839138031 +94,, +95,, +95,BOWL,SUM,0,0,0,0,0,2,0,11.745683908462524 +95,CUP,SUM,0,0,0,0,2,14,15,16.599567890167236 +95,SPOON,SUM,0,0,0,0,2,61,0,18.346917152404785 +95,,SUM,0,0,0,0,4,77,15,46.692168951034546 +95,, +96,, +96,BOWL,SUM,0,0,0,0,0,27,4,14.394084930419922 +96,CUP,SUM,1,0,0,1,0,313,65,0.0 +96,SPOON,SUM,0,0,0,0,0,336,0,34.9485239982605 +96,,SUM,1,0,0,1,0,676,69,49.34260892868042 +96,, +97,, +97,BOWL,SUM,0,0,0,0,0,19,2,13.86349892616272 +97,CUP,SUM,0,0,0,0,8,194,38,70.20660400390625 +97,SPOON,SUM,0,0,0,0,2,34,4,21.49853515625 +97,,SUM,0,0,0,0,10,247,44,105.56863808631897 +97,, +98,, +98,BOWL,SUM,0,0,0,0,0,7,0,11.7428879737854 +98,CUP,SUM,1,0,0,1,0,312,52,0.0 +98,SPOON,SUM,0,0,0,0,0,35,51,67.2218849658966 +98,,SUM,1,0,0,1,0,354,103,78.964772939682 +98,, +99,, +99,BOWL,SUM,0,0,0,0,2,13,1,12.927755117416382 +99,CUP,SUM,0,0,0,0,0,17,0,10.423380851745605 +99,SPOON,SUM,1,0,1,0,42,1230,0,0.0 +99,,SUM,1,0,1,0,44,1260,1,23.351135969161987 +99,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_20_part5.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_20_part5.csv new file mode 100644 index 0000000000..c601b23d46 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_20_part5.csv @@ -0,0 +1,405 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,4,4,16.8509449959 +0,CUP,SUM,1,0,0,1,0,376,64,0 +0,SPOON,SUM,0,0,0,0,0,2,0,14.4624040127 +0,,SUM,1,0,0,1,0,382,68,31.3133490086 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,0,44,6,15.72539711 +1,CUP,SUM,0,0,0,0,6,50,3,15.7780170441 +1,SPOON,SUM,0,0,0,0,0,134,0,22.4156689644 +1,,SUM,0,0,0,0,6,228,9,53.9190831184 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,0,68,6,15.9052248001 +2,CUP,SUM,1,0,0,1,10,286,76,0 +2,SPOON,SUM,1,0,1,0,0,1582,0,0 +2,,SUM,2,0,1,1,10,1936,82,15.9052248001 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,0,64,0,13.6579060555 +3,CUP,SUM,0,0,0,0,2,147,36,61.0802681446 +3,SPOON,SUM,0,0,0,0,0,191,0,26.4844560623 +3,,SUM,0,0,0,0,2,402,36,101.2226302624 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,8,0,11.5378541946 +4,CUP,SUM,1,0,1,0,6,180,112,0 +4,SPOON,SUM,0,0,0,0,0,92,1,21.2722089291 +4,,SUM,1,0,1,0,6,280,113,32.8100631237 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,0,20,1,13.070925951 +5,CUP,SUM,0,0,0,0,6,19,2,12.0576558113 +5,SPOON,SUM,0,0,0,0,0,18,5,18.6095821857 +5,,SUM,0,0,0,0,6,57,8,43.7381639481 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,2,17,6,15.7336740494 +6,CUP,SUM,0,0,0,0,2,118,24,35.4150259495 +6,SPOON,SUM,0,0,0,0,0,11,6,20.9591391087 +6,,SUM,0,0,0,0,4,146,36,72.1078391075 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,0,18,1,13.1833469868 +7,CUP,SUM,0,0,0,0,0,124,32,32.5886030197 +7,SPOON,SUM,0,0,0,0,0,81,0,19.0326709747 +7,,SUM,0,0,0,0,0,223,33,64.8046209812 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,0,13,1,13.1886670589 +8,CUP,SUM,0,0,0,0,0,328,45,83.0526170731 +8,SPOON,SUM,0,0,0,0,112,127,2,74.2810690403 +8,,SUM,0,0,0,0,112,468,48,170.5223531723 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,31,0,11.8736739159 +9,CUP,SUM,0,0,0,0,2,297,41,68.50324893 +9,SPOON,SUM,0,0,0,0,0,248,0,30.7643930912 +9,,SUM,0,0,0,0,2,576,41,111.141315937 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,10,112,4,22.7592170238 +10,CUP,SUM,0,0,0,0,0,119,29,43.1505658627 +10,SPOON,SUM,0,0,0,0,0,92,1,20.8146970272 +10,,SUM,0,0,0,0,10,323,34,86.7244799137 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,0,200,18,33.2134690285 +11,CUP,SUM,1,0,0,1,0,313,69,0 +11,SPOON,SUM,0,0,0,0,0,19,8,20.1969490051 +11,,SUM,1,0,0,1,0,532,95,53.4104180336 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,2,7,0,12.3934619427 +12,CUP,SUM,1,0,0,1,2,351,76,0 +12,SPOON,SUM,0,0,0,0,0,12,10,24.0773999691 +12,,SUM,1,0,0,1,4,370,86,36.4708619118 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,48,47,6,40.3116791248 +13,CUP,SUM,0,0,0,0,0,94,19,23.052380085 +13,SPOON,SUM,0,0,0,0,0,0,3,16.0345199108 +13,,SUM,0,0,0,0,48,141,28,79.3985791206 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,18,39,0,21.2412071228 +14,CUP,SUM,1,0,1,0,0,141,112,0 +14,SPOON,SUM,0,0,0,0,0,579,0,50.450466156 +14,,SUM,1,0,1,0,18,759,112,71.6916732788 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,0,130,45,52.0398108959 +15,CUP,SUM,0,0,0,0,0,16,1,10.2729468346 +15,SPOON,SUM,0,0,0,0,2,565,0,50.6436471939 +15,,SUM,0,0,0,0,2,711,46,112.9564049244 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,46,1,13.9608390331 +16,CUP,SUM,0,0,0,0,0,19,4,10.2112598419 +16,SPOON,SUM,0,0,0,0,0,10,3,16.5545449257 +16,,SUM,0,0,0,0,0,75,8,40.7266438007 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,0,118,12,23.1149590015 +17,CUP,SUM,0,0,0,0,0,23,1,12.357943058 +17,SPOON,SUM,0,0,0,0,2,75,1,20.1323468685 +17,,SUM,0,0,0,0,2,216,14,55.6052489281 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,0,20,1,13.9091069698 +18,CUP,SUM,1,0,0,1,0,350,63,0 +18,SPOON,SUM,0,0,0,0,6,21,3,22.1631031036 +18,,SUM,1,0,0,1,6,391,67,36.0722100735 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,312,38,55.0290489197 +19,CUP,SUM,0,0,0,0,0,29,0,10.5194239616 +19,SPOON,SUM,0,0,0,0,0,253,1,30.9716010094 +19,,SUM,0,0,0,0,0,594,39,96.5200738907 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,0,20,0,11.6968009472 +20,CUP,SUM,0,0,0,0,0,16,1,10.2629871368 +20,SPOON,SUM,0,0,0,0,0,20,0,15.0130970478 +20,,SUM,0,0,0,0,0,56,1,36.9728851318 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,24,0,12.0745220184 +21,CUP,SUM,0,0,0,0,0,113,19,36.6548829079 +21,SPOON,SUM,1,0,1,0,6,1620,0,0 +21,,SUM,1,0,1,0,6,1757,19,48.7294049263 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,0,3,2,12.1732878685 +22,CUP,SUM,1,0,1,0,6,187,92,0 +22,SPOON,SUM,0,0,0,0,0,180,1,27.3421421051 +22,,SUM,1,0,1,0,6,370,95,39.5154299736 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,1,0,1,0,0,1050,66,0 +23,CUP,SUM,0,0,0,0,0,3,1,10.1048259735 +23,SPOON,SUM,0,0,0,0,0,598,0,51.3631789684 +23,,SUM,1,0,1,0,0,1651,67,61.4680049419 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,60,29,8,45.6723129749 +24,CUP,SUM,0,0,0,0,0,1,0,9.8374590874 +24,SPOON,SUM,0,0,0,0,0,300,12,39.0122652054 +24,,SUM,0,0,0,0,60,330,20,94.5220372677 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,0,13,0,11.644302845 +25,CUP,SUM,1,0,0,1,0,295,61,0 +25,SPOON,SUM,0,0,0,0,0,73,6,21.0935530663 +25,,SUM,1,0,0,1,0,381,67,32.7378559113 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,0,15,0,11.716219902 +26,CUP,SUM,1,0,1,0,10,162,102,0 +26,SPOON,SUM,0,0,0,0,0,58,0,18.4936330318 +26,,SUM,1,0,1,0,10,235,102,30.2098529339 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,0,9,0,11.6194059849 +27,CUP,SUM,0,0,0,0,4,109,38,56.9114379883 +27,SPOON,SUM,0,0,0,0,6,38,3,23.8712489605 +27,,SUM,0,0,0,0,10,156,41,92.4020929337 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,6,14,0,14.4092750549 +28,CUP,SUM,1,0,1,0,2,301,111,0 +28,SPOON,SUM,0,0,0,0,0,68,4,25.087667942 +28,,SUM,1,0,1,0,8,383,115,39.496942997 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,0,28,4,13.8732130527 +29,CUP,SUM,0,0,0,0,0,15,4,10.2965741158 +29,SPOON,SUM,0,0,0,0,0,43,2,20.1576280594 +29,,SUM,0,0,0,0,0,86,10,44.3274152279 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,0,7,4,13.5498878956 +30,CUP,SUM,1,0,1,0,0,154,110,0 +30,SPOON,SUM,0,0,0,0,0,297,1,34.6174721718 +30,,SUM,1,0,1,0,0,458,115,48.1673600674 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,0,130,30,39.492027998 +31,CUP,SUM,0,0,0,0,2,19,2,11.1567490101 +31,SPOON,SUM,0,0,0,0,0,30,1,17.1411149502 +31,,SUM,0,0,0,0,2,179,33,67.7898919582 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,0,76,8,20.0282680988 +32,CUP,SUM,0,0,0,0,0,41,19,20.4345338345 +32,SPOON,SUM,1,0,1,0,0,1581,0,0 +32,,SUM,1,0,1,0,0,1698,27,40.4628019333 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,5,2,11.8694500923 +33,CUP,SUM,0,0,0,0,0,271,41,75.8831310272 +33,SPOON,SUM,0,0,0,0,0,67,0,18.8069889545 +33,,SUM,0,0,0,0,0,343,43,106.5595700741 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,0,22,6,15.5772020817 +34,CUP,SUM,0,0,0,0,2,26,2,14.5066299438 +34,SPOON,SUM,1,0,1,0,0,1582,0,0 +34,,SUM,1,0,1,0,2,1630,8,30.0838320255 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,8,59,8,22.4225108624 +35,CUP,SUM,0,0,0,0,0,6,0,10.0787148476 +35,SPOON,SUM,1,0,1,0,0,1042,60,0 +35,,SUM,1,0,1,0,8,1107,68,32.5012257099 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,0,15,4,13.6849200726 +36,CUP,SUM,0,0,0,0,0,8,0,10.1236839294 +36,SPOON,SUM,0,0,0,0,0,65,3,20.6050429344 +36,,SUM,0,0,0,0,0,88,7,44.4136469364 +36,,,,,,,,,, +37,,,,,,,,,, +37,BOWL,SUM,0,0,0,0,0,9,0,11.4047660828 +37,CUP,SUM,0,0,0,0,2,30,10,12.9653429985 +37,SPOON,SUM,0,0,0,0,0,5,0,14.9848229885 +37,,SUM,0,0,0,0,2,44,10,39.3549320698 +37,,,,,,,,,, +38,,,,,,,,,, +38,BOWL,SUM,0,0,0,0,0,15,0,11.8040709496 +38,CUP,SUM,0,0,0,0,0,55,22,22.5911250114 +38,SPOON,SUM,1,0,1,0,0,1584,0,0 +38,,SUM,1,0,1,0,0,1654,22,34.395195961 +38,,,,,,,,,, +39,,,,,,,,,, +39,BOWL,SUM,1,0,1,0,2,260,104,0 +39,CUP,SUM,0,0,0,0,0,4,0,10.0997760296 +39,SPOON,SUM,0,0,0,0,4,76,1,22.1050150394 +39,,SUM,1,0,1,0,6,340,105,32.204791069 +39,,,,,,,,,, +40,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,2,14,2,12.9989700317 +40,CUP,SUM,1,0,0,1,0,456,79,0 +40,SPOON,SUM,0,0,0,0,0,89,0,19.5746049881 +40,,SUM,1,0,0,1,2,559,81,32.5735750198 +40,,,,,,,,,, +41,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,2,25,2,13.4762868881 +41,CUP,SUM,0,0,0,0,4,26,2,11.9604721069 +41,SPOON,SUM,0,0,0,0,0,1,1,16.7412829399 +41,,SUM,0,0,0,0,6,52,5,42.178041935 +41,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,2,19,0,12.9581480026 +42,CUP,SUM,0,0,0,0,0,6,2,9.9945669174 +42,SPOON,SUM,0,0,0,0,0,32,2,19.6938149929 +42,,SUM,0,0,0,0,2,57,4,42.6465299129 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,0,377,40,55.941519022 +43,CUP,SUM,0,0,0,0,0,24,2,13.5179698467 +43,SPOON,SUM,0,0,0,0,0,7,4,17.0821590424 +43,,SUM,0,0,0,0,0,408,46,86.5416479111 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,1,0,1,0,0,1028,62,0 +44,CUP,SUM,0,0,0,0,2,19,14,22.2811911106 +44,SPOON,SUM,0,0,0,0,0,35,0,17.2157931328 +44,,SUM,1,0,1,0,2,1082,76,39.4969842434 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,2,40,0,14.6062629223 +45,CUP,SUM,0,0,0,0,0,4,8,10.5065019131 +45,SPOON,SUM,0,0,0,0,0,163,0,25.2054560184 +45,,SUM,0,0,0,0,2,207,8,50.3182208538 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,0,22,0,12.2335879803 +46,CUP,SUM,0,0,0,0,0,185,40,75.6164219379 +46,SPOON,SUM,0,0,0,0,0,691,0,58.1018061638 +46,,SUM,0,0,0,0,0,898,40,145.951816082 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,0,0,0,0,0,35,0,13.2895159721 +47,CUP,SUM,0,0,0,0,0,164,39,65.4061870575 +47,SPOON,SUM,0,0,0,0,0,1,2,15.4754080772 +47,,SUM,0,0,0,0,0,200,41,94.1711111069 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,4,24,7,18.2394249439 +48,CUP,SUM,0,0,0,0,0,65,7,19.5930800438 +48,SPOON,SUM,1,0,1,0,0,1094,58,0 +48,,SUM,1,0,1,0,4,1183,72,37.8325049877 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,0,32,0,12.3095350266 +49,CUP,SUM,0,0,0,0,0,21,4,10.8437919617 +49,SPOON,SUM,0,0,0,0,0,93,0,19.8876669407 +49,,SUM,0,0,0,0,0,146,4,43.0409939289 +49,,,,,,,,,, +50,,,,,,,,,, +50,BOWL,SUM,0,0,0,0,2,45,2,14.6427628994 +50,CUP,SUM,0,0,0,0,0,10,4,12.259750843 +50,SPOON,SUM,1,0,1,0,0,979,66,0 +50,,SUM,1,0,1,0,2,1034,72,26.9025137424 +50,,,,,,,,,, +51,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,0,2,0,11.7499349117 +51,CUP,SUM,0,0,0,0,0,21,0,10.3382468224 +51,SPOON,SUM,0,0,0,0,0,398,0,39.502548933 +51,,SUM,0,0,0,0,0,421,0,61.5907306671 +51,,,,,,,,,, +52,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,4,32,0,13.2991418839 +52,CUP,SUM,0,0,0,0,4,34,12,18.7251541615 +52,SPOON,SUM,0,0,0,0,0,242,3,33.9212021828 +52,,SUM,0,0,0,0,8,308,15,65.9454982281 +52,,,,,,,,,, +53,,,,,,,,,, +53,BOWL,SUM,0,0,0,0,0,41,2,12.8079600334 +53,CUP,SUM,0,0,0,0,2,36,3,13.1640739441 +53,SPOON,SUM,0,0,0,0,0,290,1,34.4143531322 +53,,SUM,0,0,0,0,2,367,6,60.3863871098 +53,,,,,,,,,, +54,,,,,,,,,, +54,BOWL,SUM,0,0,0,0,0,29,0,12.979790926 +54,CUP,SUM,0,0,0,0,6,9,6,13.1186299324 +54,SPOON,SUM,0,0,0,0,0,0,1,17.1345071793 +54,,SUM,0,0,0,0,6,38,7,43.2329280376 +54,,,,,,,,,, +55,,,,,,,,,, +55,BOWL,SUM,0,0,0,0,6,283,37,56.2008860111 +55,CUP,SUM,0,0,0,0,2,93,18,36.6717619896 +55,SPOON,SUM,0,0,0,0,0,12,0,15.135807991 +55,,SUM,0,0,0,0,8,388,55,108.0084559917 +55,,,,,,,,,, +56,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,2,69,0,15.2165598869 +56,CUP,SUM,0,0,0,0,0,242,55,84.0072259903 +56,SPOON,SUM,0,0,0,0,0,0,0,14.9178640842 +56,,SUM,0,0,0,0,2,311,55,114.1416499615 +56,,,,,,,,,, +57,,,,,,,,,, +57,BOWL,SUM,0,0,0,0,0,334,16,40.9521811008 +57,CUP,SUM,0,0,0,0,0,14,7,13.6643660069 +57,SPOON,SUM,0,0,0,0,0,7,1,16.9616379738 +57,,SUM,0,0,0,0,0,355,24,71.5781850815 +57,,,,,,,,,, +58,,,,,,,,,, +58,BOWL,SUM,0,0,0,0,0,9,0,12.285421133 +58,CUP,SUM,0,0,0,0,0,6,6,12.3378100395 +58,SPOON,SUM,1,0,1,0,0,1583,0,0 +58,,SUM,1,0,1,0,0,1598,6,24.6232311726 +58,,,,,,,,,, +59,,,,,,,,,, +59,BOWL,SUM,1,0,1,0,0,879,74,0 +59,CUP,SUM,0,0,0,0,0,15,6,10.912997961 +59,SPOON,SUM,0,0,0,0,0,5,0,15.4320969582 +59,,SUM,1,0,1,0,0,899,80,26.3450949192 +59,,,,,,,,,, +60,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,0,12,0,12.1844551563 +60,CUP,SUM,0,0,0,0,0,226,33,54.7287359238 +60,SPOON,SUM,0,0,0,0,0,446,1,42.7752950191 +60,,SUM,0,0,0,0,0,684,34,109.6884860992 +60,,,,,,,,,, +61,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,0,10,1,11.9440960884 +61,CUP,SUM,0,0,0,0,0,59,3,11.849738121 +61,SPOON,SUM,0,0,0,0,0,529,0,50.533012867 +61,,SUM,0,0,0,0,0,598,4,74.3268470764 +61,,,,,,,,,, +62,,,,,,,,,, +62,BOWL,SUM,0,0,0,0,0,35,1,14.1206271648 +62,CUP,SUM,0,0,0,0,0,15,13,16.1743130684 +62,SPOON,SUM,0,0,0,0,0,660,8,65.6165308952 +62,,SUM,0,0,0,0,0,710,22,95.9114711285 +62,,,,,,,,,, +63,,,,,,,,,, +63,BOWL,SUM,0,0,0,0,16,28,2,20.7914421558 +63,CUP,SUM,1,0,0,1,0,198,68,0 +63,SPOON,SUM,0,0,0,0,6,221,1,31.9849200249 +63,,SUM,1,0,0,1,22,447,71,52.7763621807 +63,,,,,,,,,, +64,,,,,,,,,, +64,BOWL,SUM,0,0,0,0,0,15,2,12.5509970188 +64,CUP,SUM,1,0,0,1,0,330,73,0 +64,SPOON,SUM,0,0,0,0,0,0,0,15.5169560909 +64,,SUM,1,0,0,1,0,345,75,28.0679531097 +64,,,,,,,,,, +65,,,,,,,,,, +65,BOWL,SUM,0,0,0,0,0,11,0,11.8463180065 +65,CUP,SUM,0,0,0,0,0,29,15,14.4405009747 +65,SPOON,SUM,0,0,0,0,0,1,0,15.2897210121 +65,,SUM,0,0,0,0,0,41,15,41.5765399933 +65,,,,,,,,,, +66,,,,,,,,,, +66,BOWL,SUM,0,0,0,0,0,14,0,12.6264710426 +66,CUP,SUM,0,0,0,0,0,46,7,16.2201619148 +66,SPOON,SUM,0,0,0,0,0,3,4,17.1546640396 +66,,SUM,0,0,0,0,0,63,11,46.0012969971 +66,,,,,,,,,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_21.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_21.csv new file mode 100644 index 0000000000..30d718bc22 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_21.csv @@ -0,0 +1,603 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,0,4,4,16.541619062423706 +0,CUP,SUM,1,0,0,1,0,376,64,0.0 +0,SPOON,SUM,0,0,0,0,0,2,0,13.968730926513672 +0,,SUM,1,0,0,1,0,382,68,30.510349988937378 +0,, +1,, +1,BOWL,SUM,0,0,0,0,0,44,6,15.393714904785156 +1,CUP,SUM,0,0,0,0,6,50,4,16.64452314376831 +1,SPOON,SUM,0,0,0,0,0,358,1,37.23827910423279 +1,,SUM,0,0,0,0,6,452,11,69.27651715278625 +1,, +2,, +2,BOWL,SUM,0,0,0,0,2,318,16,38.89597296714783 +2,CUP,SUM,0,0,0,0,0,4,2,11.58195185661316 +2,SPOON,SUM,0,0,0,0,28,476,0,57.163543939590454 +2,,SUM,0,0,0,0,30,798,18,107.64146876335144 +2,, +3,, +3,BOWL,SUM,0,0,0,0,136,144,11,90.22694993019104 +3,CUP,SUM,0,0,0,0,0,41,3,13.624433994293213 +3,SPOON,SUM,1,0,1,0,0,1308,38,0.0 +3,,SUM,1,0,1,0,136,1493,52,103.85138392448425 +3,, +4,, +4,BOWL,SUM,0,0,0,0,0,28,0,11.921869039535522 +4,CUP,SUM,0,0,0,0,0,3,1,11.355768918991089 +4,SPOON,SUM,0,0,0,0,2,97,0,19.908149003982544 +4,,SUM,0,0,0,0,2,128,1,43.185786962509155 +4,, +5,, +5,BOWL,SUM,0,0,0,0,0,2,0,11.115190982818604 +5,CUP,SUM,1,0,0,1,0,391,62,0.0 +5,SPOON,SUM,0,0,0,0,0,129,1,23.020267963409424 +5,,SUM,1,0,0,1,0,522,63,34.13545894622803 +5,, +6,, +6,BOWL,SUM,0,0,0,0,0,42,4,15.43816590309143 +6,CUP,SUM,0,0,0,0,0,161,96,89.59807991981506 +6,SPOON,SUM,0,0,0,0,10,403,3,45.29447388648987 +6,,SUM,0,0,0,0,10,606,103,150.33071970939636 +6,, +7,, +7,BOWL,SUM,0,0,0,0,0,9,4,13.73454999923706 +7,CUP,SUM,0,0,0,0,0,362,54,98.75077700614929 +7,SPOON,SUM,1,0,1,0,280,1455,46,0.0 +7,,SUM,1,0,1,0,280,1826,104,112.48532700538635 +7,, +8,, +8,BOWL,SUM,0,0,0,0,0,24,0,12.315101861953735 +8,CUP,SUM,0,0,0,0,0,48,7,15.994061946868896 +8,SPOON,SUM,0,0,0,0,0,1,1,16.341161012649536 +8,,SUM,0,0,0,0,0,73,8,44.65032482147217 +8,, +9,, +9,BOWL,SUM,0,0,0,0,0,20,1,11.520861148834229 +9,CUP,SUM,0,0,0,0,0,30,4,12.34924602508545 +9,SPOON,SUM,0,0,0,0,0,50,1,18.492778778076172 +9,,SUM,0,0,0,0,0,100,6,42.36288595199585 +9,, +10,, +10,BOWL,SUM,0,0,0,0,0,10,0,12.10605502128601 +10,CUP,SUM,1,0,0,1,0,341,59,0.0 +10,SPOON,SUM,0,0,0,0,0,321,21,49.235625982284546 +10,,SUM,1,0,0,1,0,672,80,61.34168100357056 +10,, +11,, +11,BOWL,SUM,0,0,0,0,0,36,8,17.24114203453064 +11,CUP,SUM,1,0,0,1,2,326,61,0.0 +11,SPOON,SUM,0,0,0,0,0,4,0,14.857477903366089 +11,,SUM,1,0,0,1,2,366,69,32.09861993789673 +11,, +12,, +12,BOWL,SUM,0,0,0,0,0,24,0,11.661360025405884 +12,CUP,SUM,0,0,0,0,0,245,56,89.33010005950928 +12,SPOON,SUM,0,0,0,0,2,63,0,17.945136070251465 +12,,SUM,0,0,0,0,2,332,56,118.93659615516663 +12,, +13,, +13,BOWL,SUM,0,0,0,0,0,24,0,11.889593124389648 +13,CUP,SUM,0,0,0,0,0,26,5,13.457940101623535 +13,SPOON,SUM,0,0,0,0,0,13,2,17.783196926116943 +13,,SUM,0,0,0,0,0,63,7,43.13073015213013 +13,, +14,, +14,BOWL,SUM,0,0,0,0,0,55,3,16.026561975479126 +14,CUP,SUM,1,0,0,1,0,375,57,0.0 +14,SPOON,SUM,0,0,0,0,0,232,12,34.571065187454224 +14,,SUM,1,0,0,1,0,662,72,50.59762716293335 +14,, +15,, +15,BOWL,SUM,0,0,0,0,8,31,4,17.403772830963135 +15,CUP,SUM,0,0,0,0,0,60,3,16.019205808639526 +15,SPOON,SUM,1,0,1,0,0,1582,0,0.0 +15,,SUM,1,0,1,0,8,1673,7,33.42297863960266 +15,, +16,, +16,BOWL,SUM,0,0,0,0,0,271,2,27.572556018829346 +16,CUP,SUM,0,0,0,0,0,9,4,9.680843114852905 +16,SPOON,SUM,0,0,0,0,0,251,1,30.87655210494995 +16,,SUM,0,0,0,0,0,531,7,68.1299512386322 +16,, +17,, +17,BOWL,SUM,0,0,0,0,0,28,4,13.424590110778809 +17,CUP,SUM,0,0,0,0,2,13,3,12.053299903869629 +17,SPOON,SUM,0,0,0,0,0,202,27,43.561787128448486 +17,,SUM,0,0,0,0,2,243,34,69.03967714309692 +17,, +18,, +18,BOWL,SUM,0,0,0,0,0,46,0,12.384988069534302 +18,CUP,SUM,1,0,1,0,0,218,112,0.0 +18,SPOON,SUM,0,0,0,0,0,61,0,17.352421045303345 +18,,SUM,1,0,1,0,0,325,112,29.737409114837646 +18,, +19,, +19,BOWL,SUM,0,0,0,0,6,26,7,18.434528827667236 +19,CUP,SUM,0,0,0,0,0,29,6,13.934072971343994 +19,SPOON,SUM,0,0,0,0,0,1,1,16.1821768283844 +19,,SUM,0,0,0,0,6,56,14,48.55077862739563 +19,, +20,, +20,BOWL,SUM,0,0,0,0,0,66,0,14.274210929870605 +20,CUP,SUM,1,0,0,1,2,305,52,0.0 +20,SPOON,SUM,0,0,0,0,8,184,1,31.494851112365723 +20,,SUM,1,0,0,1,10,555,53,45.76906204223633 +20,, +21,, +21,BOWL,SUM,0,0,0,0,0,17,0,11.723674058914185 +21,CUP,SUM,0,0,0,0,0,12,2,10.174437046051025 +21,SPOON,SUM,0,0,0,0,20,682,0,64.08861899375916 +21,,SUM,0,0,0,0,20,711,2,85.98673009872437 +21,, +22,, +22,BOWL,SUM,0,0,0,0,0,29,0,12.072590112686157 +22,CUP,SUM,0,0,0,0,0,11,4,10.181043148040771 +22,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +22,,SUM,1,0,1,0,0,1621,4,22.25363326072693 +22,, +23,, +23,BOWL,SUM,0,0,0,0,0,9,1,11.716970920562744 +23,CUP,SUM,0,0,0,0,0,132,24,42.03620481491089 +23,SPOON,SUM,0,0,0,0,6,0,0,16.70905113220215 +23,,SUM,0,0,0,0,6,141,25,70.46222686767578 +23,, +24,, +24,BOWL,SUM,0,0,0,0,0,21,5,15.321784973144531 +24,CUP,SUM,0,0,0,0,0,15,5,10.522090911865234 +24,SPOON,SUM,0,0,0,0,0,221,8,31.113394021987915 +24,,SUM,0,0,0,0,0,257,18,56.95726990699768 +24,, +25,, +25,BOWL,SUM,0,0,0,0,0,123,14,27.05543804168701 +25,CUP,SUM,0,0,0,0,2,15,5,12.483309030532837 +25,SPOON,SUM,0,0,0,0,10,7,7,24.477030038833618 +25,,SUM,0,0,0,0,12,145,26,64.01577711105347 +25,, +26,, +26,BOWL,SUM,0,0,0,0,0,22,0,11.872951030731201 +26,CUP,SUM,0,0,0,0,0,8,4,11.664565086364746 +26,SPOON,SUM,0,0,0,0,4,303,1,35.03022789955139 +26,,SUM,0,0,0,0,4,333,5,58.56774401664734 +26,, +27,, +27,BOWL,SUM,0,0,0,0,2,43,6,16.888969898223877 +27,CUP,SUM,0,0,0,0,0,11,12,12.51368498802185 +27,SPOON,SUM,0,0,0,0,0,42,0,16.872605085372925 +27,,SUM,0,0,0,0,2,96,18,46.27525997161865 +27,, +28,, +28,BOWL,SUM,0,0,0,0,0,19,6,15.438680171966553 +28,CUP,SUM,1,0,0,1,0,401,66,0.0 +28,SPOON,SUM,0,0,0,0,0,120,1,22.979886054992676 +28,,SUM,1,0,0,1,0,540,73,38.41856622695923 +28,, +29,, +29,BOWL,SUM,0,0,0,0,50,46,1,36.25591683387756 +29,CUP,SUM,0,0,0,0,0,26,2,10.206614971160889 +29,SPOON,SUM,0,0,0,0,2,9,2,18.82004189491272 +29,,SUM,0,0,0,0,52,81,5,65.28257369995117 +29,, +30,, +30,BOWL,SUM,1,0,1,0,0,682,89,0.0 +30,CUP,SUM,0,0,0,0,8,105,26,42.488070011138916 +30,SPOON,SUM,0,0,0,0,0,49,7,28.3596248626709 +30,,SUM,1,0,1,0,8,836,122,70.84769487380981 +30,, +31,, +31,BOWL,SUM,0,0,0,0,56,42,2,38.16239786148071 +31,CUP,SUM,1,0,1,0,0,158,63,0.0 +31,SPOON,SUM,0,0,0,0,0,3,2,18.102380990982056 +31,,SUM,1,0,1,0,56,203,67,56.26477885246277 +31,, +32,, +32,BOWL,SUM,0,0,0,0,0,8,4,13.521120071411133 +32,CUP,SUM,0,0,0,0,0,94,25,42.87702202796936 +32,SPOON,SUM,0,0,0,0,0,12,0,15.253751993179321 +32,,SUM,0,0,0,0,0,114,29,71.65189409255981 +32,, +33,, +33,BOWL,SUM,0,0,0,0,0,9,1,13.193986892700195 +33,CUP,SUM,0,0,0,0,0,78,14,28.153281927108765 +33,SPOON,SUM,0,0,0,0,0,169,0,25.118070125579834 +33,,SUM,0,0,0,0,0,256,15,66.4653389453888 +33,, +34,, +34,BOWL,SUM,0,0,0,0,0,67,16,25.34480094909668 +34,CUP,SUM,0,0,0,0,0,11,0,10.220991134643555 +34,SPOON,SUM,0,0,0,0,0,550,3,55.14628791809082 +34,,SUM,0,0,0,0,0,628,19,90.71208000183105 +34,, +35,, +35,BOWL,SUM,0,0,0,0,0,44,1,15.207098007202148 +35,CUP,SUM,0,0,0,0,0,64,12,22.452762126922607 +35,SPOON,SUM,0,0,0,0,0,7,1,16.082567930221558 +35,,SUM,0,0,0,0,0,115,14,53.74242806434631 +35,, +36,, +36,BOWL,SUM,0,0,0,0,0,21,0,11.890246868133545 +36,CUP,SUM,0,0,0,0,0,11,0,9.678146123886108 +36,SPOON,SUM,0,0,0,0,0,372,0,36.847166776657104 +36,,SUM,0,0,0,0,0,404,0,58.41555976867676 +36,, +37,, +37,BOWL,SUM,0,0,0,0,0,8,0,11.739371061325073 +37,CUP,SUM,0,0,0,0,0,60,5,14.421916007995605 +37,SPOON,SUM,0,0,0,0,0,215,2,28.142296075820923 +37,,SUM,0,0,0,0,0,283,7,54.3035831451416 +37,, +38,, +38,BOWL,SUM,0,0,0,0,0,305,16,36.34313917160034 +38,CUP,SUM,0,0,0,0,0,2,2,10.178843021392822 +38,SPOON,SUM,0,0,0,0,10,295,0,37.18364191055298 +38,,SUM,0,0,0,0,10,602,18,83.70562410354614 +38,, +39,, +39,BOWL,SUM,0,0,0,0,0,68,18,26.834912061691284 +39,CUP,SUM,0,0,0,0,2,8,11,11.392252922058105 +39,SPOON,SUM,0,0,0,0,6,58,0,18.76616096496582 +39,,SUM,0,0,0,0,8,134,29,56.99332594871521 +39,, +40,, +40,BOWL,SUM,0,0,0,0,62,186,20,59.85063099861145 +40,CUP,SUM,0,0,0,0,0,15,0,10.44594407081604 +40,SPOON,SUM,0,0,0,0,0,395,0,39.95213198661804 +40,,SUM,0,0,0,0,62,596,20,110.24870705604553 +40,, +41,, +41,BOWL,SUM,0,0,0,0,0,37,4,14.447642087936401 +41,CUP,SUM,0,0,0,0,0,75,9,17.028894186019897 +41,SPOON,SUM,0,0,0,0,0,333,1,36.92210006713867 +41,,SUM,0,0,0,0,0,445,14,68.39863634109497 +41,, +42,, +42,BOWL,SUM,0,0,0,0,0,50,8,18.22691798210144 +42,CUP,SUM,0,0,0,0,0,32,7,12.54319715499878 +42,SPOON,SUM,1,0,1,0,0,1016,62,0.0 +42,,SUM,1,0,1,0,0,1098,77,30.77011513710022 +42,, +43,, +43,BOWL,SUM,0,0,0,0,0,163,16,29.780818939208984 +43,CUP,SUM,0,0,0,0,0,41,2,11.052860021591187 +43,SPOON,SUM,0,0,0,0,0,59,0,18.00150179862976 +43,,SUM,0,0,0,0,0,263,18,58.83518075942993 +43,, +44,, +44,BOWL,SUM,0,0,0,0,0,12,0,11.80092191696167 +44,CUP,SUM,1,0,0,1,0,320,61,0.0 +44,SPOON,SUM,0,0,0,0,2,10,18,29.366395950317383 +44,,SUM,1,0,0,1,2,342,79,41.16731786727905 +44,, +45,, +45,BOWL,SUM,0,0,0,0,0,45,4,14.53000807762146 +45,CUP,SUM,0,0,0,0,0,7,0,10.111785888671875 +45,SPOON,SUM,0,0,0,0,2,636,14,70.33266091346741 +45,,SUM,0,0,0,0,2,688,18,94.97445487976074 +45,, +46,, +46,BOWL,SUM,0,0,0,0,0,37,5,15.93717908859253 +46,CUP,SUM,0,0,0,0,0,51,14,24.755980014801025 +46,SPOON,SUM,0,0,0,0,0,20,0,15.41283893585205 +46,,SUM,0,0,0,0,0,108,19,56.105998039245605 +46,, +47,, +47,BOWL,SUM,0,0,0,0,0,22,4,13.92074704170227 +47,CUP,SUM,0,0,0,0,2,6,3,12.369369983673096 +47,SPOON,SUM,0,0,0,0,0,137,1,25.21628499031067 +47,,SUM,0,0,0,0,2,165,8,51.506402015686035 +47,, +48,, +48,BOWL,SUM,0,0,0,0,0,7,8,16.95236897468567 +48,CUP,SUM,1,0,0,1,0,362,72,0.0 +48,SPOON,SUM,0,0,0,0,0,251,0,29.561256885528564 +48,,SUM,1,0,0,1,0,620,80,46.51362586021423 +48,, +49,, +49,BOWL,SUM,0,0,0,0,0,16,0,11.698669910430908 +49,CUP,SUM,0,0,0,0,0,9,2,10.038447856903076 +49,SPOON,SUM,0,0,0,0,6,108,0,23.30882501602173 +49,,SUM,0,0,0,0,6,133,2,45.04594278335571 +49,, +50,, +50,BOWL,SUM,0,0,0,0,122,572,26,114.41744589805603 +50,CUP,SUM,0,0,0,0,4,35,4,14.929626941680908 +50,SPOON,SUM,0,0,0,0,0,2,1,16.910661935806274 +50,,SUM,0,0,0,0,126,609,31,146.2577347755432 +50,, +51,, +51,BOWL,SUM,0,0,0,0,0,14,1,11.804641962051392 +51,CUP,SUM,1,0,1,0,0,184,102,0.0 +51,SPOON,SUM,0,0,0,0,0,186,0,25.796101093292236 +51,,SUM,1,0,1,0,0,384,103,37.60074305534363 +51,, +52,, +52,BOWL,SUM,0,0,0,0,0,11,1,11.695688962936401 +52,CUP,SUM,0,0,0,0,0,342,57,99.78359484672546 +52,SPOON,SUM,0,0,0,0,0,77,2,19.631448984146118 +52,,SUM,0,0,0,0,0,430,60,131.11073279380798 +52,, +53,, +53,BOWL,SUM,0,0,0,0,18,142,8,29.693894863128662 +53,CUP,SUM,1,0,0,1,0,335,57,0.0 +53,SPOON,SUM,0,0,0,0,0,535,3,52.19551992416382 +53,,SUM,1,0,0,1,18,1012,68,81.88941478729248 +53,, +54,, +54,BOWL,SUM,0,0,0,0,2,14,0,12.84330701828003 +54,CUP,SUM,1,0,1,0,2,203,112,0.0 +54,SPOON,SUM,0,0,0,0,0,123,1,22.201336145401 +54,,SUM,1,0,1,0,4,340,113,35.04464316368103 +54,, +55,, +55,BOWL,SUM,0,0,0,0,0,5,4,13.741711139678955 +55,CUP,SUM,0,0,0,0,2,3,0,10.68982195854187 +55,SPOON,SUM,0,0,0,0,0,76,2,22.29126501083374 +55,,SUM,0,0,0,0,2,84,6,46.722798109054565 +55,, +56,, +56,BOWL,SUM,0,0,0,0,0,9,0,12.047906875610352 +56,CUP,SUM,1,0,0,1,2,294,59,0.0 +56,SPOON,SUM,0,0,0,0,0,53,6,19.462027072906494 +56,,SUM,1,0,0,1,2,356,65,31.509933948516846 +56,, +57,, +57,BOWL,SUM,0,0,0,0,0,18,2,12.422746896743774 +57,CUP,SUM,0,0,0,0,0,168,61,60.9043231010437 +57,SPOON,SUM,0,0,0,0,0,31,1,19.010995149612427 +57,,SUM,0,0,0,0,0,217,64,92.3380651473999 +57,, +58,, +58,BOWL,SUM,0,0,0,0,26,27,0,24.952194929122925 +58,CUP,SUM,1,0,0,1,0,224,70,0.0 +58,SPOON,SUM,0,0,0,0,0,1,6,19.768980979919434 +58,,SUM,1,0,0,1,26,252,76,44.72117590904236 +58,, +59,, +59,BOWL,SUM,0,0,0,0,4,12,0,13.618190050125122 +59,CUP,SUM,0,0,0,0,0,15,6,10.826990127563477 +59,SPOON,SUM,0,0,0,0,16,167,2,31.5941801071167 +59,,SUM,0,0,0,0,20,194,8,56.0393602848053 +59,, +60,, +60,BOWL,SUM,0,0,0,0,0,48,13,22.975282907485962 +60,CUP,SUM,0,0,0,0,0,9,0,10.102969884872437 +60,SPOON,SUM,0,0,0,0,4,91,6,25.232944011688232 +60,,SUM,0,0,0,0,4,148,19,58.31119680404663 +60,, +61,, +61,BOWL,SUM,0,0,0,0,2,5,0,12.217563152313232 +61,CUP,SUM,0,0,0,0,4,33,6,18.664416074752808 +61,SPOON,SUM,0,0,0,0,0,25,2,15.51955795288086 +61,,SUM,0,0,0,0,6,63,8,46.4015371799469 +61,, +62,, +62,BOWL,SUM,0,0,0,0,0,234,45,55.40419292449951 +62,CUP,SUM,0,0,0,0,0,11,7,10.582449913024902 +62,SPOON,SUM,0,0,0,0,0,20,0,15.501178979873657 +62,,SUM,0,0,0,0,0,265,52,81.48782181739807 +62,, +63,, +63,BOWL,SUM,0,0,0,0,0,43,7,17.87733483314514 +63,CUP,SUM,1,0,1,0,0,257,101,0.0 +63,SPOON,SUM,0,0,0,0,0,18,2,15.33641505241394 +63,,SUM,1,0,1,0,0,318,110,33.21374988555908 +63,, +64,, +64,BOWL,SUM,0,0,0,0,0,157,4,22.340022087097168 +64,CUP,SUM,0,0,0,0,0,9,4,10.248312950134277 +64,SPOON,SUM,0,0,0,0,0,209,14,35.579517126083374 +64,,SUM,0,0,0,0,0,375,22,68.16785216331482 +64,, +65,, +65,BOWL,SUM,0,0,0,0,48,39,0,35.49063587188721 +65,CUP,SUM,0,0,0,0,0,30,6,13.790028095245361 +65,SPOON,SUM,0,0,0,0,0,38,0,17.578777074813843 +65,,SUM,0,0,0,0,48,107,6,66.85944104194641 +65,, +66,, +66,BOWL,SUM,0,0,0,0,2,18,1,14.725537061691284 +66,CUP,SUM,0,0,0,0,2,4,4,11.375688076019287 +66,SPOON,SUM,0,0,0,0,0,98,0,21.239385843276978 +66,,SUM,0,0,0,0,4,120,5,47.34061098098755 +66,, +67,, +67,BOWL,SUM,0,0,0,0,2,8,1,12.53555703163147 +67,CUP,SUM,0,0,0,0,2,57,18,33.18125796318054 +67,SPOON,SUM,0,0,0,0,0,60,0,17.398056030273438 +67,,SUM,0,0,0,0,4,125,19,63.11487102508545 +67,, +68,, +68,BOWL,SUM,0,0,0,0,88,45,4,56.45172095298767 +68,CUP,SUM,0,0,0,0,0,13,2,10.286767959594727 +68,SPOON,SUM,1,0,1,0,0,1390,28,0.0 +68,,SUM,1,0,1,0,88,1448,34,66.7384889125824 +68,, +69,, +69,BOWL,SUM,0,0,0,0,2,16,4,14.731284141540527 +69,CUP,SUM,0,0,0,0,0,38,4,12.536655902862549 +69,SPOON,SUM,0,0,0,0,0,1,12,24.478000164031982 +69,,SUM,0,0,0,0,2,55,20,51.74594020843506 +69,, +70,, +70,BOWL,SUM,0,0,0,0,0,6,0,11.860311031341553 +70,CUP,SUM,0,0,0,0,0,5,2,9.993144989013672 +70,SPOON,SUM,0,0,0,0,0,606,2,56.51265621185303 +70,,SUM,0,0,0,0,0,617,4,78.36611223220825 +70,, +71,, +71,BOWL,SUM,0,0,0,0,0,20,10,19.15718412399292 +71,CUP,SUM,0,0,0,0,6,32,32,33.02159118652344 +71,SPOON,SUM,0,0,0,0,0,62,4,23.902745008468628 +71,,SUM,0,0,0,0,6,114,46,76.08152031898499 +71,, +72,, +72,BOWL,SUM,0,0,0,0,0,14,2,12.478629112243652 +72,CUP,SUM,0,0,0,0,0,8,4,10.08997917175293 +72,SPOON,SUM,0,0,0,0,0,291,10,37.75545406341553 +72,,SUM,0,0,0,0,0,313,16,60.32406234741211 +72,, +73,, +73,BOWL,SUM,0,0,0,0,2,178,6,24.917768001556396 +73,CUP,SUM,0,0,0,0,0,23,9,12.59283709526062 +73,SPOON,SUM,0,0,0,0,0,113,0,21.53678607940674 +73,,SUM,0,0,0,0,2,314,15,59.047391176223755 +73,, +74,, +74,BOWL,SUM,0,0,0,0,26,15,0,23.759827852249146 +74,CUP,SUM,0,0,0,0,0,24,22,21.912806034088135 +74,SPOON,SUM,0,0,0,0,0,632,0,56.075231075286865 +74,,SUM,0,0,0,0,26,671,22,101.74786496162415 +74,, +75,, +75,BOWL,SUM,0,0,0,0,14,73,16,30.81709599494934 +75,CUP,SUM,1,0,0,1,0,344,76,0.0 +75,SPOON,SUM,0,0,0,0,2,1,0,15.252706050872803 +75,,SUM,1,0,0,1,16,418,92,46.069802045822144 +75,, +76,, +76,BOWL,SUM,0,0,0,0,0,23,6,15.559469938278198 +76,CUP,SUM,0,0,0,0,0,48,15,18.263577938079834 +76,SPOON,SUM,0,0,0,0,2,35,1,18.378031015396118 +76,,SUM,0,0,0,0,2,106,22,52.20107889175415 +76,, +77,, +77,BOWL,SUM,0,0,0,0,8,11,0,15.433710813522339 +77,CUP,SUM,0,0,0,0,0,187,34,59.61596202850342 +77,SPOON,SUM,0,0,0,0,0,79,0,20.0886709690094 +77,,SUM,0,0,0,0,8,277,34,95.13834381103516 +77,, +78,, +78,BOWL,SUM,0,0,0,0,0,19,2,12.237342119216919 +78,CUP,SUM,0,0,0,0,2,17,19,19.100642919540405 +78,SPOON,SUM,0,0,0,0,0,202,0,27.350992918014526 +78,,SUM,0,0,0,0,2,238,21,58.68897795677185 +78,, +79,, +79,BOWL,SUM,0,0,0,0,0,169,10,26.195935010910034 +79,CUP,SUM,1,0,0,1,0,393,63,0.0 +79,SPOON,SUM,0,0,0,0,0,1,6,18.789809942245483 +79,,SUM,1,0,0,1,0,563,79,44.98574495315552 +79,, +80,, +80,BOWL,SUM,0,0,0,0,0,88,3,17.867407083511353 +80,CUP,SUM,0,0,0,0,0,10,17,15.719367027282715 +80,SPOON,SUM,0,0,0,0,0,27,0,15.82221007347107 +80,,SUM,0,0,0,0,0,125,20,49.40898418426514 +80,, +81,, +81,BOWL,SUM,0,0,0,0,14,53,2,20.782339096069336 +81,CUP,SUM,0,0,0,0,0,207,49,82.17309713363647 +81,SPOON,SUM,0,0,0,0,0,124,9,28.78645396232605 +81,,SUM,0,0,0,0,14,384,60,131.74189019203186 +81,, +82,, +82,BOWL,SUM,0,0,0,0,0,16,2,12.279356002807617 +82,CUP,SUM,1,0,0,1,2,387,53,0.0 +82,SPOON,SUM,0,0,0,0,2,0,0,15.806651830673218 +82,,SUM,1,0,0,1,4,403,55,28.086007833480835 +82,, +83,, +83,BOWL,SUM,0,0,0,0,32,47,4,29.855517148971558 +83,CUP,SUM,0,0,0,0,0,16,1,12.056843996047974 +83,SPOON,SUM,0,0,0,0,0,398,0,39.66174602508545 +83,,SUM,0,0,0,0,32,461,5,81.57410717010498 +83,, +84,, +84,BOWL,SUM,0,0,0,0,6,38,0,15.703772068023682 +84,CUP,SUM,0,0,0,0,2,32,3,12.961360931396484 +84,SPOON,SUM,0,0,0,0,0,238,17,38.476255893707275 +84,,SUM,0,0,0,0,8,308,20,67.14138889312744 +84,, +85,, +85,BOWL,SUM,0,0,0,0,0,26,13,22.27264094352722 +85,CUP,SUM,0,0,0,0,0,10,15,14.38785195350647 +85,SPOON,SUM,0,0,0,0,4,35,3,22.993229150772095 +85,,SUM,0,0,0,0,4,71,31,59.653722047805786 +85,, +86,, +86,BOWL,SUM,0,0,0,0,0,3,4,14.04731011390686 +86,CUP,SUM,0,0,0,0,0,53,32,31.433166980743408 +86,SPOON,SUM,0,0,0,0,0,15,0,15.719494104385376 +86,,SUM,0,0,0,0,0,71,36,61.199971199035645 +86,, +87,, +87,BOWL,SUM,0,0,0,0,0,79,8,20.567376136779785 +87,CUP,SUM,0,0,0,0,0,51,13,16.805230140686035 +87,SPOON,SUM,0,0,0,0,0,2,0,15.051785945892334 +87,,SUM,0,0,0,0,0,132,21,52.424392223358154 +87,, +88,, +88,BOWL,SUM,0,0,0,0,0,54,5,18.304708003997803 +88,CUP,SUM,1,0,0,1,0,370,79,0.0 +88,SPOON,SUM,0,0,0,0,0,8,1,16.820173978805542 +88,,SUM,1,0,0,1,0,432,85,35.124881982803345 +88,, +89,, +89,BOWL,SUM,0,0,0,0,2,12,2,13.851810932159424 +89,CUP,SUM,0,0,0,0,0,149,26,41.3277850151062 +89,SPOON,SUM,0,0,0,0,0,106,3,23.079394102096558 +89,,SUM,0,0,0,0,2,267,31,78.25899004936218 +89,, +90,, +90,BOWL,SUM,0,0,0,0,6,21,6,17.676584005355835 +90,CUP,SUM,0,0,0,0,0,224,22,51.555423974990845 +90,SPOON,SUM,0,0,0,0,8,37,0,21.4666109085083 +90,,SUM,0,0,0,0,14,282,28,90.69861888885498 +90,, +91,, +91,BOWL,SUM,0,0,0,0,0,10,0,12.191665887832642 +91,CUP,SUM,0,0,0,0,0,28,1,12.251128196716309 +91,SPOON,SUM,0,0,0,0,10,29,2,24.303138971328735 +91,,SUM,0,0,0,0,10,67,3,48.745933055877686 +91,, +92,, +92,BOWL,SUM,0,0,0,0,2,5,0,13.14736795425415 +92,CUP,SUM,0,0,0,0,0,19,6,15.272841930389404 +92,SPOON,SUM,0,0,0,0,8,364,0,43.14427185058594 +92,,SUM,0,0,0,0,10,388,6,71.56448173522949 +92,, +93,, +93,BOWL,SUM,0,0,0,0,0,42,0,13.576515913009644 +93,CUP,SUM,1,0,0,1,0,216,74,0.0 +93,SPOON,SUM,0,0,0,0,0,97,0,21.791417121887207 +93,,SUM,1,0,0,1,0,355,74,35.36793303489685 +93,, +94,, +94,BOWL,SUM,0,0,0,0,2,23,0,13.170759916305542 +94,CUP,SUM,0,0,0,0,0,153,25,48.62360501289368 +94,SPOON,SUM,0,0,0,0,0,1,8,21.87422800064087 +94,,SUM,0,0,0,0,2,177,33,83.66859292984009 +94,, +95,, +95,BOWL,SUM,0,0,0,0,2,126,13,29.186787843704224 +95,CUP,SUM,0,0,0,0,0,13,2,10.958858966827393 +95,SPOON,SUM,0,0,0,0,0,81,0,20.180065870285034 +95,,SUM,0,0,0,0,2,220,15,60.32571268081665 +95,, +96,, +96,BOWL,SUM,0,0,0,0,0,4,0,12.166712045669556 +96,CUP,SUM,1,0,0,1,0,359,71,0.0 +96,SPOON,SUM,0,0,0,0,2,253,0,31.233459949493408 +96,,SUM,1,0,0,1,2,616,71,43.400171995162964 +96,, +97,, +97,BOWL,SUM,0,0,0,0,0,8,0,11.756173133850098 +97,CUP,SUM,0,0,0,0,0,35,11,13.14326810836792 +97,SPOON,SUM,0,0,0,0,2,5,6,19.361711025238037 +97,,SUM,0,0,0,0,2,48,17,44.261152267456055 +97,, +98,, +98,BOWL,SUM,0,0,0,0,0,1,2,12.06400990486145 +98,CUP,SUM,0,0,0,0,0,12,9,10.334068059921265 +98,SPOON,SUM,0,0,0,0,0,7,3,17.22105097770691 +98,,SUM,0,0,0,0,0,20,14,39.619128942489624 +98,, +99,, +99,BOWL,SUM,0,0,0,0,0,17,1,12.417880058288574 +99,CUP,SUM,1,0,0,1,0,294,63,0.0 +99,SPOON,SUM,0,0,0,0,6,400,0,42.676424980163574 +99,,SUM,1,0,0,1,6,711,64,55.09430503845215 +99,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_23.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_23.csv new file mode 100644 index 0000000000..014a5e2f86 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_23.csv @@ -0,0 +1,603 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,4,4,17.5716340542 +0,CUP,SUM,0,0,0,0,0,55,9,19.4416348934 +0,SPOON,SUM,0,0,0,0,2,6,4,16.9294860363 +0,,SUM,0,0,0,0,2,65,17,53.9427549839 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,56,33,0,36.8005242348 +1,CUP,SUM,0,0,0,0,0,82,19,32.4132249355 +1,SPOON,SUM,0,0,0,0,0,3,5,19.2923369408 +1,,SUM,0,0,0,0,56,118,24,88.5060861111 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,18,32,1,21.3079550266 +2,CUP,SUM,0,0,0,0,2,47,3,16.1786630154 +2,SPOON,SUM,0,0,0,0,0,43,5,24.0762009621 +2,,SUM,0,0,0,0,20,122,9,61.5628190041 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,0,44,2,12.586493969 +3,CUP,SUM,0,0,0,0,0,19,4,13.0866601467 +3,SPOON,SUM,0,0,0,0,0,16,2,14.7841489315 +3,,SUM,0,0,0,0,0,79,8,40.4573030472 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,96,0,15.8043551445 +4,CUP,SUM,1,0,1,0,0,211,111,0 +4,SPOON,SUM,0,0,0,0,0,101,0,20.9952759743 +4,,SUM,1,0,1,0,0,408,111,36.7996311188 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,2,26,2,12.688945055 +5,CUP,SUM,0,0,0,0,0,4,7,14.6775410175 +5,SPOON,SUM,0,0,0,0,0,7,1,16.1825361252 +5,,SUM,0,0,0,0,2,37,10,43.5490221977 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,0,16,4,14.0186100006 +6,CUP,SUM,0,0,0,0,2,85,24,38.2838788033 +6,SPOON,SUM,0,0,0,0,0,56,0,17.4946520329 +6,,SUM,0,0,0,0,2,157,28,69.7971408367 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,34,312,12,50.5547099113 +7,CUP,SUM,0,0,0,0,0,12,2,9.9926021099 +7,SPOON,SUM,0,0,0,0,0,128,4,26.0042510033 +7,,SUM,0,0,0,0,34,452,18,86.5515630245 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,0,17,0,11.6770071983 +8,CUP,SUM,1,0,1,0,0,223,112,0 +8,SPOON,SUM,0,0,0,0,0,48,2,16.8923089504 +8,,SUM,1,0,1,0,0,288,114,28.5693161488 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,4,4,18.0801069736 +9,CUP,SUM,0,0,0,0,0,55,9,21.4746448994 +9,SPOON,SUM,0,0,0,0,2,6,4,17.9350988865 +9,,SUM,0,0,0,0,2,65,17,57.4898507595 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,56,33,0,41.5058259964 +10,CUP,SUM,0,0,0,0,0,82,19,35.7338111401 +10,SPOON,SUM,0,0,0,0,0,3,5,20.5338299274 +10,,SUM,0,0,0,0,56,118,24,97.7734670639 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,18,32,1,23.6723239422 +11,CUP,SUM,0,0,0,0,2,47,3,17.6801428795 +11,SPOON,SUM,0,0,0,0,0,43,5,26.4655170441 +11,,SUM,0,0,0,0,20,122,9,67.8179838657 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,0,44,2,13.1662709713 +12,CUP,SUM,0,0,0,0,0,19,4,13.0682039261 +12,SPOON,SUM,0,0,0,0,0,16,2,15.3152089119 +12,,SUM,0,0,0,0,0,79,8,41.5496838093 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,0,96,0,15.6802790165 +13,CUP,SUM,1,0,1,0,0,211,111,0 +13,SPOON,SUM,0,0,0,0,0,101,0,21.0154089928 +13,,SUM,1,0,1,0,0,408,111,36.6956880093 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,2,26,2,12.5678629875 +14,CUP,SUM,0,0,0,0,0,4,7,14.6379430294 +14,SPOON,SUM,0,0,0,0,0,7,1,16.2660369873 +14,,SUM,0,0,0,0,2,37,10,43.4718430042 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,0,16,4,13.8152770996 +15,CUP,SUM,0,0,0,0,2,85,24,38.1496729851 +15,SPOON,SUM,0,0,0,0,0,56,0,17.1152851582 +15,,SUM,0,0,0,0,2,157,28,69.0802352428 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,34,312,12,50.5147790909 +16,CUP,SUM,0,0,0,0,0,12,2,10.0440628529 +16,SPOON,SUM,0,0,0,0,0,128,4,25.5890719891 +16,,SUM,0,0,0,0,34,452,18,86.1479139328 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,0,17,0,11.7943370342 +17,CUP,SUM,1,0,1,0,0,223,112,0 +17,SPOON,SUM,0,0,0,0,0,48,2,16.8464679718 +17,,SUM,1,0,1,0,0,288,114,28.640805006 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,0,6,0,11.3148088455 +18,CUP,SUM,0,0,0,0,0,38,5,15.6674668789 +18,SPOON,SUM,1,0,1,0,2,1107,58,0 +18,,SUM,1,0,1,0,2,1151,63,26.9822757244 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,20,1,12.3129169941 +19,CUP,SUM,0,0,0,0,0,157,35,63.7877619267 +19,SPOON,SUM,0,0,0,0,0,7,16,27.0735828876 +19,,SUM,0,0,0,0,0,184,52,103.1742618084 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,10,13,1,17.1791968346 +20,CUP,SUM,0,0,0,0,0,48,7,15.7053399086 +20,SPOON,SUM,0,0,0,0,0,8,2,17.9993610382 +20,,SUM,0,0,0,0,10,69,10,50.8838977814 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,98,17,26.6209249496 +21,CUP,SUM,0,0,0,0,0,7,4,9.7912361622 +21,SPOON,SUM,0,0,0,0,0,73,1,20.5449922085 +21,,SUM,0,0,0,0,0,178,22,56.9571533203 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,2,19,2,12.5121331215 +22,CUP,SUM,0,0,0,0,0,88,16,31.1956171989 +22,SPOON,SUM,1,0,1,0,4,635,83,0 +22,,SUM,1,0,1,0,6,742,101,43.7077503204 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,16,0,11.5749959946 +23,CUP,SUM,0,0,0,0,0,9,10,10.0895562172 +23,SPOON,SUM,0,0,0,0,0,159,3,29.0062940121 +23,,SUM,0,0,0,0,0,184,13,50.6708462238 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,0,20,1,11.9258360863 +24,CUP,SUM,0,0,0,0,0,30,1,11.8613040447 +24,SPOON,SUM,0,0,0,0,0,198,3,31.4805071354 +24,,SUM,0,0,0,0,0,248,5,55.2676472664 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,0,91,2,16.1815700531 +25,CUP,SUM,0,0,0,0,0,1,9,9.7956678867 +25,SPOON,SUM,0,0,0,0,2,35,12,24.8946299553 +25,,SUM,0,0,0,0,2,127,23,50.8718678951 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,0,168,52,58.0166120529 +26,CUP,SUM,0,0,0,0,0,92,18,26.9181129932 +26,SPOON,SUM,0,0,0,0,0,78,1,20.511852026 +26,,SUM,0,0,0,0,0,338,71,105.4465770721 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,0,4,2,11.6590487957 +27,CUP,SUM,0,0,0,0,0,184,33,57.5904629231 +27,SPOON,SUM,1,0,1,0,0,1340,28,0 +27,,SUM,1,0,1,0,0,1528,63,69.2495117188 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,4,29,0,13.3160810471 +28,CUP,SUM,0,0,0,0,8,26,1,15.7224040031 +28,SPOON,SUM,0,0,0,0,0,8,2,15.2901558876 +28,,SUM,0,0,0,0,12,63,3,44.3286409378 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,6,4,4,14.9229180813 +29,CUP,SUM,0,0,0,0,0,29,21,21.172852993 +29,SPOON,SUM,0,0,0,0,10,40,0,19.9652061462 +29,,SUM,0,0,0,0,16,73,25,56.0609772205 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,2,2,0,12.0351610184 +30,CUP,SUM,0,0,0,0,0,6,4,9.7417128086 +30,SPOON,SUM,1,0,1,0,0,1545,28,0 +30,,SUM,1,0,1,0,2,1553,32,21.776873827 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,322,122,2,163.0332980156 +31,CUP,SUM,0,0,0,0,0,12,2,9.8832650185 +31,SPOON,SUM,1,0,1,0,70,856,6,0 +31,,SUM,1,0,1,0,392,990,10,172.9165630341 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,0,0,0,11.2032630444 +32,CUP,SUM,1,0,1,0,0,198,112,0 +32,SPOON,SUM,0,0,0,0,0,49,2,17.0390479565 +32,,SUM,1,0,1,0,0,247,114,28.2423110008 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,4,4,17.4277670383 +33,CUP,SUM,0,0,0,0,0,55,9,19.6992499828 +33,SPOON,SUM,0,0,0,0,2,6,4,16.8153460026 +33,,SUM,0,0,0,0,2,65,17,53.9423630238 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,56,33,0,38.0098500252 +34,CUP,SUM,0,0,0,0,0,82,19,32.5568349361 +34,SPOON,SUM,0,0,0,0,0,3,5,19.8923809528 +34,,SUM,0,0,0,0,56,118,24,90.4590659142 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,18,32,1,21.5439460278 +35,CUP,SUM,0,0,0,0,2,47,3,16.1329660416 +35,SPOON,SUM,0,0,0,0,0,43,5,24.3047480583 +35,,SUM,0,0,0,0,20,122,9,61.9816601276 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,0,44,2,12.7741150856 +36,CUP,SUM,0,0,0,0,0,19,4,13.4126889706 +36,SPOON,SUM,0,0,0,0,0,16,2,15.1960949898 +36,,SUM,0,0,0,0,0,79,8,41.3828990459 +36,,,,,,,,,, +37,,,,,,,,,, +37,BOWL,SUM,0,0,0,0,0,96,0,15.7407610416 +37,CUP,SUM,1,0,1,0,0,211,111,0 +37,SPOON,SUM,0,0,0,0,0,101,0,20.8453609943 +37,,SUM,1,0,1,0,0,408,111,36.586122036 +37,,,,,,,,,, +38,,,,,,,,,, +38,BOWL,SUM,0,0,0,0,2,26,2,12.5227241516 +38,CUP,SUM,0,0,0,0,0,4,7,14.5791881084 +38,SPOON,SUM,0,0,0,0,0,7,1,16.0815799236 +38,,SUM,0,0,0,0,2,37,10,43.1834921837 +38,,,,,,,,,, +39,,,,,,,,,, +39,BOWL,SUM,0,0,0,0,0,16,4,13.6114439964 +39,CUP,SUM,0,0,0,0,2,85,24,37.9522621632 +39,SPOON,SUM,0,0,0,0,0,56,0,16.8924138546 +39,,SUM,0,0,0,0,2,157,28,68.4561200142 +39,,,,,,,,,, +40,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,34,312,12,50.6537780762 +40,CUP,SUM,0,0,0,0,0,12,2,10.0361227989 +40,SPOON,SUM,0,0,0,0,0,128,4,25.5381669998 +40,,SUM,0,0,0,0,34,452,18,86.2280678749 +40,,,,,,,,,, +41,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,0,17,0,11.3363130093 +41,CUP,SUM,1,0,1,0,0,223,112,0 +41,SPOON,SUM,0,0,0,0,0,48,2,16.7650251389 +41,,SUM,1,0,1,0,0,288,114,28.1013381481 +41,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,0,6,0,11.3198149204 +42,CUP,SUM,0,0,0,0,0,38,5,15.3017270565 +42,SPOON,SUM,1,0,1,0,2,1107,58,0 +42,,SUM,1,0,1,0,2,1151,63,26.6215419769 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,0,20,1,12.1962120533 +43,CUP,SUM,0,0,0,0,0,157,35,62.4545969963 +43,SPOON,SUM,0,0,0,0,0,7,16,26.9644839764 +43,,SUM,0,0,0,0,0,184,52,101.615293026 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,10,13,1,17.2791688442 +44,CUP,SUM,0,0,0,0,0,48,7,15.2073619366 +44,SPOON,SUM,0,0,0,0,0,8,2,17.8622179031 +44,,SUM,0,0,0,0,10,69,10,50.3487486839 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,0,98,17,26.4498870373 +45,CUP,SUM,0,0,0,0,0,7,4,9.6623880863 +45,SPOON,SUM,0,0,0,0,0,73,1,20.4326348305 +45,,SUM,0,0,0,0,0,178,22,56.5449099541 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,2,19,2,12.6613600254 +46,CUP,SUM,0,0,0,0,0,88,16,30.8820381165 +46,SPOON,SUM,1,0,1,0,4,635,83,0 +46,,SUM,1,0,1,0,6,742,101,43.5433981419 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,0,0,0,0,0,16,0,11.7881770134 +47,CUP,SUM,0,0,0,0,0,9,10,10.2549099922 +47,SPOON,SUM,0,0,0,0,0,159,3,29.1220958233 +47,,SUM,0,0,0,0,0,184,13,51.1651828289 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,0,20,1,11.7891380787 +48,CUP,SUM,0,0,0,0,0,30,1,11.8420460224 +48,SPOON,SUM,0,0,0,0,0,198,3,31.0835821629 +48,,SUM,0,0,0,0,0,248,5,54.714766264 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,0,91,2,15.9377610683 +49,CUP,SUM,0,0,0,0,0,1,9,9.9264090061 +49,SPOON,SUM,0,0,0,0,2,35,12,24.5458981991 +49,,SUM,0,0,0,0,2,127,23,50.4100682735 +49,,,,,,,,,, +50,,,,,,,,,, +50,BOWL,SUM,0,0,0,0,0,168,52,57.6521639824 +50,CUP,SUM,0,0,0,0,0,92,18,26.8697309494 +50,SPOON,SUM,0,0,0,0,0,78,1,20.8240039349 +50,,SUM,0,0,0,0,0,338,71,105.3458988667 +50,,,,,,,,,, +51,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,0,4,2,11.4290399551 +51,CUP,SUM,0,0,0,0,0,184,33,57.0652248859 +51,SPOON,SUM,1,0,1,0,0,1340,28,0 +51,,SUM,1,0,1,0,0,1528,63,68.4942648411 +51,,,,,,,,,, +52,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,4,29,0,13.2588009834 +52,CUP,SUM,0,0,0,0,8,26,1,15.4761948586 +52,SPOON,SUM,0,0,0,0,0,8,2,15.3842058182 +52,,SUM,0,0,0,0,12,63,3,44.1192016602 +52,,,,,,,,,, +53,,,,,,,,,, +53,BOWL,SUM,0,0,0,0,6,4,4,14.7245700359 +53,CUP,SUM,0,0,0,0,0,29,21,21.4173891544 +53,SPOON,SUM,0,0,0,0,10,40,0,20.0968501568 +53,,SUM,0,0,0,0,16,73,25,56.2388093472 +53,,,,,,,,,, +54,,,,,,,,,, +54,BOWL,SUM,0,0,0,0,2,2,0,11.9175410271 +54,CUP,SUM,0,0,0,0,0,6,4,9.4509279728 +54,SPOON,SUM,1,0,1,0,0,1545,28,0 +54,,SUM,1,0,1,0,2,1553,32,21.3684689999 +54,,,,,,,,,, +55,,,,,,,,,, +55,BOWL,SUM,0,0,0,0,322,122,2,160.9695210457 +55,CUP,SUM,0,0,0,0,0,12,2,9.711648941 +55,SPOON,SUM,1,0,1,0,70,856,6,0 +55,,SUM,1,0,1,0,392,990,10,170.6811699867 +55,,,,,,,,,, +56,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,0,0,0,11.3280420303 +56,CUP,SUM,1,0,1,0,0,198,112,0 +56,SPOON,SUM,0,0,0,0,0,49,2,16.9925980568 +56,,SUM,1,0,1,0,0,247,114,28.3206400871 +56,,,,,,,,,, +57,,,,,,,,,, +57,BOWL,SUM,0,0,0,0,24,33,0,22.9728081226 +57,CUP,SUM,1,0,0,1,0,281,61,0 +57,SPOON,SUM,0,0,0,0,0,1,2,14.8020370007 +57,,SUM,1,0,0,1,24,315,63,37.7748451233 +57,,,,,,,,,, +58,,,,,,,,,, +58,BOWL,SUM,0,0,0,0,0,12,0,11.7954099178 +58,CUP,SUM,0,0,0,0,0,21,3,11.7812108994 +58,SPOON,SUM,0,0,0,0,0,446,4,44.8120770454 +58,,SUM,0,0,0,0,0,479,7,68.3886978626 +58,,,,,,,,,, +59,,,,,,,,,, +59,BOWL,SUM,0,0,0,0,0,243,103,100.5761508942 +59,CUP,SUM,0,0,0,0,0,8,8,12.5209720135 +59,SPOON,SUM,1,0,1,0,2,1527,10,0 +59,,SUM,1,0,1,0,2,1778,121,113.0971229076 +59,,,,,,,,,, +60,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,0,192,11,33.6850159168 +60,CUP,SUM,0,0,0,0,0,56,11,21.5535101891 +60,SPOON,SUM,0,0,0,0,0,30,0,16.1786220074 +60,,SUM,0,0,0,0,0,278,22,71.4171481133 +60,,,,,,,,,, +61,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,0,10,0,11.6730358601 +61,CUP,SUM,0,0,0,0,48,37,16,40.4139950275 +61,SPOON,SUM,1,0,1,0,2,1465,18,0 +61,,SUM,1,0,1,0,50,1512,34,52.0870308876 +61,,,,,,,,,, +62,,,,,,,,,, +62,BOWL,SUM,0,0,0,0,0,14,0,12.6886808872 +62,CUP,SUM,1,0,1,0,2,143,112,0 +62,SPOON,SUM,0,0,0,0,0,0,4,16.9858191013 +62,,SUM,1,0,1,0,2,157,116,29.6744999886 +62,,,,,,,,,, +63,,,,,,,,,, +63,BOWL,SUM,0,0,0,0,0,45,8,18.1703219414 +63,CUP,SUM,0,0,0,0,2,7,6,11.2310080528 +63,SPOON,SUM,0,0,0,0,0,30,2,19.1364359856 +63,,SUM,0,0,0,0,2,82,16,48.5377659798 +63,,,,,,,,,, +64,,,,,,,,,, +64,BOWL,SUM,0,0,0,0,2,12,0,12.921875 +64,CUP,SUM,0,0,0,0,0,93,13,26.7180919647 +64,SPOON,SUM,0,0,0,0,0,22,3,20.1819729805 +64,,SUM,0,0,0,0,2,127,16,59.8219399452 +64,,,,,,,,,, +65,,,,,,,,,, +65,BOWL,SUM,0,0,0,0,0,203,18,34.3697149754 +65,CUP,SUM,0,0,0,0,2,68,16,35.4700160027 +65,SPOON,SUM,0,0,0,0,0,37,8,21.5068860054 +65,,SUM,0,0,0,0,2,308,42,91.3466169834 +65,,,,,,,,,, +66,,,,,,,,,, +66,BOWL,SUM,0,0,0,0,0,23,0,12.1334168911 +66,CUP,SUM,0,0,0,0,0,12,4,10.2397680283 +66,SPOON,SUM,0,0,0,0,4,157,4,33.1031339169 +66,,SUM,0,0,0,0,4,192,8,55.4763188362 +66,,,,,,,,,, +67,,,,,,,,,, +67,BOWL,SUM,0,0,0,0,0,32,0,12.6780040264 +67,CUP,SUM,0,0,0,0,0,100,24,46.1033549309 +67,SPOON,SUM,0,0,0,0,0,37,1,18.8906981945 +67,,SUM,0,0,0,0,0,169,25,77.6720571518 +67,,,,,,,,,, +68,,,,,,,,,, +68,BOWL,SUM,1,0,1,0,0,200,104,0 +68,CUP,SUM,1,0,1,0,0,155,107,0 +68,SPOON,SUM,1,0,1,0,0,1644,0,0 +68,,SUM,3,0,3,0,0,1999,211,0 +68,,,,,,,,,, +69,,,,,,,,,, +69,BOWL,SUM,0,0,0,0,0,4,0,11.6119709015 +69,CUP,SUM,0,0,0,0,0,29,7,13.0138311386 +69,SPOON,SUM,1,0,1,0,0,1452,12,0 +69,,SUM,1,0,1,0,0,1485,19,24.6258020401 +69,,,,,,,,,, +70,,,,,,,,,, +70,BOWL,SUM,0,0,0,0,2,6,0,12.8745610714 +70,CUP,SUM,1,0,0,1,0,280,53,0 +70,SPOON,SUM,0,0,0,0,66,10,7,54.6645619869 +70,,SUM,1,0,0,1,68,296,60,67.5391230583 +70,,,,,,,,,, +71,,,,,,,,,, +71,BOWL,SUM,0,0,0,0,2,7,0,12.241964817 +71,CUP,SUM,1,0,1,0,0,156,112,0 +71,SPOON,SUM,0,0,0,0,0,42,2,17.723690033 +71,,SUM,1,0,1,0,2,205,114,29.96565485 +71,,,,,,,,,, +72,,,,,,,,,, +72,BOWL,SUM,0,0,0,0,0,10,0,11.426774025 +72,CUP,SUM,0,0,0,0,0,16,0,9.8449981213 +72,SPOON,SUM,0,0,0,0,0,196,1,28.5257689953 +72,,SUM,0,0,0,0,0,222,1,49.7975411415 +72,,,,,,,,,, +73,,,,,,,,,, +73,BOWL,SUM,0,0,0,0,0,15,2,11.8330690861 +73,CUP,SUM,0,0,0,0,0,8,0,9.4882118702 +73,SPOON,SUM,0,0,0,0,0,522,2,50.2431609631 +73,,SUM,0,0,0,0,0,545,4,71.5644419193 +73,,,,,,,,,, +74,,,,,,,,,, +74,BOWL,SUM,0,0,0,0,0,86,20,28.0851528645 +74,CUP,SUM,1,0,1,0,0,132,94,0 +74,SPOON,SUM,0,0,0,0,0,249,3,31.2668969631 +74,,SUM,1,0,1,0,0,467,117,59.3520498276 +74,,,,,,,,,, +75,,,,,,,,,, +75,BOWL,SUM,0,0,0,0,2,10,0,12.2688360214 +75,CUP,SUM,0,0,0,0,0,88,23,38.380095005 +75,SPOON,SUM,0,0,0,0,0,11,1,16.2518131733 +75,,SUM,0,0,0,0,2,109,24,66.9007441998 +75,,,,,,,,,, +76,,,,,,,,,, +76,BOWL,SUM,0,0,0,0,0,10,0,11.2944850922 +76,CUP,SUM,0,0,0,0,0,8,3,10.0129680634 +76,SPOON,SUM,0,0,0,0,0,260,6,33.9424290657 +76,,SUM,0,0,0,0,0,278,9,55.2498822212 +76,,,,,,,,,, +77,,,,,,,,,, +77,BOWL,SUM,0,0,0,0,0,10,1,13.1931428909 +77,CUP,SUM,0,0,0,0,0,9,0,9.751516819 +77,SPOON,SUM,0,0,0,0,0,10,4,18.1173081398 +77,,SUM,0,0,0,0,0,29,5,41.0619678497 +77,,,,,,,,,, +78,,,,,,,,,, +78,BOWL,SUM,0,0,0,0,0,34,4,14.1389770508 +78,CUP,SUM,0,0,0,0,0,115,28,44.1766660213 +78,SPOON,SUM,0,0,0,0,2,12,0,15.4181218147 +78,,SUM,0,0,0,0,2,161,32,73.7337648869 +78,,,,,,,,,, +79,,,,,,,,,, +79,BOWL,SUM,0,0,0,0,0,8,0,11.5186760426 +79,CUP,SUM,0,0,0,0,0,32,5,15.583384037 +79,SPOON,SUM,1,0,1,0,14,1418,16,0 +79,,SUM,1,0,1,0,14,1458,21,27.1020600796 +79,,,,,,,,,, +80,,,,,,,,,, +80,BOWL,SUM,0,0,0,0,0,6,2,11.698745966 +80,CUP,SUM,0,0,0,0,0,132,28,42.1430940628 +80,SPOON,SUM,0,0,0,0,0,28,5,22.9585101604 +80,,SUM,0,0,0,0,0,166,35,76.8003501892 +80,,,,,,,,,, +81,,,,,,,,,, +81,BOWL,SUM,0,0,0,0,0,3,4,13.5740571022 +81,CUP,SUM,1,0,1,0,0,152,112,0 +81,SPOON,SUM,0,0,0,0,0,609,25,65.4494850636 +81,,SUM,1,0,1,0,0,764,141,79.0235421658 +81,,,,,,,,,, +82,,,,,,,,,, +82,BOWL,SUM,0,0,0,0,10,51,0,17.1875798702 +82,CUP,SUM,1,0,1,0,56,393,109,0 +82,SPOON,SUM,1,0,1,0,0,1410,24,0 +82,,SUM,2,0,2,0,66,1854,133,17.1875798702 +82,,,,,,,,,, +83,,,,,,,,,, +83,BOWL,SUM,0,0,0,0,0,6,0,11.9714441299 +83,CUP,SUM,0,0,0,0,0,7,7,10.4866909981 +83,SPOON,SUM,0,0,0,0,4,11,4,19.7361738682 +83,,SUM,0,0,0,0,4,24,11,42.1943089962 +83,,,,,,,,,, +84,,,,,,,,,, +84,BOWL,SUM,0,0,0,0,2,64,22,30.489784956 +84,CUP,SUM,0,0,0,0,6,8,5,12.1371769905 +84,SPOON,SUM,0,0,0,0,0,12,5,19.9708070755 +84,,SUM,0,0,0,0,8,84,32,62.597769022 +84,,,,,,,,,, +85,,,,,,,,,, +85,BOWL,SUM,0,0,0,0,2,12,0,12.5614521503 +85,CUP,SUM,0,0,0,0,0,10,11,13.4567670822 +85,SPOON,SUM,1,0,1,0,0,1383,24,0 +85,,SUM,1,0,1,0,2,1405,35,26.0182192326 +85,,,,,,,,,, +86,,,,,,,,,, +86,BOWL,SUM,0,0,0,0,0,43,10,19.1295990944 +86,CUP,SUM,0,0,0,0,0,12,8,10.407184124 +86,SPOON,SUM,0,0,0,0,58,316,0,61.5393950939 +86,,SUM,0,0,0,0,58,371,18,91.0761783123 +86,,,,,,,,,, +87,,,,,,,,,, +87,BOWL,SUM,0,0,0,0,0,25,0,12.2027368546 +87,CUP,SUM,0,0,0,0,0,18,9,15.4101610184 +87,SPOON,SUM,0,0,0,0,0,113,0,21.3580830097 +87,,SUM,0,0,0,0,0,156,9,48.9709808826 +87,,,,,,,,,, +88,,,,,,,,,, +88,BOWL,SUM,0,0,0,0,0,34,0,12.7008519173 +88,CUP,SUM,1,0,1,0,18,282,94,0 +88,SPOON,SUM,0,0,0,0,0,58,4,24.5023488998 +88,,SUM,1,0,1,0,18,374,98,37.2032008171 +88,,,,,,,,,, +89,,,,,,,,,, +89,BOWL,SUM,0,0,0,0,0,10,0,11.4643411636 +89,CUP,SUM,0,0,0,0,2,5,2,10.3784909248 +89,SPOON,SUM,0,0,0,0,0,77,3,21.4177660942 +89,,SUM,0,0,0,0,2,92,5,43.2605981827 +89,,,,,,,,,, +90,,,,,,,,,, +90,BOWL,SUM,0,0,0,0,0,64,2,14.2040040493 +90,CUP,SUM,0,0,0,0,0,26,3,10.5875091553 +90,SPOON,SUM,0,0,0,0,0,41,0,17.2069540024 +90,,SUM,0,0,0,0,0,131,5,41.998467207 +90,,,,,,,,,, +91,,,,,,,,,, +91,BOWL,SUM,0,0,0,0,0,37,8,17.6730949879 +91,CUP,SUM,0,0,0,0,0,95,30,46.7202019691 +91,SPOON,SUM,0,0,0,0,2,69,1,19.4828600883 +91,,SUM,0,0,0,0,2,201,39,83.8761570454 +91,,,,,,,,,, +92,,,,,,,,,, +92,BOWL,SUM,0,0,0,0,0,410,28,53.0840809345 +92,CUP,SUM,0,0,0,0,8,10,3,15.5654091835 +92,SPOON,SUM,0,0,0,0,0,608,1,55.1510210037 +92,,SUM,0,0,0,0,8,1028,32,123.8005111218 +92,,,,,,,,,, +93,,,,,,,,,, +93,BOWL,SUM,0,0,0,0,0,12,0,12.3146522045 +93,CUP,SUM,1,0,1,0,2,329,112,0 +93,SPOON,SUM,0,0,0,0,2,30,0,16.6185059547 +93,,SUM,1,0,1,0,4,371,112,28.9331581593 +93,,,,,,,,,, +94,,,,,,,,,, +94,BOWL,SUM,0,0,0,0,0,50,0,13.3685188293 +94,CUP,SUM,0,0,0,0,0,8,8,11.024638176 +94,SPOON,SUM,0,0,0,0,0,28,2,18.6950039864 +94,,SUM,0,0,0,0,0,86,10,43.0881609917 +94,,,,,,,,,, +95,,,,,,,,,, +95,BOWL,SUM,0,0,0,0,0,31,10,19.4320070744 +95,CUP,SUM,0,0,0,0,0,27,7,11.5381388664 +95,SPOON,SUM,1,0,1,0,0,1394,32,0 +95,,SUM,1,0,1,0,0,1452,49,30.9701459408 +95,,,,,,,,,, +96,, +96,BOWL,SUM,0,0,0,0,0,4,4,16.489403009414673 +96,CUP,SUM,0,0,0,0,0,55,9,19.545895099639893 +96,SPOON,SUM,0,0,0,0,2,6,4,17.2055721282959 +96,,SUM,0,0,0,0,2,65,17,53.240870237350464 +96,, +97,, +97,BOWL,SUM,0,0,0,0,56,33,0,39.56890106201172 +97,CUP,SUM,0,0,0,0,0,82,19,32.32267904281616 +97,SPOON,SUM,0,0,0,0,0,3,5,19.56752610206604 +97,,SUM,0,0,0,0,56,118,24,91.45910620689392 +97,, +98,, +98,BOWL,SUM,0,0,0,0,18,32,1,22.297812938690186 +98,CUP,SUM,0,0,0,0,2,47,3,16.502789974212646 +98,SPOON,SUM,0,0,0,0,0,43,5,24.380967140197754 +98,,SUM,0,0,0,0,20,122,9,63.181570053100586 +98,, +99,, +99,BOWL,SUM,0,0,0,0,0,44,2,12.503745079040527 +99,CUP,SUM,0,0,0,0,0,19,4,12.852078914642334 +99,SPOON,SUM,0,0,0,0,0,16,2,14.891032218933105 +99,,SUM,0,0,0,0,0,79,8,40.24685621261597 +99,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_24.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_24.csv new file mode 100644 index 0000000000..7e0c1b62f0 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_orig_kitchen_var_data_offset_24.csv @@ -0,0 +1,603 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,8,0,14.5587670803 +0,CUP,SUM,1,0,1,0,0,246,95,0 +0,SPOON,SUM,1,0,1,0,4,1581,0,0 +0,,SUM,2,0,2,0,4,1835,95,14.5587670803 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,0,80,30,36.3957979679 +1,CUP,SUM,0,0,0,0,0,77,16,34.3625080585 +1,SPOON,SUM,1,0,1,0,0,1502,14,0 +1,,SUM,1,0,1,0,0,1659,60,70.7583060265 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,0,7,6,14.3585660458 +2,CUP,SUM,0,0,0,0,0,10,8,10.158673048 +2,SPOON,SUM,0,0,0,0,8,78,3,24.3467988968 +2,,SUM,0,0,0,0,8,95,17,48.8640379906 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,0,10,4,13.1129789352 +3,CUP,SUM,1,0,1,0,0,153,96,0 +3,SPOON,SUM,0,0,0,0,6,92,4,22.6893649101 +3,,SUM,1,0,1,0,6,255,104,35.8023438454 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,25,0,11.6274368763 +4,CUP,SUM,0,0,0,0,2,10,10,12.1225669384 +4,SPOON,SUM,0,0,0,0,0,6,6,17.8500339985 +4,,SUM,0,0,0,0,2,41,16,41.6000378132 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,0,7,0,11.4442329407 +5,CUP,SUM,0,0,0,0,0,20,2,13.1928701401 +5,SPOON,SUM,1,0,1,0,0,970,60,0 +5,,SUM,1,0,1,0,0,997,62,24.6371030807 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,2,10,0,11.7734761238 +6,CUP,SUM,0,0,0,0,0,37,36,34.5613100529 +6,SPOON,SUM,0,0,0,0,0,51,12,23.9673299789 +6,,SUM,0,0,0,0,2,98,48,70.3021161556 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,6,22,1,15.1259889603 +7,CUP,SUM,0,0,0,0,0,18,4,15.0457670689 +7,SPOON,SUM,1,0,1,0,0,1498,18,0 +7,,SUM,1,0,1,0,6,1538,23,30.1717560291 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,2,31,4,14.5450110435 +8,CUP,SUM,0,0,0,0,16,36,9,22.9440920353 +8,SPOON,SUM,0,0,0,0,2,105,3,25.415979147 +8,,SUM,0,0,0,0,20,172,16,62.9050822258 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,32,5,15.1207740307 +9,CUP,SUM,0,0,0,0,0,16,2,9.9891061783 +9,SPOON,SUM,0,0,0,0,0,21,1,15.2303538322 +9,,SUM,0,0,0,0,0,69,8,40.3402340412 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,58,57,8,43.2434282303 +10,CUP,SUM,0,0,0,0,0,37,1,12.1449420452 +10,SPOON,SUM,1,0,1,0,0,1308,46,0 +10,,SUM,1,0,1,0,58,1402,55,55.3883702755 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,0,33,10,19.9012920856 +11,CUP,SUM,0,0,0,0,8,12,9,17.1729691029 +11,SPOON,SUM,0,0,0,0,0,26,0,15.2908670902 +11,,SUM,0,0,0,0,8,71,19,52.3651282787 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,1,0,1,0,0,485,96,0 +12,CUP,SUM,1,0,0,1,0,165,70,0 +12,SPOON,SUM,1,0,1,0,0,1412,30,0 +12,,SUM,3,0,2,1,0,2062,196,0 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,2,15,2,12.6332809925 +13,CUP,SUM,0,0,0,0,0,116,31,45.6210238934 +13,SPOON,SUM,0,0,0,0,0,57,1,17.4619050026 +13,,SUM,0,0,0,0,2,188,34,75.7162098885 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,0,13,0,11.4789869785 +14,CUP,SUM,0,0,0,0,0,12,8,10.0131118298 +14,SPOON,SUM,0,0,0,0,2,8,1,16.868724823 +14,,SUM,0,0,0,0,2,33,9,38.3608236313 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,0,7,0,11.6051900387 +15,CUP,SUM,0,0,0,0,0,55,24,39.4590990543 +15,SPOON,SUM,0,0,0,0,0,159,4,25.4759171009 +15,,SUM,0,0,0,0,0,221,28,76.5402061939 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,6,3,13.5761630535 +16,CUP,SUM,1,0,1,0,0,514,87,0 +16,SPOON,SUM,0,0,0,0,0,13,14,26.7668828964 +16,,SUM,1,0,1,0,0,533,104,40.3430459499 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,0,27,1,13.6072800159 +17,CUP,SUM,1,0,1,0,0,237,112,0 +17,SPOON,SUM,0,0,0,0,0,27,5,19.9880068302 +17,,SUM,1,0,1,0,0,291,118,33.5952868462 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,0,39,9,18.9138531685 +18,CUP,SUM,0,0,0,0,0,17,0,10.4959058762 +18,SPOON,SUM,0,0,0,0,0,20,6,20.3762631416 +18,,SUM,0,0,0,0,0,76,15,49.7860221863 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,32,23,1,28.3958170414 +19,CUP,SUM,0,0,0,0,0,124,36,52.7314310074 +19,SPOON,SUM,0,0,0,0,10,18,2,22.4617929459 +19,,SUM,0,0,0,0,42,165,39,103.5890409946 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,0,58,4,15.5366549492 +20,CUP,SUM,1,0,1,0,0,128,103,0 +20,SPOON,SUM,0,0,0,0,0,1,1,16.3208339214 +20,,SUM,1,0,1,0,0,187,108,31.8574888706 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,12,0,11.5648970604 +21,CUP,SUM,0,0,0,0,0,9,0,9.6473062038 +21,SPOON,SUM,0,0,0,0,0,189,9,31.8942639828 +21,,SUM,0,0,0,0,0,210,9,53.106467247 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,0,18,8,17.3270578384 +22,CUP,SUM,0,0,0,0,0,9,3,10.3105170727 +22,SPOON,SUM,0,0,0,0,0,16,0,15.0868079662 +22,,SUM,0,0,0,0,0,43,11,42.7243828773 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,46,12,20.8605680466 +23,CUP,SUM,1,0,0,1,0,227,60,0 +23,SPOON,SUM,0,0,0,0,0,210,5,34.9356329441 +23,,SUM,1,0,0,1,0,483,77,55.7962009907 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,0,24,0,12.069726944 +24,CUP,SUM,0,0,0,0,0,48,20,33.5206210613 +24,SPOON,SUM,0,0,0,0,0,1,2,17.9614751339 +24,,SUM,0,0,0,0,0,73,22,63.5518231392 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,2,15,6,15.9225189686 +25,CUP,SUM,0,0,0,0,0,13,13,15.481607914 +25,SPOON,SUM,0,0,0,0,0,17,8,27.4611940384 +25,,SUM,0,0,0,0,2,45,27,58.8653209209 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,0,28,0,12.2244851589 +26,CUP,SUM,1,0,0,1,0,288,60,0 +26,SPOON,SUM,0,0,0,0,0,3,1,16.5359528065 +26,,SUM,1,0,0,1,0,319,61,28.7604379654 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,0,86,10,21.1301589012 +27,CUP,SUM,0,0,0,0,2,87,23,36.6329979897 +27,SPOON,SUM,0,0,0,0,0,186,19,37.258341074 +27,,SUM,0,0,0,0,2,359,52,95.0214979649 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,0,66,16,24.7831311226 +28,CUP,SUM,0,0,0,0,0,96,19,35.1585199833 +28,SPOON,SUM,0,0,0,0,0,31,4,21.5473620892 +28,,SUM,0,0,0,0,0,193,39,81.489013195 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,0,8,0,11.3191020489 +29,CUP,SUM,0,0,0,0,0,48,2,12.3733718395 +29,SPOON,SUM,0,0,0,0,0,25,0,15.3750908375 +29,,SUM,0,0,0,0,0,81,2,39.0675647259 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,0,3,4,13.6438319683 +30,CUP,SUM,0,0,0,0,0,17,2,10.2048580647 +30,SPOON,SUM,0,0,0,0,22,355,2,47.432872057 +30,,SUM,0,0,0,0,22,375,8,71.2815620899 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,0,565,59,102.5721609592 +31,CUP,SUM,0,0,0,0,0,92,25,43.1652269363 +31,SPOON,SUM,0,0,0,0,8,44,2,23.864828825 +31,,SUM,0,0,0,0,8,701,86,169.6022167206 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,2,61,26,34.4847509861 +32,CUP,SUM,0,0,0,0,0,32,0,10.9557831287 +32,SPOON,SUM,0,0,0,0,0,87,3,22.4030470848 +32,,SUM,0,0,0,0,2,180,29,67.8435811996 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,42,0,12.7927818298 +33,CUP,SUM,0,0,0,0,0,19,3,10.4473018646 +33,SPOON,SUM,0,0,0,0,0,655,26,71.3341021538 +33,,SUM,0,0,0,0,0,716,29,94.5741858482 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,2,19,0,12.9202580452 +34,CUP,SUM,0,0,0,0,0,15,7,11.8734748363 +34,SPOON,SUM,0,0,0,0,0,9,3,19.5156669617 +34,,SUM,0,0,0,0,2,43,10,44.3093998432 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,0,19,0,12.0618848801 +35,CUP,SUM,1,0,1,0,0,121,112,0 +35,SPOON,SUM,0,0,0,0,0,272,1,33.1823079586 +35,,SUM,1,0,1,0,0,412,113,45.2441928387 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,14,13,6,20.9958100319 +36,CUP,SUM,0,0,0,0,0,23,8,13.3394870758 +36,SPOON,SUM,1,0,1,0,2,1131,54,0 +36,,SUM,1,0,1,0,16,1167,68,34.3352971077 +36,,,,,,,,,, +37,,,,,,,,,, +37,BOWL,SUM,0,0,0,0,0,17,1,13.4081709385 +37,CUP,SUM,1,0,1,0,0,125,112,0 +37,SPOON,SUM,0,0,0,0,0,3,2,17.7692148685 +37,,SUM,1,0,1,0,0,145,115,31.177385807 +37,,,,,,,,,, +38,,,,,,,,,, +38,BOWL,SUM,0,0,0,0,0,316,46,62.3591780663 +38,CUP,SUM,0,0,0,0,10,122,26,49.9695320129 +38,SPOON,SUM,0,0,0,0,0,0,2,15.1243238449 +38,,SUM,0,0,0,0,10,438,74,127.4530339241 +38,,,,,,,,,, +39,,,,,,,,,, +39,BOWL,SUM,0,0,0,0,6,8,0,13.8970279694 +39,CUP,SUM,1,0,1,0,0,155,111,0 +39,SPOON,SUM,0,0,0,0,0,39,9,24.2805249691 +39,,SUM,1,0,1,0,6,202,120,38.1775529385 +39,,,,,,,,,, +40,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,0,112,6,21.7156510353 +40,CUP,SUM,0,0,0,0,0,217,27,51.2160708904 +40,SPOON,SUM,0,0,0,0,0,10,3,16.7608270645 +40,,SUM,0,0,0,0,0,339,36,89.6925489902 +40,,,,,,,,,, +41,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,0,15,0,11.799890995 +41,CUP,SUM,0,0,0,0,2,16,11,13.1471238136 +41,SPOON,SUM,0,0,0,0,2,21,8,21.096848011 +41,,SUM,0,0,0,0,4,52,19,46.0438628197 +41,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,0,15,0,11.6780760288 +42,CUP,SUM,1,0,1,0,0,399,108,0 +42,SPOON,SUM,0,0,0,0,0,14,1,17.0666999817 +42,,SUM,1,0,1,0,0,428,109,28.7447760105 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,0,4,0,12.3454270363 +43,CUP,SUM,0,0,0,0,0,16,7,14.9778211117 +43,SPOON,SUM,0,0,0,0,6,46,3,22.5940299034 +43,,SUM,0,0,0,0,6,66,10,49.9172780514 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,0,20,2,12.7661941051 +44,CUP,SUM,0,0,0,0,0,11,12,14.1420428753 +44,SPOON,SUM,0,0,0,0,2,0,0,15.8573138714 +44,,SUM,0,0,0,0,2,31,14,42.7655508518 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,0,25,10,18.9081859589 +45,CUP,SUM,1,0,1,0,4,138,102,0 +45,SPOON,SUM,0,0,0,0,0,110,0,21.3078889847 +45,,SUM,1,0,1,0,4,273,112,40.2160749435 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,0,22,0,12.5946278572 +46,CUP,SUM,0,0,0,0,0,49,14,24.7306270599 +46,SPOON,SUM,0,0,0,0,26,117,7,38.9284188747 +46,,SUM,0,0,0,0,26,188,21,76.2536737919 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,0,0,0,0,0,17,3,14.5759670734 +47,CUP,SUM,0,0,0,0,0,36,13,19.7965810299 +47,SPOON,SUM,0,0,0,0,2,67,9,24.9991438389 +47,,SUM,0,0,0,0,2,120,25,59.3716919422 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,0,8,0,11.6111280918 +48,CUP,SUM,0,0,0,0,2,33,5,18.9176979065 +48,SPOON,SUM,0,0,0,0,0,2,5,18.2412159443 +48,,SUM,0,0,0,0,2,43,10,48.7700419426 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,2,29,7,17.9276900291 +49,CUP,SUM,0,0,0,0,0,42,4,14.5768558979 +49,SPOON,SUM,0,0,0,0,10,5,4,21.6473970413 +49,,SUM,0,0,0,0,12,76,15,54.1519429684 +49,,,,,,,,,, +50,,,,,,,,,, +50,BOWL,SUM,0,0,0,0,6,102,0,19.8814308643 +50,CUP,SUM,0,0,0,0,0,6,10,10.5333008766 +50,SPOON,SUM,0,0,0,0,2,116,4,25.1995050907 +50,,SUM,0,0,0,0,8,224,14,55.6142368317 +50,,,,,,,,,, +51,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,0,33,6,15.666877985 +51,CUP,SUM,0,0,0,0,0,23,6,12.5528719425 +51,SPOON,SUM,0,0,0,0,4,94,14,34.7790107727 +51,,SUM,0,0,0,0,4,150,26,62.9987607002 +51,,,,,,,,,, +52,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,0,7,2,11.5694139004 +52,CUP,SUM,0,0,0,0,0,30,11,11.29717803 +52,SPOON,SUM,0,0,0,0,50,59,8,46.428842783 +52,,SUM,0,0,0,0,50,96,21,69.2954347134 +52,,,,,,,,,, +53,,,,,,,,,, +53,BOWL,SUM,1,0,1,0,0,324,104,0 +53,CUP,SUM,0,0,0,0,0,45,12,20.9711258411 +53,SPOON,SUM,1,0,1,0,0,1305,36,0 +53,,SUM,2,0,2,0,0,1674,152,20.9711258411 +53,,,,,,,,,, +54,,,,,,,,,, +54,BOWL,SUM,0,0,0,0,0,70,6,17.717621088 +54,CUP,SUM,0,0,0,0,0,9,5,11.6789131165 +54,SPOON,SUM,0,0,0,0,0,214,0,28.2604880333 +54,,SUM,0,0,0,0,0,293,11,57.6570222378 +54,,,,,,,,,, +55,,,,,,,,,, +55,BOWL,SUM,0,0,0,0,0,43,0,14.0144228935 +55,CUP,SUM,0,0,0,0,0,10,2,11.3367128372 +55,SPOON,SUM,1,0,1,0,2,1093,56,0 +55,,SUM,1,0,1,0,2,1146,58,25.3511357307 +55,,,,,,,,,, +56,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,0,2,0,12.1840648651 +56,CUP,SUM,0,0,0,0,0,21,14,17.6656439304 +56,SPOON,SUM,0,0,0,0,0,7,2,18.4740569592 +56,,SUM,0,0,0,0,0,30,16,48.3237657547 +56,,,,,,,,,, +57,,,,,,,,,, +57,BOWL,SUM,0,0,0,0,0,17,4,14.4918768406 +57,CUP,SUM,0,0,0,0,0,15,17,18.2671658993 +57,SPOON,SUM,0,0,0,0,0,184,0,26.1378428936 +57,,SUM,0,0,0,0,0,216,21,58.8968856335 +57,,,,,,,,,, +58,,,,,,,,,, +58,BOWL,SUM,0,0,0,0,0,27,0,12.7042350769 +58,CUP,SUM,0,0,0,0,4,39,5,16.6206741333 +58,SPOON,SUM,1,0,1,0,0,1250,38,0 +58,,SUM,1,0,1,0,4,1316,43,29.3249092102 +58,,,,,,,,,, +59,,,,,,,,,, +59,BOWL,SUM,0,0,0,0,0,45,12,21.6067061424 +59,CUP,SUM,0,0,0,0,0,79,9,16.4744000435 +59,SPOON,SUM,0,0,0,0,0,55,1,19.3228468895 +59,,SUM,0,0,0,0,0,179,22,57.4039530754 +59,,,,,,,,,, +60,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,0,53,18,26.7554831505 +60,CUP,SUM,0,0,0,0,0,7,4,11.6673879623 +60,SPOON,SUM,0,0,0,0,0,38,5,19.8063838482 +60,,SUM,0,0,0,0,0,98,27,58.229254961 +60,,,,,,,,,, +61,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,0,52,0,13.0563619137 +61,CUP,SUM,1,0,1,0,0,271,111,0 +61,SPOON,SUM,0,0,0,0,0,33,0,15.807459116 +61,,SUM,1,0,1,0,0,356,111,28.8638210297 +61,,,,,,,,,, +62,,,,,,,,,, +62,BOWL,SUM,0,0,0,0,0,4,0,11.8178429604 +62,CUP,SUM,0,0,0,0,0,19,14,14.8419089317 +62,SPOON,SUM,1,0,1,0,76,688,12,0 +62,,SUM,1,0,1,0,76,711,26,26.6597518921 +62,,,,,,,,,, +63,,,,,,,,,, +63,BOWL,SUM,1,0,1,0,0,1212,40,0 +63,CUP,SUM,0,0,0,0,0,32,6,14.0581738949 +63,SPOON,SUM,1,0,1,0,2,1305,44,0 +63,,SUM,2,0,2,0,2,2549,90,14.0581738949 +63,,,,,,,,,, +64,,,,,,,,,, +64,BOWL,SUM,0,0,0,0,2,3,4,14.2193031311 +64,CUP,SUM,0,0,0,0,2,32,2,14.398911953 +64,SPOON,SUM,0,0,0,0,0,68,1,20.3984799385 +64,,SUM,0,0,0,0,4,103,7,49.0166950226 +64,,,,,,,,,, +65,,,,,,,,,, +65,BOWL,SUM,0,0,0,0,0,41,0,12.9544479847 +65,CUP,SUM,0,0,0,0,0,6,11,12.1216208935 +65,SPOON,SUM,0,0,0,0,2,15,8,28.9064691067 +65,,SUM,0,0,0,0,2,62,19,53.9825379848 +65,,,,,,,,,, +66,,,,,,,,,, +66,BOWL,SUM,0,0,0,0,32,68,7,33.5719671249 +66,CUP,SUM,0,0,0,0,0,12,3,11.9695019722 +66,SPOON,SUM,0,0,0,0,0,2,4,17.5726020336 +66,,SUM,0,0,0,0,32,82,14,63.1140711308 +66,,,,,,,,,, +67,,,,,,,,,, +67,BOWL,SUM,0,0,0,0,0,38,29,35.9416131973 +67,CUP,SUM,1,0,1,0,0,208,110,0 +67,SPOON,SUM,0,0,0,0,0,2,0,15.3915410042 +67,,SUM,1,0,1,0,0,248,139,51.3331542015 +67,,,,,,,,,, +68,,,,,,,,,, +68,BOWL,SUM,0,0,0,0,0,5,0,11.8899610043 +68,CUP,SUM,0,0,0,0,2,9,1,12.7409060001 +68,SPOON,SUM,0,0,0,0,0,3,6,18.5476679802 +68,,SUM,0,0,0,0,2,17,7,43.1785349846 +68,,,,,,,,,, +69,,,,,,,,,, +69,BOWL,SUM,0,0,0,0,0,25,0,12.7210719585 +69,CUP,SUM,1,0,1,0,0,101,108,0 +69,SPOON,SUM,0,0,0,0,0,65,1,19.5884871483 +69,,SUM,1,0,1,0,0,191,109,32.3095591068 +69,,,,,,,,,, +70,,,,,,,,,, +70,BOWL,SUM,0,0,0,0,0,10,2,12.2427489758 +70,CUP,SUM,0,0,0,0,0,34,10,14.1390531063 +70,SPOON,SUM,0,0,0,0,0,35,0,17.5793428421 +70,,SUM,0,0,0,0,0,79,12,43.9611449242 +70,,,,,,,,,, +71,,,,,,,,,, +71,BOWL,SUM,0,0,0,0,0,41,0,13.1978878975 +71,CUP,SUM,0,0,0,0,0,26,12,14.8474369049 +71,SPOON,SUM,0,0,0,0,0,21,2,15.8453211784 +71,,SUM,0,0,0,0,0,88,14,43.8906459808 +71,,,,,,,,,, +72,,,,,,,,,, +72,BOWL,SUM,0,0,0,0,0,21,0,12.6368579865 +72,CUP,SUM,0,0,0,0,2,89,14,34.5403821468 +72,SPOON,SUM,1,0,1,0,0,1122,72,0 +72,,SUM,1,0,1,0,2,1232,86,47.1772401333 +72,,,,,,,,,, +73,,,,,,,,,, +73,BOWL,SUM,0,0,0,0,2,34,0,13.3598079681 +73,CUP,SUM,0,0,0,0,2,11,5,12.880644083 +73,SPOON,SUM,0,0,0,0,0,585,6,54.8748559952 +73,,SUM,0,0,0,0,4,630,11,81.1153080463 +73,,,,,,,,,, +74,,,,,,,,,, +74,BOWL,SUM,1,0,1,0,0,196,104,0 +74,CUP,SUM,0,0,0,0,4,4,5,12.0585098267 +74,SPOON,SUM,0,0,0,0,2,197,0,27.1619510651 +74,,SUM,1,0,1,0,6,397,109,39.2204608917 +74,,,,,,,,,, +75,,,,,,,,,, +75,BOWL,SUM,0,0,0,0,0,37,18,25.9284539223 +75,CUP,SUM,0,0,0,0,0,69,12,25.0156350136 +75,SPOON,SUM,0,0,0,0,0,20,3,17.655785799 +75,,SUM,0,0,0,0,0,126,33,68.5998747349 +75,,,,,,,,,, +76,,,,,,,,,, +76,BOWL,SUM,0,0,0,0,0,46,25,33.1043941975 +76,CUP,SUM,1,0,1,0,0,97,108,0 +76,SPOON,SUM,1,0,1,0,0,1552,20,0 +76,,SUM,2,0,2,0,0,1695,153,33.1043941975 +76,,,,,,,,,, +77,,,,,,,,,, +77,BOWL,SUM,0,0,0,0,160,107,14,98.7961609364 +77,CUP,SUM,0,0,0,0,0,27,8,15.2627530098 +77,SPOON,SUM,0,0,0,0,0,18,5,21.3380539417 +77,,SUM,0,0,0,0,160,152,27,135.3969678879 +77,,,,,,,,,, +78,,,,,,,,,, +78,BOWL,SUM,0,0,0,0,2,8,0,12.6613740921 +78,CUP,SUM,0,0,0,0,0,26,9,18.8173952103 +78,SPOON,SUM,1,0,1,0,0,1446,20,0 +78,,SUM,1,0,1,0,2,1480,29,31.4787693024 +78,,,,,,,,,, +79,,,,,,,,,, +79,BOWL,SUM,0,0,0,0,0,52,12,21.9758050442 +79,CUP,SUM,0,0,0,0,2,77,26,48.950699091 +79,SPOON,SUM,0,0,0,0,0,146,1,25.780878067 +79,,SUM,0,0,0,0,2,275,39,96.7073822021 +79,,,,,,,,,, +80,,,,,,,,,, +80,BOWL,SUM,0,0,0,0,0,209,11,33.8143270016 +80,CUP,SUM,0,0,0,0,0,24,7,11.0131089687 +80,SPOON,SUM,0,0,0,0,0,141,1,25.2733571529 +80,,SUM,0,0,0,0,0,374,19,70.1007931232 +80,,,,,,,,,, +81,,,,,,,,,, +81,BOWL,SUM,0,0,0,0,0,12,0,12.0618948936 +81,CUP,SUM,0,0,0,0,0,11,4,13.4873588085 +81,SPOON,SUM,0,0,0,0,0,16,21,33.6829819679 +81,,SUM,0,0,0,0,0,39,25,59.2322356701 +81,,,,,,,,,, +82,,,,,,,,,, +82,BOWL,SUM,0,0,0,0,6,29,3,19.3235340118 +82,CUP,SUM,1,0,1,0,0,180,102,0 +82,SPOON,SUM,1,0,1,0,0,1382,24,0 +82,,SUM,2,0,2,0,6,1591,129,19.3235340118 +82,,,,,,,,,, +83,,,,,,,,,, +83,BOWL,SUM,0,0,0,0,0,169,10,28.1221339703 +83,CUP,SUM,0,0,0,0,0,11,0,9.9194951057 +83,SPOON,SUM,0,0,0,0,0,124,4,24.0729269981 +83,,SUM,0,0,0,0,0,304,14,62.1145560741 +83,,,,,,,,,, +84,,,,,,,,,, +84,BOWL,SUM,0,0,0,0,6,7,0,13.8449349403 +84,CUP,SUM,0,0,0,0,0,42,7,19.1734611988 +84,SPOON,SUM,0,0,0,0,0,53,0,17.7996301651 +84,,SUM,0,0,0,0,6,102,7,50.8180263042 +84,,,,,,,,,, +85,,,,,,,,,, +85,BOWL,SUM,0,0,0,0,0,4,0,11.6139111519 +85,CUP,SUM,0,0,0,0,0,64,21,39.4884488583 +85,SPOON,SUM,0,0,0,0,0,109,23,39.709305048 +85,,SUM,0,0,0,0,0,177,44,90.8116650581 +85,,,,,,,,,, +86,, +86,BOWL,SUM,0,0,0,0,0,4,4,17.403174877166748 +86,CUP,SUM,1,0,1,0,0,123,112,0.0 +86,SPOON,SUM,0,0,0,0,0,1,4,16.189035177230835 +86,,SUM,1,0,1,0,0,128,120,33.59221005439758 +86,, +87,, +87,BOWL,SUM,0,0,0,0,0,44,6,15.712407112121582 +87,CUP,SUM,1,0,0,1,6,279,57,0.0 +87,SPOON,SUM,1,0,1,0,0,1455,24,0.0 +87,,SUM,2,0,1,1,6,1778,87,15.712407112121582 +87,, +88,, +88,BOWL,SUM,0,0,0,0,0,2,0,10.914373874664307 +88,CUP,SUM,0,0,0,0,0,20,8,12.251648902893066 +88,SPOON,SUM,0,0,0,0,0,104,2,22.30026412010193 +88,,SUM,0,0,0,0,0,126,10,45.4662868976593 +88,, +89,, +89,BOWL,SUM,0,0,0,0,0,8,0,11.24014401435852 +89,CUP,SUM,0,0,0,0,0,21,8,13.134323120117188 +89,SPOON,SUM,0,0,0,0,0,24,0,14.858274936676025 +89,,SUM,0,0,0,0,0,53,8,39.23274207115173 +89,, +90,, +90,BOWL,SUM,0,0,0,0,0,47,24,30.12774896621704 +90,CUP,SUM,0,0,0,0,0,78,14,26.91368007659912 +90,SPOON,SUM,0,0,0,0,0,0,6,18.06906294822693 +90,,SUM,0,0,0,0,0,125,44,75.11049199104309 +90,, +91,, +91,BOWL,SUM,0,0,0,0,0,22,13,20.842495918273926 +91,CUP,SUM,0,0,0,0,0,8,12,12.233747005462646 +91,SPOON,SUM,1,0,1,0,0,1533,12,0.0 +91,,SUM,1,0,1,0,0,1563,37,33.07624292373657 +91,, +92,, +92,BOWL,SUM,0,0,0,0,0,11,3,13.072870016098022 +92,CUP,SUM,0,0,0,0,2,7,2,10.365808963775635 +92,SPOON,SUM,0,0,0,0,6,240,0,30.204480171203613 +92,,SUM,0,0,0,0,8,258,5,53.64315915107727 +92,, +93,, +93,BOWL,SUM,0,0,0,0,0,24,0,11.431034803390503 +93,CUP,SUM,0,0,0,0,6,16,2,14.660398006439209 +93,SPOON,SUM,0,0,0,0,0,26,6,18.3532931804657 +93,,SUM,0,0,0,0,6,66,8,44.44472599029541 +93,, +94,, +94,BOWL,SUM,0,0,0,0,0,3,1,11.073020219802856 +94,CUP,SUM,0,0,0,0,2,49,55,51.14508080482483 +94,SPOON,SUM,0,0,0,0,0,68,17,30.544511079788208 +94,,SUM,0,0,0,0,2,120,73,92.7626121044159 +94,, +95,, +95,BOWL,SUM,0,0,0,0,0,197,16,30.80978488922119 +95,CUP,SUM,0,0,0,0,0,19,9,16.194391012191772 +95,SPOON,SUM,0,0,0,0,0,32,3,20.661670923233032 +95,,SUM,0,0,0,0,0,248,28,67.665846824646 +95,, +96,, +96,BOWL,SUM,0,0,0,0,6,19,6,16.473062992095947 +96,CUP,SUM,0,0,0,0,0,27,11,18.163229942321777 +96,SPOON,SUM,0,0,0,0,0,4,15,27.404163122177124 +96,,SUM,0,0,0,0,6,50,32,62.04045605659485 +96,, +97,, +97,BOWL,SUM,0,0,0,0,6,33,0,13.858877897262573 +97,CUP,SUM,0,0,0,0,0,238,45,77.66377782821655 +97,SPOON,SUM,1,0,1,0,14,1470,14,0.0 +97,,SUM,1,0,1,0,20,1741,59,91.52265572547913 +97,, +98,, +98,BOWL,SUM,0,0,0,0,0,99,47,50.283355951309204 +98,CUP,SUM,0,0,0,0,0,62,48,45.73499512672424 +98,SPOON,SUM,0,0,0,0,0,132,2,25.251017808914185 +98,,SUM,0,0,0,0,0,293,97,121.26936888694763 +98,, +99,, +99,BOWL,SUM,0,0,0,0,34,43,10,35.797842025756836 +99,CUP,SUM,0,0,0,0,2,12,9,12.773009061813354 +99,SPOON,SUM,0,0,0,0,0,39,2,19.353954076766968 +99,,SUM,0,0,0,0,36,94,21,67.92480516433716 +99,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_urdf_kitchen_new_var_and_orig_data_18_offset.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_urdf_kitchen_new_var_and_orig_data_18_offset.csv new file mode 100644 index 0000000000..23b54d9bee --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_urdf_kitchen_new_var_and_orig_data_18_offset.csv @@ -0,0 +1,297 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,18,229,0,68.9963440895 +42,CUP,SUM,0,0,0,0,0,9,1,26.4340348244 +42,SPOON,SUM,1,0,1,0,0,1582,0,0 +42,,SUM,1,0,1,0,18,1820,1,95.4303789139 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,56,116,0,79.9690589905 +43,CUP,SUM,0,0,0,0,0,107,8,40.7685558796 +43,SPOON,SUM,0,0,0,0,0,54,4,36.072701931 +43,,SUM,0,0,0,0,56,277,12,156.8103168011 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,2,923,2,163.1681480408 +44,CUP,SUM,0,0,0,0,0,15,2,31.198348999 +44,SPOON,SUM,1,0,1,0,0,1581,0,0 +44,,SUM,1,0,1,0,2,2519,4,194.3664970398 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,0,489,8,100.219274044 +45,CUP,SUM,1,0,0,1,0,260,51,0 +45,SPOON,SUM,0,0,0,0,0,1311,0,214.4038147926 +45,,SUM,1,0,0,1,0,2060,59,314.6230888367 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,0,791,6,141.3282909393 +46,CUP,SUM,0,0,0,0,0,31,4,40.5027530193 +46,SPOON,SUM,0,0,0,0,0,36,1,35.8564841747 +46,,SUM,0,0,0,0,0,858,11,217.6875281334 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,1,0,1,0,0,1505,12,0 +47,CUP,SUM,0,0,0,0,0,16,10,48.2965600491 +47,SPOON,SUM,0,0,0,0,0,141,0,45.5945219994 +47,,SUM,1,0,1,0,0,1662,22,93.8910820484 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,0,39,2,32.6298799515 +48,CUP,SUM,0,0,0,0,0,17,2,22.9499671459 +48,SPOON,SUM,0,0,0,0,2,309,3,72.4762880802 +48,,SUM,0,0,0,0,2,365,7,128.0561351776 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,2,61,2,37.0273389816 +49,CUP,SUM,0,0,0,0,2,16,3,26.9119381905 +49,SPOON,SUM,0,0,0,0,0,49,1,35.9744360447 +49,,SUM,0,0,0,0,4,126,6,99.9137132168 +49,,,,,,,,,, +50,,,,,,,,,, +50,BOWL,SUM,0,0,0,0,0,22,8,36.4264848232 +50,CUP,SUM,0,0,0,0,0,32,4,31.1820831299 +50,SPOON,SUM,0,0,0,0,0,19,1,31.0216591358 +50,,SUM,0,0,0,0,0,73,13,98.6302270889 +50,,,,,,,,,, +51,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,0,40,0,27.926181078 +51,CUP,SUM,0,0,0,0,0,29,4,23.0344479084 +51,SPOON,SUM,0,0,0,0,0,133,0,41.0714511871 +51,,SUM,0,0,0,0,0,202,4,92.0320801735 +51,,,,,,,,,, +52,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,0,11,1,27.6224989891 +52,CUP,SUM,0,0,0,0,0,10,6,30.5902280807 +52,SPOON,SUM,0,0,0,0,0,1089,0,181.9770760536 +52,,SUM,0,0,0,0,0,1110,7,240.1898031235 +52,,,,,,,,,, +53,,,,,,,,,, +53,BOWL,SUM,0,0,0,0,2,11,0,24.2608959675 +53,CUP,SUM,0,0,0,0,0,60,4,31.1020469666 +53,SPOON,SUM,0,0,0,0,0,1,0,27.1566960812 +53,,SUM,0,0,0,0,2,72,4,82.5196390152 +53,,,,,,,,,, +54,,,,,,,,,, +54,BOWL,SUM,0,0,0,0,2,36,7,37.5189521313 +54,CUP,SUM,0,0,0,0,0,175,9,55.6745691299 +54,SPOON,SUM,0,0,0,0,0,27,1,31.8248779774 +54,,SUM,0,0,0,0,2,238,17,125.0183992386 +54,,,,,,,,,, +55,,,,,,,,,, +55,BOWL,SUM,0,0,0,0,62,91,7,84.9240019321 +55,CUP,SUM,0,0,0,0,4,321,59,232.2065999508 +55,SPOON,SUM,0,0,0,0,0,295,0,69.1713039875 +55,,SUM,0,0,0,0,66,707,66,386.3019058704 +55,,,,,,,,,, +56,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,0,97,1,37.2479720116 +56,CUP,SUM,0,0,0,0,0,36,5,27.7422468662 +56,SPOON,SUM,0,0,0,0,0,56,0,32.4963800907 +56,,SUM,0,0,0,0,0,189,6,97.4865989685 +56,,,,,,,,,, +57,,,,,,,,,, +57,BOWL,SUM,0,0,0,0,0,25,2,23.9649591446 +57,CUP,SUM,0,0,0,0,0,9,6,22.5667698383 +57,SPOON,SUM,0,0,0,0,0,15,0,27.0664019585 +57,,SUM,0,0,0,0,0,49,8,73.5981309414 +57,,,,,,,,,, +58,,,,,,,,,, +58,BOWL,SUM,1,0,1,0,0,1592,0,0 +58,CUP,SUM,0,0,0,0,0,85,18,91.9112911224 +58,SPOON,SUM,0,0,0,0,0,99,3,44.95550704 +58,,SUM,1,0,1,0,0,1776,21,136.8667981625 +58,,,,,,,,,, +59,,,,,,,,,, +59,BOWL,SUM,0,0,0,0,0,13,4,28.3912680149 +59,CUP,SUM,0,0,0,0,8,12,11,29.9622421265 +59,SPOON,SUM,0,0,0,0,2,14,0,28.1288101673 +59,,SUM,0,0,0,0,10,39,15,86.4823203087 +59,,,,,,,,,, +60,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,0,12,1,27.8608810902 +60,CUP,SUM,0,0,0,0,0,101,2,36.6035819054 +60,SPOON,SUM,0,0,0,0,0,2,1,30.6950380802 +60,,SUM,0,0,0,0,0,115,4,95.1595010757 +60,,,,,,,,,, +61,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,2,5,0,24.4513149261 +61,CUP,SUM,0,0,0,0,8,29,8,30.2048289776 +61,SPOON,SUM,0,0,0,0,20,704,0,137.5585179329 +61,,SUM,0,0,0,0,30,738,8,192.2146618366 +61,,,,,,,,,, +62,,,,,,,,,, +62,BOWL,SUM,0,0,0,0,0,22,0,24.5587189198 +62,CUP,SUM,0,0,0,0,0,104,26,65.3001048565 +62,SPOON,SUM,0,0,0,0,0,212,0,54.885324955 +62,,SUM,0,0,0,0,0,338,26,144.7441487312 +62,,,,,,,,,, +63,,,,,,,,,, +63,BOWL,SUM,0,0,0,0,0,22,8,56.9815850258 +63,CUP,SUM,0,0,0,0,0,146,18,47.6941969395 +63,SPOON,SUM,0,0,0,0,0,70,2,36.7326760292 +63,,SUM,0,0,0,0,0,238,28,141.4084579945 +63,,,,,,,,,, +64,,,,,,,,,, +64,BOWL,SUM,0,0,0,0,0,13,3,28.2540800571 +64,CUP,SUM,1,0,1,0,8,732,83,0 +64,SPOON,SUM,0,0,0,0,0,15,0,27.2941269875 +64,,SUM,1,0,1,0,8,760,86,55.5482070446 +64,,,,,,,,,, +65,,,,,,,,,, +65,BOWL,SUM,0,0,0,0,0,181,6,67.5725009441 +65,CUP,SUM,0,0,0,0,0,15,5,27.0746839046 +65,SPOON,SUM,0,0,0,0,40,22,1,64.2712130547 +65,,SUM,0,0,0,0,40,218,12,158.9183979034 +65,,,,,,,,,, +66,,,,,,,,,, +66,BOWL,SUM,0,0,0,0,4,1,0,24.7752959728 +66,CUP,SUM,1,0,1,0,0,138,101,0 +66,SPOON,SUM,0,0,0,0,0,200,1,58.0958769321 +66,,SUM,1,0,1,0,4,339,102,82.871172905 +66,,,,,,,,,, +67,,,,,,,,,, +67,BOWL,SUM,0,0,0,0,0,39,2,24.0880470276 +67,CUP,SUM,0,0,0,0,12,15,2,30.3406538963 +67,SPOON,SUM,0,0,0,0,0,72,2,44.2663228512 +67,,SUM,0,0,0,0,12,126,6,98.6950237751 +67,,,,,,,,,, +68,,,,,,,,,, +68,BOWL,SUM,1,0,1,0,2,1083,76,0 +68,CUP,SUM,0,0,0,0,0,793,24,209.6676089764 +68,SPOON,SUM,0,0,0,0,2,18,1,31.9318881035 +68,,SUM,1,0,1,0,4,1894,101,241.5994970799 +68,,,,,,,,,, +69,,,,,,,,,, +69,BOWL,SUM,0,0,0,0,22,840,2,152.0486588478 +69,CUP,SUM,0,0,0,0,0,51,3,31.8037548065 +69,SPOON,SUM,0,0,0,0,0,67,0,36.5603148937 +69,,SUM,0,0,0,0,22,958,5,220.4127285481 +69,,,,,,,,,, +70,, +70,BOWL,SUM,0,0,0,0,0,53,1,40.593096017837524 +70,CUP,SUM,0,0,0,0,0,20,11,44.325608015060425 +70,SPOON,SUM,0,0,0,0,0,5,0,28.83497714996338 +70,,SUM,0,0,0,0,0,78,12,113.75368118286133 +70,, +71,, +71,BOWL,SUM,0,0,0,0,0,204,22,89.0019600391388 +71,CUP,SUM,0,0,0,0,6,20,10,40.99391794204712 +71,SPOON,SUM,0,0,0,0,0,65,0,34.76001811027527 +71,,SUM,0,0,0,0,6,289,32,164.75589609146118 +71,, +72,, +72,BOWL,SUM,0,0,0,0,0,34,1,34.7856879234314 +72,CUP,SUM,1,0,1,0,0,100,111,0.0 +72,SPOON,SUM,0,0,0,0,0,40,0,33.832687854766846 +72,,SUM,1,0,1,0,0,174,112,68.61837577819824 +72,, +73,, +73,BOWL,SUM,0,0,0,0,58,31,0,76.99489092826843 +73,CUP,SUM,0,0,0,0,0,17,0,25.103039979934692 +73,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +73,,SUM,1,0,1,0,58,1629,0,102.09793090820313 +73,, +74,, +74,BOWL,SUM,1,0,1,0,0,1632,0,0.0 +74,CUP,SUM,0,0,0,0,0,19,7,38.90129089355469 +74,SPOON,SUM,0,0,0,0,0,1,2,37.9612021446228 +74,,SUM,1,0,1,0,0,1652,9,76.86249303817749 +74,, +75,, +75,BOWL,SUM,0,0,0,0,0,76,4,45.240936040878296 +75,CUP,SUM,0,0,0,0,12,141,36,139.87509894371033 +75,SPOON,SUM,0,0,0,0,0,12,1,33.82890200614929 +75,,SUM,0,0,0,0,12,229,41,218.94493699073792 +75,, +76,, +76,BOWL,SUM,0,0,0,0,0,124,1,45.27759313583374 +76,CUP,SUM,0,0,0,0,2,149,1,49.231327056884766 +76,SPOON,SUM,0,0,0,0,0,251,2,67.66902589797974 +76,,SUM,0,0,0,0,2,524,4,162.17794609069824 +76,, +77,, +77,BOWL,SUM,1,0,1,0,0,1583,0,0.0 +77,CUP,SUM,0,0,0,0,0,55,3,39.87890911102295 +77,SPOON,SUM,0,0,0,0,4,36,0,35.443878173828125 +77,,SUM,1,0,1,0,4,1674,3,75.32278728485107 +77,, +78,, +78,BOWL,SUM,0,0,0,0,0,9,0,25.341346979141235 +78,CUP,SUM,0,0,0,0,0,8,16,38.987515926361084 +78,SPOON,SUM,1,0,1,0,0,1590,0,0.0 +78,,SUM,1,0,1,0,0,1607,16,64.32886290550232 +78,, +79,, +79,BOWL,SUM,0,0,0,0,10,166,0,58.96588492393494 +79,CUP,SUM,0,0,0,0,14,37,8,44.92793679237366 +79,SPOON,SUM,0,0,0,0,0,46,3,38.968827962875366 +79,,SUM,0,0,0,0,24,249,11,142.86264967918396 +79,, +80,, +80,BOWL,SUM,0,0,0,0,0,58,5,53.24796485900879 +80,CUP,SUM,0,0,0,0,0,49,9,57.71652889251709 +80,SPOON,SUM,1,1,0,0,96,1316,0,0.0 +80,,SUM,1,1,0,0,96,1423,14,110.96449375152588 +80,, +81,, +81,BOWL,SUM,0,0,0,0,0,70,2,31.943436861038208 +81,CUP,SUM,0,0,0,0,0,36,3,25.738546133041382 +81,SPOON,SUM,0,0,0,0,2,21,2,39.391892194747925 +81,,SUM,0,0,0,0,2,127,7,97.07387518882751 +81,, +82,, +82,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +82,CUP,SUM,0,0,0,0,0,5,4,24.696147918701172 +82,SPOON,SUM,1,0,1,0,14,1645,0,0.0 +82,,SUM,2,1,1,0,14,3169,4,24.696147918701172 +82,, +83,, +83,BOWL,SUM,0,0,0,0,6,6,4,45.89408588409424 +83,CUP,SUM,1,0,1,0,0,1451,29,0.0 +83,SPOON,SUM,0,0,0,0,0,454,0,99.35275411605835 +83,,SUM,1,0,1,0,6,1911,33,145.2468400001526 +83,, +84,, +84,BOWL,SUM,0,0,0,0,0,59,1,36.43769192695618 +84,CUP,SUM,0,0,0,0,0,54,14,63.650896072387695 +84,SPOON,SUM,0,0,0,0,6,173,3,62.512564182281494 +84,,SUM,0,0,0,0,6,286,18,162.60115218162537 +84,, +85,, +85,BOWL,SUM,0,0,0,0,0,27,0,26.488090991973877 +85,CUP,SUM,0,0,0,0,0,26,3,25.234678030014038 +85,SPOON,SUM,0,0,0,0,0,3,2,38.28414797782898 +85,,SUM,0,0,0,0,0,56,5,90.0069169998169 +85,, +86,, +86,BOWL,SUM,0,0,0,0,0,32,3,39.56361699104309 +86,CUP,SUM,1,0,1,0,46,1168,13,0.0 +86,SPOON,SUM,0,0,0,0,0,0,0,29.432920932769775 +86,,SUM,1,0,1,0,46,1200,16,68.99653792381287 +86,, +87,, +87,BOWL,SUM,0,0,0,0,0,16,3,39.915016889572144 +87,CUP,SUM,0,0,0,0,10,36,8,44.18278789520264 +87,SPOON,SUM,0,0,0,0,0,25,0,30.19478702545166 +87,,SUM,0,0,0,0,10,77,11,114.29259181022644 +87,, +88,, +88,BOWL,SUM,0,0,0,0,0,20,0,26.6420259475708 +88,CUP,SUM,0,0,0,0,0,46,14,42.07520508766174 +88,SPOON,SUM,1,0,1,0,2,1493,12,0.0 +88,,SUM,1,0,1,0,2,1559,26,68.71723103523254 +88,, +89,, +89,BOWL,SUM,0,0,0,0,0,150,0,46.822927951812744 +89,CUP,SUM,0,0,0,0,2,22,11,32.09808015823364 +89,SPOON,SUM,0,0,0,0,0,347,0,81.19809198379517 +89,,SUM,0,0,0,0,2,519,11,160.11910009384155 +89,, +90,, +90,BOWL,SUM,0,0,0,0,0,123,5,55.82639193534851 +90,CUP,SUM,0,0,0,0,26,104,3,56.15952014923096 +90,SPOON,SUM,0,0,0,0,0,193,0,56.707945108413696 +90,,SUM,0,0,0,0,26,420,8,168.69385719299316 +90,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_urdf_kitchen_new_var_and_orig_data_19_offset.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_urdf_kitchen_new_var_and_orig_data_19_offset.csv new file mode 100644 index 0000000000..9eefc5d584 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_urdf_kitchen_new_var_and_orig_data_19_offset.csv @@ -0,0 +1,337 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,8,1,34.4429359436 +0,CUP,SUM,0,0,0,0,0,47,10,49.2273170948 +0,SPOON,SUM,0,0,0,0,0,14,6,39.1924028397 +0,,SUM,0,0,0,0,0,69,17,122.8626558781 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,0,105,1,41.1579101086 +1,CUP,SUM,0,0,0,0,14,13,4,34.9759438038 +1,SPOON,SUM,0,0,0,0,0,208,0,59.9602169991 +1,,SUM,0,0,0,0,14,326,5,136.0940709114 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,0,11,1,30.0742609501 +2,CUP,SUM,0,0,0,0,0,29,2,24.8898508549 +2,SPOON,SUM,0,0,0,0,0,215,5,69.4613740444 +2,,SUM,0,0,0,0,0,255,8,124.4254858494 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,1,0,1,0,0,1027,68,0 +3,CUP,SUM,0,0,0,0,0,18,10,25.3782529831 +3,SPOON,SUM,1,0,1,0,0,1582,0,0 +3,,SUM,2,0,2,0,0,2627,78,25.3782529831 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,46,8,40.9767580032 +4,CUP,SUM,0,0,0,0,8,110,6,71.2527179718 +4,SPOON,SUM,0,0,0,0,0,0,0,28.6313681602 +4,,SUM,0,0,0,0,8,156,14,140.8608441353 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,1,0,1,0,0,1394,24,0 +5,CUP,SUM,0,0,0,0,0,11,6,29.4031970501 +5,SPOON,SUM,0,0,0,0,0,27,0,29.2916431427 +5,,SUM,1,0,1,0,0,1432,30,58.6948401928 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,0,29,4,31.4773638248 +6,CUP,SUM,0,0,0,0,2,30,13,67.8522150517 +6,SPOON,SUM,1,0,1,0,0,1479,10,0 +6,,SUM,1,0,1,0,2,1538,27,99.3295788765 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,0,8,0,26.4151370525 +7,CUP,SUM,0,0,0,0,2,18,6,30.8402969837 +7,SPOON,SUM,0,0,0,0,0,478,0,99.7227091789 +7,,SUM,0,0,0,0,2,504,6,156.9781432152 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,0,31,2,27.8037798405 +8,CUP,SUM,0,0,0,0,2,60,17,65.1589000225 +8,SPOON,SUM,0,0,0,0,24,36,1,56.2376630306 +8,,SUM,0,0,0,0,26,127,20,149.2003428936 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,21,0,26.4497849941 +9,CUP,SUM,0,0,0,0,0,24,7,39.4621751308 +9,SPOON,SUM,1,0,1,0,0,1650,0,0 +9,,SUM,1,0,1,0,0,1695,7,65.911960125 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,345,7,95.6216540337 +10,CUP,SUM,0,0,0,0,0,26,11,55.4485421181 +10,SPOON,SUM,0,0,0,0,0,13,2,29.2205209732 +10,,SUM,0,0,0,0,0,384,20,180.2907171249 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,1,1,0,0,0,1519,0,0 +11,CUP,SUM,0,0,0,0,0,24,7,38.7515330315 +11,SPOON,SUM,0,0,0,0,2,881,0,169.5500180721 +11,,SUM,1,1,0,0,2,2424,7,208.3015511036 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,0,24,2,25.872699976 +12,CUP,SUM,0,0,0,0,0,94,28,139.498557806 +12,SPOON,SUM,0,0,0,0,0,61,0,34.67856884 +12,,SUM,0,0,0,0,0,179,30,200.049826622 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,1,0,1,0,0,1583,0,0 +13,CUP,SUM,0,0,0,0,0,4,11,29.6381459236 +13,SPOON,SUM,0,0,0,0,2,270,4,71.8106749058 +13,,SUM,1,0,1,0,2,1857,15,101.4488208294 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,1,0,1,0,0,1582,0,0 +14,CUP,SUM,0,0,0,0,0,13,4,33.06082201 +14,SPOON,SUM,0,0,0,0,30,192,1,76.9684391022 +14,,SUM,1,0,1,0,30,1787,5,110.0292611122 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,1,1,0,0,16,1501,0,0 +15,CUP,SUM,0,0,0,0,0,2,3,28.1806509495 +15,SPOON,SUM,0,0,0,0,4,165,2,54.3394618034 +15,,SUM,1,1,0,0,20,1668,5,82.5201127529 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,121,0,39.8936269283 +16,CUP,SUM,0,0,0,0,0,22,3,28.561070919 +16,SPOON,SUM,0,0,0,0,0,45,2,34.473074913 +16,,SUM,0,0,0,0,0,188,5,102.9277727604 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,0,28,3,30.14083004 +17,CUP,SUM,0,0,0,0,0,16,9,33.0939338207 +17,SPOON,SUM,0,0,0,0,0,174,0,52.7049121857 +17,,SUM,0,0,0,0,0,218,12,115.9396760464 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,0,74,4,34.7922329903 +18,CUP,SUM,0,0,0,0,0,8,3,37.0788319111 +18,SPOON,SUM,0,0,0,0,0,616,2,123.5109379292 +18,,SUM,0,0,0,0,0,698,9,195.3820028305 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,232,46,136.9864470959 +19,CUP,SUM,1,0,1,0,6,1306,51,0 +19,SPOON,SUM,0,0,0,0,0,42,1,37.2340939045 +19,,SUM,1,0,1,0,6,1580,98,174.2205410004 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,2,13,1,30.303388834 +20,CUP,SUM,0,0,0,0,0,51,8,33.6037430763 +20,SPOON,SUM,0,0,0,0,0,115,0,42.5485999584 +20,,SUM,0,0,0,0,2,179,9,106.4557318687 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,69,4,38.5302920341 +21,CUP,SUM,0,0,0,0,0,26,11,29.473744154 +21,SPOON,SUM,0,0,0,0,0,90,4,47.2745840549 +21,,SUM,0,0,0,0,0,185,19,115.2786202431 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,8,626,2,131.4837458134 +22,CUP,SUM,0,0,0,0,0,25,11,55.4221699238 +22,SPOON,SUM,0,0,0,0,0,58,2,34.1896259785 +22,,SUM,0,0,0,0,8,709,15,221.0955417156 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,1,0,1,0,0,1552,4,0 +23,CUP,SUM,0,0,0,0,0,22,5,24.3536968231 +23,SPOON,SUM,0,0,0,0,0,8,0,29.0261969566 +23,,SUM,1,0,1,0,0,1582,9,53.3798937798 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,0,10,0,24.8071880341 +24,CUP,SUM,0,0,0,0,0,4,6,36.6674258709 +24,SPOON,SUM,1,0,1,0,0,1593,0,0 +24,,SUM,1,0,1,0,0,1607,6,61.474613905 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,0,274,4,69.1960241795 +25,CUP,SUM,0,0,0,0,0,33,11,61.5241639614 +25,SPOON,SUM,0,0,0,0,0,27,0,27.4335110188 +25,,SUM,0,0,0,0,0,334,15,158.1536991596 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,34,184,0,66.3272950649 +26,CUP,SUM,0,0,0,0,0,20,7,43.8812971115 +26,SPOON,SUM,0,0,0,0,12,517,3,123.4966318607 +26,,SUM,0,0,0,0,46,721,10,233.7052240372 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,0,14,0,23.5585739613 +27,CUP,SUM,1,0,1,0,0,698,98,0 +27,SPOON,SUM,0,0,0,0,0,29,0,27.8421809673 +27,,SUM,1,0,1,0,0,741,98,51.4007549286 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,0,105,3,48.9966371059 +28,CUP,SUM,0,0,0,0,6,17,4,29.1510550976 +28,SPOON,SUM,0,0,0,0,0,12,4,31.9758889675 +28,,SUM,0,0,0,0,6,134,11,110.123581171 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,0,25,0,24.3965408802 +29,CUP,SUM,0,0,0,0,0,35,3,27.9686379433 +29,SPOON,SUM,0,0,0,0,2,1170,0,194.5713341236 +29,,SUM,0,0,0,0,2,1230,3,246.9365129471 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,1,0,1,0,2,1280,40,0 +30,CUP,SUM,0,0,0,0,0,11,8,31.1809418201 +30,SPOON,SUM,0,0,0,0,0,40,1,35.9498288631 +30,,SUM,1,0,1,0,2,1331,49,67.1307706833 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,0,31,1,27.5491690636 +31,CUP,SUM,0,0,0,0,0,8,2,22.8388168812 +31,SPOON,SUM,1,0,1,0,0,1581,0,0 +31,,SUM,1,0,1,0,0,1620,3,50.3879859447 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,0,142,4,46.1934111118 +32,CUP,SUM,1,0,1,0,0,644,103,0 +32,SPOON,SUM,0,0,0,0,0,25,3,31.8172330856 +32,,SUM,1,0,1,0,0,811,110,78.0106441975 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,1,0,1,0,4,1529,4,0 +33,CUP,SUM,0,0,0,0,0,22,6,40.0260591507 +33,SPOON,SUM,0,0,0,0,0,20,0,28.0625598431 +33,,SUM,1,0,1,0,4,1571,10,68.0886189938 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,0,17,1,28.1020629406 +34,CUP,SUM,0,0,0,0,0,33,9,36.5631380081 +34,SPOON,SUM,1,0,1,0,0,1581,0,0 +34,,SUM,1,0,1,0,0,1631,10,64.6652009487 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,0,9,0,23.9481008053 +35,CUP,SUM,0,0,0,0,0,8,4,22.0263149738 +35,SPOON,SUM,0,0,0,0,10,6,0,34.596350193 +35,,SUM,0,0,0,0,10,23,4,80.5707659721 +35,,,,,,,,,, +36,, +36,BOWL,SUM,0,0,0,0,0,173,11,70.18461203575134 +36,CUP,SUM,0,0,0,0,0,42,12,35.78221893310547 +36,SPOON,SUM,0,0,0,0,0,112,1,44.7280170917511 +36,,SUM,0,0,0,0,0,327,24,150.6948480606079 +36,, +37,, +37,BOWL,SUM,1,0,1,0,0,1062,70,0.0 +37,CUP,SUM,0,0,0,0,0,36,10,48.637977838516235 +37,SPOON,SUM,0,0,0,0,0,725,0,126.20501399040222 +37,,SUM,1,0,1,0,0,1823,80,174.84299182891846 +37,, +38,, +38,BOWL,SUM,0,0,0,0,0,18,5,36.04970383644104 +38,CUP,SUM,0,0,0,0,0,6,6,30.73450994491577 +38,SPOON,SUM,1,0,1,0,40,1308,0,0.0 +38,,SUM,1,0,1,0,40,1332,11,66.78421378135681 +38,, +39,, +39,BOWL,SUM,0,0,0,0,0,24,2,23.629273891448975 +39,CUP,SUM,0,0,0,0,12,23,6,31.325545072555542 +39,SPOON,SUM,1,0,1,0,98,1751,0,0.0 +39,,SUM,1,0,1,0,110,1798,8,54.95481896400452 +39,, +40,, +40,, +40,, +41,, +41,BOWL,SUM,0,0,0,0,0,87,16,68.88963198661804 +41,CUP,SUM,0,0,0,0,0,39,14,36.130337953567505 +41,SPOON,SUM,0,0,0,0,0,69,3,44.28561997413635 +41,,SUM,0,0,0,0,0,195,33,149.3055899143219 +41,, +42,, +42,BOWL,SUM,1,0,1,0,2,834,78,0.0 +42,CUP,SUM,0,0,0,0,0,40,13,60.74578619003296 +42,SPOON,SUM,0,0,0,0,0,118,0,40.867072105407715 +42,,SUM,1,0,1,0,2,992,91,101.61285829544067 +42,, +43,, +43,BOWL,SUM,0,0,0,0,0,162,17,67.42052793502808 +43,CUP,SUM,0,0,0,0,100,199,3,121.1108980178833 +43,SPOON,SUM,0,0,0,0,0,41,2,25.26520800590515 +43,,SUM,0,0,0,0,100,402,22,213.79663395881653 +43,, +44,, +44,BOWL,SUM,0,0,0,0,114,158,8,127.8998339176178 +44,CUP,SUM,0,0,0,0,2,763,19,149.13248991966248 +44,SPOON,SUM,0,0,0,0,0,370,0,70.82729887962341 +44,,SUM,0,0,0,0,116,1291,27,347.8596227169037 +44,, +45,, +45,BOWL,SUM,0,0,0,0,14,41,0,28.850829124450684 +45,CUP,SUM,0,0,0,0,4,3,6,26.422257900238037 +45,SPOON,SUM,0,0,0,0,0,195,1,50.95596885681152 +45,,SUM,0,0,0,0,18,239,7,106.22905588150024 +45,, +46,, +46,BOWL,SUM,1,0,1,0,0,1406,30,0.0 +46,CUP,SUM,0,0,0,0,0,20,4,29.9908709526062 +46,SPOON,SUM,1,0,1,0,22,1439,0,0.0 +46,,SUM,2,0,2,0,22,2865,34,29.9908709526062 +46,, +47,, +47,BOWL,SUM,1,0,1,0,0,1112,60,0.0 +47,CUP,SUM,0,0,0,0,0,25,3,29.721153020858765 +47,SPOON,SUM,0,0,0,0,0,39,2,25.262455940246582 +47,,SUM,1,0,1,0,0,1176,65,54.98360896110535 +47,, +48,, +48,BOWL,SUM,0,0,0,0,0,21,3,31.488306999206543 +48,CUP,SUM,0,0,0,0,0,2,3,21.03487205505371 +48,SPOON,SUM,1,0,1,0,2,1581,0,0.0 +48,,SUM,1,0,1,0,2,1604,6,52.523179054260254 +48,, +49,, +49,BOWL,SUM,0,0,0,0,0,116,8,42.22543811798096 +49,CUP,SUM,0,0,0,0,0,53,12,55.961663007736206 +49,SPOON,SUM,0,0,0,0,0,87,3,34.097228050231934 +49,,SUM,0,0,0,0,0,256,23,132.2843291759491 +49,, +50,, +50,BOWL,SUM,0,0,0,0,38,242,3,75.90007495880127 +50,CUP,SUM,0,0,0,0,0,11,4,20.721118927001953 +50,SPOON,SUM,0,0,0,0,0,281,11,73.90509700775146 +50,,SUM,0,0,0,0,38,534,18,170.5262908935547 +50,, +51,, +51,BOWL,SUM,0,0,0,0,0,25,6,44.1587119102478 +51,CUP,SUM,0,0,0,0,0,89,18,81.4437940120697 +51,SPOON,SUM,0,0,0,0,0,5,2,28.452425003051758 +51,,SUM,0,0,0,0,0,119,26,154.05493092536926 +51,, +52,, +52,BOWL,SUM,0,0,0,0,0,121,2,33.502959966659546 +52,CUP,SUM,1,0,1,0,50,1125,14,0.0 +52,SPOON,SUM,0,0,0,0,0,27,0,21.057939052581787 +52,,SUM,1,0,1,0,50,1273,16,54.56089901924133 +52,, +53,, +53,BOWL,SUM,0,0,0,0,0,12,0,19.724541902542114 +53,CUP,SUM,1,0,1,0,6,566,102,0.0 +53,SPOON,SUM,0,0,0,0,0,165,1,47.109232902526855 +53,,SUM,1,0,1,0,6,743,103,66.83377480506897 +53,, +54,, +54,BOWL,SUM,1,0,1,0,0,1582,0,0.0 +54,CUP,SUM,0,0,0,0,0,5,9,21.71409296989441 +54,SPOON,SUM,0,0,0,0,0,6,16,50.21505689620972 +54,,SUM,1,0,1,0,0,1593,25,71.92914986610413 +54,, +55,, +55,BOWL,SUM,0,0,0,0,0,24,0,20.378875017166138 +55,CUP,SUM,0,0,0,0,0,150,8,44.889930963516235 +55,SPOON,SUM,0,0,0,0,6,10,1,26.734954118728638 +55,,SUM,0,0,0,0,6,184,9,92.00376009941101 +55,, +56,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_urdf_kitchen_new_var_and_orig_data_21_offset.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_urdf_kitchen_new_var_and_orig_data_21_offset.csv new file mode 100644 index 0000000000..ab2d67f0d4 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_urdf_kitchen_new_var_and_orig_data_21_offset.csv @@ -0,0 +1,159 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,60,15,64.4178390503 +0,CUP,SUM,0,0,0,0,0,36,14,34.4013369083 +0,SPOON,SUM,0,0,0,0,0,69,3,37.6175448895 +0,,SUM,0,0,0,0,0,165,32,136.4367208481 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,2,116,2,42.2036991119 +1,CUP,SUM,0,0,0,0,2,44,9,60.0065009594 +1,SPOON,SUM,0,0,0,0,0,89,0,29.3489229679 +1,,SUM,0,0,0,0,4,249,11,131.5591230392 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,0,68,0,24.2453341484 +2,CUP,SUM,0,0,0,0,2,39,6,30.3325030804 +2,SPOON,SUM,0,0,0,0,0,204,27,79.4397370815 +2,,SUM,0,0,0,0,2,311,33,134.0175743103 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,0,9,5,31.7882127762 +3,CUP,SUM,0,0,0,0,0,74,14,31.2922811508 +3,SPOON,SUM,0,0,0,0,6,19,0,22.5737519264 +3,,SUM,0,0,0,0,6,102,19,85.6542458534 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,96,1,36.884483099 +4,CUP,SUM,0,0,0,0,0,70,30,102.668817997 +4,SPOON,SUM,1,0,1,0,2,1582,0,0 +4,,SUM,1,0,1,0,2,1748,31,139.553301096 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,2,48,6,33.0644869804 +5,CUP,SUM,0,0,0,0,0,136,41,187.942125082 +5,SPOON,SUM,1,0,1,0,0,1545,8,0 +5,,SUM,1,0,1,0,2,1729,55,221.0066120625 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,0,10,1,23.4852979183 +6,CUP,SUM,0,0,0,0,0,146,2,38.8861558437 +6,SPOON,SUM,0,0,0,0,0,94,7,42.1510310173 +6,,SUM,0,0,0,0,0,250,10,104.5224847794 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,112,98,0,113.4256110191 +7,CUP,SUM,1,0,1,0,0,969,75,0 +7,SPOON,SUM,0,0,0,0,2,87,0,30.635447979 +7,,SUM,1,0,1,0,114,1154,75,144.0610589981 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,2,809,0,130.6746602058 +8,CUP,SUM,0,0,0,0,4,12,12,31.3567140102 +8,SPOON,SUM,0,0,0,0,0,12,2,20.6154119968 +8,,SUM,0,0,0,0,6,833,14,182.6467862129 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,1,0,1,0,0,1581,0,0 +9,CUP,SUM,0,0,0,0,0,14,10,25.6787419319 +9,SPOON,SUM,0,0,0,0,0,313,2,72.5799851418 +9,,SUM,1,0,1,0,0,1908,12,98.2587270737 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,1,0,1,0,0,1539,14,0 +10,CUP,SUM,1,0,1,0,0,250,110,0 +10,SPOON,SUM,0,0,0,0,0,45,1,28.5080900192 +10,,SUM,2,0,2,0,0,1834,125,28.5080900192 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,0,62,2,25.0188989639 +11,CUP,SUM,0,0,0,0,12,27,3,34.3416850567 +11,SPOON,SUM,0,0,0,0,0,114,12,47.5226948261 +11,,SUM,0,0,0,0,12,203,17,106.8832788467 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,0,706,8,133.7913370132 +12,CUP,SUM,0,0,0,0,0,25,7,21.2784662247 +12,SPOON,SUM,0,0,0,0,0,282,0,60.6166319847 +12,,SUM,0,0,0,0,0,1013,15,215.6864352226 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,0,20,4,23.9032127857 +13,CUP,SUM,0,0,0,0,2,15,6,21.971339941 +13,SPOON,SUM,1,0,1,0,0,1575,10,0 +13,,SUM,1,0,1,0,2,1610,20,45.8745527267 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,0,8,1,26.485722065 +14,CUP,SUM,0,0,0,0,0,34,10,42.9451861382 +14,SPOON,SUM,0,0,0,0,0,14,6,29.3647139072 +14,,SUM,0,0,0,0,0,56,17,98.7956221104 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,0,105,1,33.4059650898 +15,CUP,SUM,0,0,0,0,14,13,4,29.9115078449 +15,SPOON,SUM,0,0,0,0,0,208,0,47.3256452084 +15,,SUM,0,0,0,0,14,326,5,110.6431181431 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,13,2,28.1054470539 +16,CUP,SUM,0,0,0,0,0,71,34,120.0621759892 +16,SPOON,SUM,0,0,0,0,0,191,3,51.8278610706 +16,,SUM,0,0,0,0,0,275,39,199.9954841137 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,0,6,2,20.1087398529 +17,CUP,SUM,0,0,0,0,0,1,2,20.7723360062 +17,SPOON,SUM,0,0,0,0,0,56,4,32.947507143 +17,,SUM,0,0,0,0,0,63,8,73.8285830021 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,0,37,0,23.8909761906 +18,CUP,SUM,0,0,0,0,0,268,8,62.0061480999 +18,SPOON,SUM,0,0,0,0,0,2,4,28.3638119698 +18,,SUM,0,0,0,0,0,307,12,114.2609362602 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,26,0,19.7916970253 +19,CUP,SUM,0,0,0,0,26,140,18,106.3630390167 +19,SPOON,SUM,0,0,0,0,0,2,2,19.7059419155 +19,,SUM,0,0,0,0,26,168,20,145.8606779575 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,2,216,4,62.7763419151 +20,CUP,SUM,1,0,1,0,0,334,96,0 +20,SPOON,SUM,0,0,0,0,0,8,1,23.8051259518 +20,,SUM,1,0,1,0,2,558,101,86.5814678669 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,1,0,1,0,0,1323,30,0 +21,CUP,SUM,0,0,0,0,0,60,7,34.7004499435 +21,SPOON,SUM,0,0,0,0,0,335,2,73.4478421211 +21,,SUM,1,0,1,0,0,1718,39,108.1482920647 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,0,60,0,24.7396440506 +22,CUP,SUM,0,0,0,0,0,23,4,21.3903291225 +22,SPOON,SUM,0,0,0,0,0,21,2,20.9841299057 +22,,SUM,0,0,0,0,0,104,6,67.1141030788 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,20,6,35.8851728439 +23,CUP,SUM,0,0,0,0,0,17,7,29.8822488785 +23,SPOON,SUM,0,0,0,0,0,132,3,38.30885005 +23,,SUM,0,0,0,0,0,169,16,104.0762717724 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,0,6,0,19.7678961754 +24,CUP,SUM,0,0,0,0,0,17,6,29.135119915 +24,SPOON,SUM,0,0,0,0,0,61,0,25.3360450268 +24,,SUM,0,0,0,0,0,84,6,74.2390611172 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,0,21,4,35.9429531097 +25,CUP,SUM,0,0,0,0,0,78,8,30.7559418678 +25,SPOON,SUM,0,0,0,0,0,386,1,78.833078146 +25,,SUM,0,0,0,0,0,485,13,145.5319731236 +25,,,,,,,,,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_urdf_kitchen_new_var_and_orig_data_offset_20.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_urdf_kitchen_new_var_and_orig_data_offset_20.csv new file mode 100644 index 0000000000..b8620d664f --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_urdf_kitchen_new_var_and_orig_data_offset_20.csv @@ -0,0 +1,603 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,74,17,70.8268978596 +0,CUP,SUM,0,0,0,0,0,20,5,27.9378159046 +0,SPOON,SUM,0,0,0,0,0,2,0,26.7342700958 +0,,SUM,0,0,0,0,0,96,22,125.49898386 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,1,0,1,0,4,1439,22,0 +1,CUP,SUM,0,0,0,0,0,44,5,27.8267869949 +1,SPOON,SUM,0,0,0,0,0,6,0,27.1394309998 +1,,SUM,1,0,1,0,4,1489,27,54.9662179947 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,0,30,1,27.6529948711 +2,CUP,SUM,1,0,1,0,4,756,89,0 +2,SPOON,SUM,0,0,0,0,0,71,0,36.2025351524 +2,,SUM,1,0,1,0,4,857,90,63.8555300236 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,0,102,2,41.3206689358 +3,CUP,SUM,0,0,0,0,0,17,10,35.572947979 +3,SPOON,SUM,0,0,0,0,0,42,0,31.4449617863 +3,,SUM,0,0,0,0,0,161,12,108.338578701 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,1,0,23.6733739376 +4,CUP,SUM,0,0,0,0,0,39,10,55.4981350899 +4,SPOON,SUM,0,0,0,0,2,4,4,31.6272780895 +4,,SUM,0,0,0,0,2,44,14,110.798787117 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,0,891,2,144.6714878082 +5,CUP,SUM,0,0,0,0,0,22,6,46.3663709164 +5,SPOON,SUM,0,0,0,0,0,13,0,27.1031668186 +5,,SUM,0,0,0,0,0,926,8,218.1410255432 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,0,135,4,41.0504000187 +6,CUP,SUM,0,0,0,0,0,11,7,34.6019530296 +6,SPOON,SUM,1,0,1,0,0,1583,0,0 +6,,SUM,1,0,1,0,0,1729,11,75.6523530483 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,0,19,2,23.5203440189 +7,CUP,SUM,0,0,0,0,0,21,8,30.7975211143 +7,SPOON,SUM,0,0,0,0,0,9,0,26.4882068634 +7,,SUM,0,0,0,0,0,49,10,80.8060719967 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,1,0,1,0,0,1547,8,0 +8,CUP,SUM,0,0,0,0,0,4,9,26.732462883 +8,SPOON,SUM,0,0,0,0,0,13,2,34.8035309315 +8,,SUM,1,0,1,0,0,1564,19,61.5359938145 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,12,48,1,35.2072501183 +9,CUP,SUM,0,0,0,0,0,53,7,27.2681469917 +9,SPOON,SUM,0,0,0,0,0,146,11,57.1210310459 +9,,SUM,0,0,0,0,12,247,19,119.5964281559 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,51,3,39.4630432129 +10,CUP,SUM,0,0,0,0,18,101,12,50.4285941124 +10,SPOON,SUM,0,0,0,0,0,60,2,38.5984928608 +10,,SUM,0,0,0,0,18,212,17,128.4901301861 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,2,28,0,24.0493671894 +11,CUP,SUM,0,0,0,0,0,22,6,26.5288271904 +11,SPOON,SUM,0,0,0,0,0,407,10,89.1786301136 +11,,SUM,0,0,0,0,2,457,16,139.7568244934 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,34,97,2,58.0814681053 +12,CUP,SUM,0,0,0,0,0,24,1,25.8945009708 +12,SPOON,SUM,0,0,0,0,0,3,0,26.1888129711 +12,,SUM,0,0,0,0,34,124,3,110.1647820473 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,22,203,6,72.2099750042 +13,CUP,SUM,0,0,0,0,0,70,11,60.3242101669 +13,SPOON,SUM,0,0,0,0,0,57,1,35.2245330811 +13,,SUM,0,0,0,0,22,330,18,167.7587182522 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,0,24,4,39.1941978931 +14,CUP,SUM,0,0,0,0,0,26,7,34.8602330685 +14,SPOON,SUM,0,0,0,0,2,1,2,26.6729710102 +14,,SUM,0,0,0,0,2,51,13,100.7274019718 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,20,7,6,45.2288668156 +15,CUP,SUM,0,0,0,0,0,23,2,22.457324028 +15,SPOON,SUM,0,0,0,0,2,272,3,74.8734259605 +15,,SUM,0,0,0,0,22,302,11,142.5596168041 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,2,78,1,33.0716621876 +16,CUP,SUM,0,0,0,0,0,32,16,39.9263310432 +16,SPOON,SUM,0,0,0,0,0,111,11,53.150247097 +16,,SUM,0,0,0,0,2,221,28,126.1482403278 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,0,1518,1,237.3025140762 +17,CUP,SUM,0,0,0,0,2,7,3,22.5577368736 +17,SPOON,SUM,0,0,0,0,0,2,0,26.3094959259 +17,,SUM,0,0,0,0,2,1527,4,286.1697468758 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,2,25,4,39.8751730919 +18,CUP,SUM,0,0,0,0,16,285,12,103.1421740055 +18,SPOON,SUM,0,0,0,0,0,10,0,27.0078980923 +18,,SUM,0,0,0,0,18,320,16,170.0252451897 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,1,0,1,0,0,2119,10,0 +19,CUP,SUM,0,0,0,0,0,31,9,28.1502699852 +19,SPOON,SUM,0,0,0,0,0,175,2,57.5337779522 +19,,SUM,1,0,1,0,0,2325,21,85.6840479374 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,1,0,1,0,0,1537,10,0 +20,CUP,SUM,0,0,0,0,0,12,5,22.8142981529 +20,SPOON,SUM,0,0,0,0,0,7,6,35.4264390469 +20,,SUM,1,0,1,0,0,1556,21,58.2407371998 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,4,0,22.7915940285 +21,CUP,SUM,0,0,0,0,0,29,13,51.704982996 +21,SPOON,SUM,0,0,0,0,0,1,2,26.4925119877 +21,,SUM,0,0,0,0,0,34,15,100.9890890121 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,2,29,4,28.9458739758 +22,CUP,SUM,0,0,0,0,2,2,2,22.3924059868 +22,SPOON,SUM,1,0,1,0,0,1582,0,0 +22,,SUM,1,0,1,0,4,1613,6,51.3382799625 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,12,3,35.2964580059 +23,CUP,SUM,0,0,0,0,0,8,2,21.774928093 +23,SPOON,SUM,0,0,0,0,0,12,0,26.3360610008 +23,,SUM,0,0,0,0,0,32,5,83.4074470997 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,0,49,4,32.7235970497 +24,CUP,SUM,0,0,0,0,6,13,5,24.8707158566 +24,SPOON,SUM,0,0,0,0,0,78,0,35.5187289715 +24,,SUM,0,0,0,0,6,140,9,93.1130418777 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,0,23,0,23.96058321 +25,CUP,SUM,0,0,0,0,0,19,11,23.172055006 +25,SPOON,SUM,0,0,0,0,0,20,3,38.8800611496 +25,,SUM,0,0,0,0,0,62,14,86.0126993656 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,0,124,0,37.4754738808 +26,CUP,SUM,0,0,0,0,6,12,6,32.1204490662 +26,SPOON,SUM,0,0,0,0,2,177,0,50.0609209538 +26,,SUM,0,0,0,0,8,313,6,119.6568439007 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,0,18,0,23.6420960426 +27,CUP,SUM,0,0,0,0,2,89,22,79.4091150761 +27,SPOON,SUM,0,0,0,0,0,35,4,34.9010310173 +27,,SUM,0,0,0,0,2,142,26,137.952242136 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,0,202,6,58.0445590019 +28,CUP,SUM,0,0,0,0,4,19,1,27.1968998909 +28,SPOON,SUM,1,0,1,0,0,1581,0,0 +28,,SUM,1,0,1,0,4,1802,7,85.2414588928 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,0,56,0,27.8832390308 +29,CUP,SUM,0,0,0,0,0,18,0,22.2743990421 +29,SPOON,SUM,0,0,0,0,0,70,0,36.1096980572 +29,,SUM,0,0,0,0,0,144,0,86.2673361301 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,4,65,0,29.7002179623 +30,CUP,SUM,0,0,0,0,2,111,11,40.2094619274 +30,SPOON,SUM,0,0,0,0,0,65,0,35.3483040333 +30,,SUM,0,0,0,0,6,241,11,105.257983923 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,0,134,7,46.2338969707 +31,CUP,SUM,1,0,1,0,0,204,111,0 +31,SPOON,SUM,0,0,0,0,6,117,1,46.1285829544 +31,,SUM,1,0,1,0,6,455,119,92.3624799252 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,0,5,3,27.260201931 +32,CUP,SUM,1,0,1,0,34,1136,20,0 +32,SPOON,SUM,0,0,0,0,4,87,0,37.3867118359 +32,,SUM,1,0,1,0,38,1228,23,64.6469137669 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,2,50,0,29.0564219952 +33,CUP,SUM,0,0,0,0,2,30,11,52.2461299896 +33,SPOON,SUM,1,0,1,0,2,1558,0,0 +33,,SUM,1,0,1,0,6,1638,11,81.3025519848 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,4,36,1,29.2755799294 +34,CUP,SUM,1,0,1,0,16,956,63,0 +34,SPOON,SUM,0,0,0,0,0,82,0,36.3381979465 +34,,SUM,1,0,1,0,20,1074,64,65.6137778759 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,0,162,8,51.2654240131 +35,CUP,SUM,0,0,0,0,0,77,18,69.6667709351 +35,SPOON,SUM,0,0,0,0,14,53,0,40.1664390564 +35,,SUM,0,0,0,0,14,292,26,161.0986340046 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,0,38,1,28.3740000725 +36,CUP,SUM,0,0,0,0,0,16,7,26.5309481621 +36,SPOON,SUM,1,0,1,0,0,1582,0,0 +36,,SUM,1,0,1,0,0,1636,8,54.9049482346 +36,,,,,,,,,, +37,,,,,,,,,, +37,BOWL,SUM,0,0,0,0,6,31,2,25.3906140327 +37,CUP,SUM,0,0,0,0,0,6,2,25.9307031631 +37,SPOON,SUM,0,0,0,0,0,90,0,35.8847260475 +37,,SUM,0,0,0,0,6,127,4,87.2060432434 +37,,,,,,,,,, +38,,,,,,,,,, +38,BOWL,SUM,0,0,0,0,0,7,1,27.7414109707 +38,CUP,SUM,0,0,0,0,0,13,2,31.0384979248 +38,SPOON,SUM,1,0,1,0,22,1444,0,0 +38,,SUM,1,0,1,0,22,1464,3,58.7799088955 +38,,,,,,,,,, +39,,,,,,,,,, +39,BOWL,SUM,0,0,0,0,0,66,1,36.3026769161 +39,CUP,SUM,0,0,0,0,0,12,11,26.897382021 +39,SPOON,SUM,0,0,0,0,0,7,0,26.2982869148 +39,,SUM,0,0,0,0,0,85,12,89.4983458519 +39,,,,,,,,,, +40,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,0,73,4,48.6074919701 +40,CUP,SUM,0,0,0,0,0,17,7,26.8265709877 +40,SPOON,SUM,0,0,0,0,2,631,4,118.5117349625 +40,,SUM,0,0,0,0,2,721,15,193.9457979202 +40,,,,,,,,,, +41,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,72,186,0,94.674695015 +41,CUP,SUM,0,0,0,0,0,46,9,43.4503591061 +41,SPOON,SUM,0,0,0,0,0,4,6,39.5207998753 +41,,SUM,0,0,0,0,72,236,15,177.6458539963 +41,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,0,39,9,45.8746550083 +42,CUP,SUM,0,0,0,0,0,5,7,26.9672391415 +42,SPOON,SUM,0,0,0,0,6,404,3,99.1405289173 +42,,SUM,0,0,0,0,6,448,19,171.9824230671 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,1,0,1,0,4,1548,6,0 +43,CUP,SUM,0,0,0,0,0,61,19,70.1173670292 +43,SPOON,SUM,0,0,0,0,0,139,21,76.0831339359 +43,,SUM,1,0,1,0,4,1748,46,146.2005009651 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,1,0,1,0,0,1500,18,0 +44,CUP,SUM,0,0,0,0,2,17,4,32.2166171074 +44,SPOON,SUM,0,0,0,0,0,2,0,26.8081960678 +44,,SUM,1,0,1,0,2,1519,22,59.0248131752 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,0,43,0,24.2286331654 +45,CUP,SUM,0,0,0,0,0,6,15,39.0908198357 +45,SPOON,SUM,0,0,0,0,0,302,4,75.8153069019 +45,,SUM,0,0,0,0,0,351,19,139.134759903 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,2,8,2,23.964261055 +46,CUP,SUM,0,0,0,0,16,50,8,53.7440900803 +46,SPOON,SUM,1,0,1,0,0,1581,0,0 +46,,SUM,1,0,1,0,18,1639,10,77.7083511353 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,1,0,1,0,0,1582,0,0 +47,CUP,SUM,0,0,0,0,0,36,5,43.2834608555 +47,SPOON,SUM,0,0,0,0,0,78,0,36.2141358852 +47,,SUM,1,0,1,0,0,1696,5,79.4975967407 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,0,16,0,24.0604929924 +48,CUP,SUM,0,0,0,0,0,22,9,39.576636076 +48,SPOON,SUM,0,0,0,0,0,26,4,31.5173459053 +48,,SUM,0,0,0,0,0,64,13,95.1544749737 +48,,,,,,,,,, +49,, +49,BOWL,SUM,0,0,0,0,0,8,1,32.34467005729675 +49,CUP,SUM,0,0,0,0,0,36,10,45.33749508857727 +49,SPOON,SUM,0,0,0,0,0,14,6,36.70774507522583 +49,,SUM,0,0,0,0,0,58,17,114.38991022109985 +49,, +50,, +50,BOWL,SUM,0,0,0,0,0,105,1,37.552151918411255 +50,CUP,SUM,0,0,0,0,14,13,4,31.340137004852295 +50,SPOON,SUM,0,0,0,0,0,208,0,55.127496004104614 +50,,SUM,0,0,0,0,14,326,5,124.01978492736816 +50,, +51,, +51,BOWL,SUM,0,0,0,0,0,11,1,27.7061550617218 +51,CUP,SUM,0,0,0,0,0,31,4,31.102622985839844 +51,SPOON,SUM,0,0,0,0,0,578,12,119.7656900882721 +51,,SUM,0,0,0,0,0,620,17,178.57446813583374 +51,, +52,, +52,BOWL,SUM,0,0,0,0,0,27,3,28.265159130096436 +52,CUP,SUM,0,0,0,0,0,16,7,36.17244791984558 +52,SPOON,SUM,1,0,1,0,2,1583,0,0.0 +52,,SUM,1,0,1,0,2,1626,10,64.43760704994202 +52,, +53,, +53,BOWL,SUM,0,0,0,0,0,461,13,104.13248181343079 +53,CUP,SUM,0,0,0,0,0,9,6,22.53714895248413 +53,SPOON,SUM,0,0,0,0,0,858,2,149.87524914741516 +53,,SUM,0,0,0,0,0,1328,21,276.5448799133301 +53,, +54,, +54,BOWL,SUM,0,0,0,0,0,13,0,23.818592071533203 +54,CUP,SUM,0,0,0,0,0,27,12,40.80402994155884 +54,SPOON,SUM,0,0,0,0,0,112,0,37.53204393386841 +54,,SUM,0,0,0,0,0,152,12,102.15466594696045 +54,, +55,, +55,BOWL,SUM,0,0,0,0,0,632,42,191.9950258731842 +55,CUP,SUM,0,0,0,0,0,10,5,35.21354389190674 +55,SPOON,SUM,1,0,1,0,16,1467,0,0.0 +55,,SUM,1,0,1,0,16,2109,47,227.20856976509094 +55,, +56,, +56,BOWL,SUM,0,0,0,0,0,3,0,24.152432918548584 +56,CUP,SUM,0,0,0,0,0,47,6,39.965473890304565 +56,SPOON,SUM,1,0,1,0,2,1558,0,0.0 +56,,SUM,1,0,1,0,2,1608,6,64.11790680885315 +56,, +57,, +57,BOWL,SUM,1,1,0,0,392,304,0,0.0 +57,CUP,SUM,0,0,0,0,0,40,11,32.588995933532715 +57,SPOON,SUM,1,0,1,0,26,1341,0,0.0 +57,,SUM,2,1,1,0,418,1685,11,32.588995933532715 +57,, +58,, +58,BOWL,SUM,0,0,0,0,0,19,0,24.182656049728394 +58,CUP,SUM,0,0,0,0,0,111,7,54.11588096618652 +58,SPOON,SUM,0,0,0,0,20,377,0,88.34704208374023 +58,,SUM,0,0,0,0,20,507,7,166.64557909965515 +58,, +59,, +59,BOWL,SUM,0,0,0,0,0,35,0,24.885895013809204 +59,CUP,SUM,0,0,0,0,0,137,46,213.83675503730774 +59,SPOON,SUM,0,0,0,0,0,96,4,45.491820096969604 +59,,SUM,0,0,0,0,0,268,50,284.21447014808655 +59,, +60,, +60,BOWL,SUM,0,0,0,0,0,89,2,41.7550950050354 +60,CUP,SUM,0,0,0,0,4,17,19,53.4267098903656 +60,SPOON,SUM,1,0,1,0,26,1583,0,0.0 +60,,SUM,1,0,1,0,30,1689,21,95.181804895401 +60,, +61,, +61,BOWL,SUM,0,0,0,0,0,14,0,23.809246063232422 +61,CUP,SUM,0,0,0,0,0,23,5,23.078603982925415 +61,SPOON,SUM,0,0,0,0,0,450,0,91.85721516609192 +61,,SUM,0,0,0,0,0,487,5,138.74506521224976 +61,, +62,, +62,BOWL,SUM,0,0,0,0,0,21,3,28.28714108467102 +62,CUP,SUM,0,0,0,0,0,84,2,32.35740900039673 +62,SPOON,SUM,0,0,0,0,0,185,0,50.72635507583618 +62,,SUM,0,0,0,0,0,290,5,111.37090516090393 +62,, +63,, +63,BOWL,SUM,0,0,0,0,0,23,2,24.560804843902588 +63,CUP,SUM,0,0,0,0,0,24,6,40.089515924453735 +63,SPOON,SUM,0,0,0,0,0,3,1,31.79029393196106 +63,,SUM,0,0,0,0,0,50,9,96.44061470031738 +63,, +64,, +64,BOWL,SUM,0,0,0,0,0,37,7,36.607714891433716 +64,CUP,SUM,0,0,0,0,0,9,5,27.629971981048584 +64,SPOON,SUM,0,0,0,0,2,7,7,40.66761088371277 +64,,SUM,0,0,0,0,2,53,19,104.90529775619507 +64,, +65,, +65,BOWL,SUM,0,0,0,0,2,107,2,38.953410148620605 +65,CUP,SUM,0,0,0,0,0,139,52,201.86110305786133 +65,SPOON,SUM,0,0,0,0,2,10,6,36.73103904724121 +65,,SUM,0,0,0,0,4,256,60,277.54555225372314 +65,, +66,, +66,BOWL,SUM,0,0,0,0,0,204,0,51.26968002319336 +66,CUP,SUM,0,0,0,0,0,226,4,51.49994993209839 +66,SPOON,SUM,0,0,0,0,0,20,0,27.91160798072815 +66,,SUM,0,0,0,0,0,450,4,130.6812379360199 +66,, +67,, +67,BOWL,SUM,0,0,0,0,56,72,6,77.96985483169556 +67,CUP,SUM,0,0,0,0,0,42,4,27.774166107177734 +67,SPOON,SUM,1,0,1,0,6,1536,6,0.0 +67,,SUM,1,0,1,0,62,1650,16,105.74402093887329 +67,, +68,, +68,BOWL,SUM,0,0,0,0,0,62,3,33.34725213050842 +68,CUP,SUM,0,0,0,0,0,12,5,27.29019284248352 +68,SPOON,SUM,0,0,0,0,0,4,2,27.04372811317444 +68,,SUM,0,0,0,0,0,78,10,87.68117308616638 +68,, +69,, +69,BOWL,SUM,0,0,0,0,12,43,5,41.08380603790283 +69,CUP,SUM,1,0,1,0,6,492,103,0.0 +69,SPOON,SUM,0,0,0,0,0,43,0,32.18168616294861 +69,,SUM,1,0,1,0,18,578,108,73.26549220085144 +69,, +70,, +70,BOWL,SUM,0,0,0,0,0,84,1,38.18083095550537 +70,CUP,SUM,0,0,0,0,0,16,4,27.608883142471313 +70,SPOON,SUM,1,0,1,0,0,1585,0,0.0 +70,,SUM,1,0,1,0,0,1685,5,65.78971409797668 +70,, +71,, +71,BOWL,SUM,0,0,0,0,0,16,2,32.733861207962036 +71,CUP,SUM,0,0,0,0,0,119,6,50.12471103668213 +71,SPOON,SUM,0,0,0,0,2,6,0,27.74991798400879 +71,,SUM,0,0,0,0,2,141,8,110.60849022865295 +71,, +72,, +72,BOWL,SUM,0,0,0,0,0,30,0,24.67157793045044 +72,CUP,SUM,0,0,0,0,0,12,6,23.371321201324463 +72,SPOON,SUM,0,0,0,0,0,96,2,49.44112801551819 +72,,SUM,0,0,0,0,0,138,8,97.48402714729309 +72,, +73,, +73,BOWL,SUM,0,0,0,0,0,416,77,205.53404712677002 +73,CUP,SUM,0,0,0,0,0,20,8,31.700786113739014 +73,SPOON,SUM,1,0,1,0,8,1586,0,0.0 +73,,SUM,1,0,1,0,8,2022,85,237.23483324050903 +73,, +74,, +74,BOWL,SUM,0,0,0,0,0,82,1,37.20408391952515 +74,CUP,SUM,0,0,0,0,0,38,4,32.28237199783325 +74,SPOON,SUM,0,0,0,0,0,20,0,28.04283094406128 +74,,SUM,0,0,0,0,0,140,5,97.52928686141968 +74,, +75,, +75,BOWL,SUM,0,0,0,0,138,164,10,157.2413489818573 +75,CUP,SUM,0,0,0,0,24,245,8,104.80724596977234 +75,SPOON,SUM,0,0,0,0,0,25,3,32.95806694030762 +75,,SUM,0,0,0,0,162,434,21,295.00666189193726 +75,, +76,, +76,BOWL,SUM,0,0,0,0,2,101,5,51.14908814430237 +76,CUP,SUM,0,0,0,0,0,6,3,27.070538997650146 +76,SPOON,SUM,0,0,0,0,6,114,0,43.3409960269928 +76,,SUM,0,0,0,0,8,221,8,121.56062316894531 +76,, +77,, +77,BOWL,SUM,0,0,0,0,10,33,0,31.972867012023926 +77,CUP,SUM,0,0,0,0,18,13,1,41.049773931503296 +77,SPOON,SUM,0,0,0,0,0,691,0,128.80884289741516 +77,,SUM,0,0,0,0,28,737,1,201.83148384094238 +77,, +78,, +78,BOWL,SUM,0,0,0,0,0,855,2,150.58381009101868 +78,CUP,SUM,0,0,0,0,0,12,2,22.538084983825684 +78,SPOON,SUM,0,0,0,0,0,0,1,31.29582905769348 +78,,SUM,0,0,0,0,0,867,5,204.41772413253784 +78,, +79,, +79,BOWL,SUM,0,0,0,0,0,31,1,28.972872018814087 +79,CUP,SUM,0,0,0,0,0,14,4,22.557820081710815 +79,SPOON,SUM,0,0,0,0,2,211,2,56.09155082702637 +79,,SUM,0,0,0,0,2,256,7,107.62224292755127 +79,, +80,, +80,BOWL,SUM,0,0,0,0,2,459,4,94.37808609008789 +80,CUP,SUM,0,0,0,0,0,18,8,32.1424720287323 +80,SPOON,SUM,0,0,0,0,0,17,0,28.258009910583496 +80,,SUM,0,0,0,0,2,494,12,154.7785680294037 +80,, +81,, +81,BOWL,SUM,0,0,0,0,0,9,0,23.875941038131714 +81,CUP,SUM,0,0,0,0,0,49,10,58.543309926986694 +81,SPOON,SUM,0,0,0,0,0,89,2,37.299497842788696 +81,,SUM,0,0,0,0,0,147,12,119.7187488079071 +81,, +82,, +82,BOWL,SUM,0,0,0,0,0,12,0,24.36797308921814 +82,CUP,SUM,0,0,0,0,0,24,2,27.438289880752563 +82,SPOON,SUM,0,0,0,0,2,62,2,37.36979699134827 +82,,SUM,0,0,0,0,2,98,4,89.17605996131897 +82,, +83,, +83,BOWL,SUM,1,0,1,0,2,1320,30,0.0 +83,CUP,SUM,0,0,0,0,2,24,7,28.53793692588806 +83,SPOON,SUM,0,0,0,0,0,123,0,42.01532602310181 +83,,SUM,1,0,1,0,4,1467,37,70.55326294898987 +83,, +84,, +84,BOWL,SUM,1,0,1,0,0,1583,6,0.0 +84,CUP,SUM,0,0,0,0,0,29,9,45.49928593635559 +84,SPOON,SUM,0,0,0,0,0,168,0,51.05617594718933 +84,,SUM,1,0,1,0,0,1780,15,96.55546188354492 +84,, +85,, +85,BOWL,SUM,0,0,0,0,2,28,7,37.602872133255005 +85,CUP,SUM,0,0,0,0,6,245,9,74.22785210609436 +85,SPOON,SUM,0,0,0,0,0,11,0,27.30964207649231 +85,,SUM,0,0,0,0,8,284,16,139.14036631584167 +85,, +86,, +86,BOWL,SUM,0,0,0,0,0,18,0,23.978977918624878 +86,CUP,SUM,0,0,0,0,0,2,0,22.79436993598938 +86,SPOON,SUM,0,0,0,0,0,12,2,27.302072048187256 +86,,SUM,0,0,0,0,0,32,2,74.07541990280151 +86,, +87,, +87,BOWL,SUM,0,0,0,0,0,32,0,24.380627870559692 +87,CUP,SUM,1,0,1,0,12,992,58,0.0 +87,SPOON,SUM,0,0,0,0,0,28,8,42.092175006866455 +87,,SUM,1,0,1,0,12,1052,66,66.47280287742615 +87,, +88,, +88,BOWL,SUM,1,0,1,0,2,1469,14,0.0 +88,CUP,SUM,0,0,0,0,0,5,2,22.600815057754517 +88,SPOON,SUM,0,0,0,0,0,7,8,40.8795280456543 +88,,SUM,1,0,1,0,2,1481,24,63.48034310340881 +88,, +89,, +89,BOWL,SUM,1,0,1,0,10,1519,10,0.0 +89,CUP,SUM,0,0,0,0,0,11,7,23.238008975982666 +89,SPOON,SUM,0,0,0,0,0,121,0,41.83309507369995 +89,,SUM,1,0,1,0,10,1651,17,65.07110404968262 +89,, +90,, +90,BOWL,SUM,0,0,0,0,0,117,0,33.98329186439514 +90,CUP,SUM,0,0,0,0,0,10,4,22.944571018218994 +90,SPOON,SUM,0,0,0,0,2,300,3,74.60009789466858 +90,,SUM,0,0,0,0,2,427,7,131.52796077728271 +90,, +91,, +91,BOWL,SUM,0,0,0,0,0,20,0,24.74670696258545 +91,CUP,SUM,0,0,0,0,0,2,6,23.093858003616333 +91,SPOON,SUM,0,0,0,0,0,108,1,45.07496905326843 +91,,SUM,0,0,0,0,0,130,7,92.91553401947021 +91,, +92,, +92,BOWL,SUM,0,0,0,0,0,338,5,77.9530029296875 +92,CUP,SUM,0,0,0,0,0,16,0,23.329535007476807 +92,SPOON,SUM,0,0,0,0,0,18,2,35.81590819358826 +92,,SUM,0,0,0,0,0,372,7,137.09844613075256 +92,, +93,, +93,BOWL,SUM,0,0,0,0,0,21,0,24.332295179367065 +93,CUP,SUM,0,0,0,0,2,15,6,23.67279314994812 +93,SPOON,SUM,0,0,0,0,0,129,3,49.55849099159241 +93,,SUM,0,0,0,0,2,165,9,97.56357932090759 +93,, +94,, +94,BOWL,SUM,0,0,0,0,0,39,2,33.091761112213135 +94,CUP,SUM,0,0,0,0,0,32,9,45.967511892318726 +94,SPOON,SUM,0,0,0,0,0,401,1,87.26315903663635 +94,,SUM,0,0,0,0,0,472,12,166.3224320411682 +94,, +95,, +95,BOWL,SUM,0,0,0,0,2,56,9,46.75724220275879 +95,CUP,SUM,0,0,0,0,0,15,6,27.6285240650177 +95,SPOON,SUM,1,0,1,0,6,1583,0,0.0 +95,,SUM,1,0,1,0,8,1654,15,74.38576626777649 +95,, +96,, +96,BOWL,SUM,0,0,0,0,0,41,1,29.054709911346436 +96,CUP,SUM,0,0,0,0,0,22,3,30.865474939346313 +96,SPOON,SUM,0,0,0,0,0,66,0,36.919437885284424 +96,,SUM,0,0,0,0,0,129,4,96.83962273597717 +96,, +97,, +97,BOWL,SUM,0,0,0,0,0,40,0,29.21930193901062 +97,CUP,SUM,0,0,0,0,0,58,10,29.00004291534424 +97,SPOON,SUM,0,0,0,0,6,48,0,34.85069012641907 +97,,SUM,0,0,0,0,6,146,10,93.07003498077393 +97,, +98,, +98,BOWL,SUM,0,0,0,0,0,21,3,28.4028480052948 +98,CUP,SUM,0,0,0,0,8,91,26,83.37716007232666 +98,SPOON,SUM,0,0,0,0,2,54,4,37.63170790672302 +98,,SUM,0,0,0,0,10,166,33,149.41171598434448 +98,, +99,, +99,BOWL,SUM,0,0,0,0,0,17,2,33.01196002960205 +99,CUP,SUM,0,0,0,0,0,26,7,27.884660005569458 +99,SPOON,SUM,1,0,1,0,0,1552,10,0.0 +99,,SUM,1,0,1,0,0,1595,19,60.89662003517151 +99,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_urdf_kitchen_new_var_data_orig_old_spacy_offset_22.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_urdf_kitchen_new_var_data_orig_old_spacy_offset_22.csv new file mode 100644 index 0000000000..45dd4cd501 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_urdf_kitchen_new_var_data_orig_old_spacy_offset_22.csv @@ -0,0 +1,171 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,18,229,0,68.9963440895 +42,CUP,SUM,0,0,0,0,0,9,1,26.4340348244 +42,SPOON,SUM,1,0,1,0,0,1582,0,0 +42,,SUM,1,0,1,0,18,1820,1,95.4303789139 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,56,116,0,79.9690589905 +43,CUP,SUM,0,0,0,0,0,107,8,40.7685558796 +43,SPOON,SUM,0,0,0,0,0,54,4,36.072701931 +43,,SUM,0,0,0,0,56,277,12,156.8103168011 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,2,923,2,163.1681480408 +44,CUP,SUM,0,0,0,0,0,15,2,31.198348999 +44,SPOON,SUM,1,0,1,0,0,1581,0,0 +44,,SUM,1,0,1,0,2,2519,4,194.3664970398 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,0,489,8,100.219274044 +45,CUP,SUM,1,0,0,1,0,260,51,0 +45,SPOON,SUM,0,0,0,0,0,1311,0,214.4038147926 +45,,SUM,1,0,0,1,0,2060,59,314.6230888367 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,0,791,6,141.3282909393 +46,CUP,SUM,0,0,0,0,0,31,4,40.5027530193 +46,SPOON,SUM,0,0,0,0,0,36,1,35.8564841747 +46,,SUM,0,0,0,0,0,858,11,217.6875281334 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,1,0,1,0,0,1505,12,0 +47,CUP,SUM,0,0,0,0,0,16,10,48.2965600491 +47,SPOON,SUM,0,0,0,0,0,141,0,45.5945219994 +47,,SUM,1,0,1,0,0,1662,22,93.8910820484 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,0,39,2,32.6298799515 +48,CUP,SUM,0,0,0,0,0,17,2,22.9499671459 +48,SPOON,SUM,0,0,0,0,2,309,3,72.4762880802 +48,,SUM,0,0,0,0,2,365,7,128.0561351776 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,2,61,2,37.0273389816 +49,CUP,SUM,0,0,0,0,2,16,3,26.9119381905 +49,SPOON,SUM,0,0,0,0,0,49,1,35.9744360447 +49,,SUM,0,0,0,0,4,126,6,99.9137132168 +49,,,,,,,,,, +50,,,,,,,,,, +50,BOWL,SUM,0,0,0,0,0,22,8,36.4264848232 +50,CUP,SUM,0,0,0,0,0,32,4,31.1820831299 +50,SPOON,SUM,0,0,0,0,0,19,1,31.0216591358 +50,,SUM,0,0,0,0,0,73,13,98.6302270889 +50,,,,,,,,,, +51,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,0,40,0,27.926181078 +51,CUP,SUM,0,0,0,0,0,29,4,23.0344479084 +51,SPOON,SUM,0,0,0,0,0,133,0,41.0714511871 +51,,SUM,0,0,0,0,0,202,4,92.0320801735 +51,,,,,,,,,, +52,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,0,11,1,27.6224989891 +52,CUP,SUM,0,0,0,0,0,10,6,30.5902280807 +52,SPOON,SUM,0,0,0,0,0,1089,0,181.9770760536 +52,,SUM,0,0,0,0,0,1110,7,240.1898031235 +52,,,,,,,,,, +53,,,,,,,,,, +53,BOWL,SUM,0,0,0,0,2,11,0,24.2608959675 +53,CUP,SUM,0,0,0,0,0,60,4,31.1020469666 +53,SPOON,SUM,0,0,0,0,0,1,0,27.1566960812 +53,,SUM,0,0,0,0,2,72,4,82.5196390152 +53,,,,,,,,,, +54,,,,,,,,,, +54,BOWL,SUM,0,0,0,0,2,36,7,37.5189521313 +54,CUP,SUM,0,0,0,0,0,175,9,55.6745691299 +54,SPOON,SUM,0,0,0,0,0,27,1,31.8248779774 +54,,SUM,0,0,0,0,2,238,17,125.0183992386 +54,,,,,,,,,, +55,,,,,,,,,, +55,BOWL,SUM,0,0,0,0,62,91,7,84.9240019321 +55,CUP,SUM,0,0,0,0,4,321,59,232.2065999508 +55,SPOON,SUM,0,0,0,0,0,295,0,69.1713039875 +55,,SUM,0,0,0,0,66,707,66,386.3019058704 +55,,,,,,,,,, +56,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,0,97,1,37.2479720116 +56,CUP,SUM,0,0,0,0,0,36,5,27.7422468662 +56,SPOON,SUM,0,0,0,0,0,56,0,32.4963800907 +56,,SUM,0,0,0,0,0,189,6,97.4865989685 +56,,,,,,,,,, +57,,,,,,,,,, +57,BOWL,SUM,0,0,0,0,0,25,2,23.9649591446 +57,CUP,SUM,0,0,0,0,0,9,6,22.5667698383 +57,SPOON,SUM,0,0,0,0,0,15,0,27.0664019585 +57,,SUM,0,0,0,0,0,49,8,73.5981309414 +57,,,,,,,,,, +58,,,,,,,,,, +58,BOWL,SUM,1,0,1,0,0,1592,0,0 +58,CUP,SUM,0,0,0,0,0,85,18,91.9112911224 +58,SPOON,SUM,0,0,0,0,0,99,3,44.95550704 +58,,SUM,1,0,1,0,0,1776,21,136.8667981625 +58,,,,,,,,,, +59,,,,,,,,,, +59,BOWL,SUM,0,0,0,0,0,13,4,28.3912680149 +59,CUP,SUM,0,0,0,0,8,12,11,29.9622421265 +59,SPOON,SUM,0,0,0,0,2,14,0,28.1288101673 +59,,SUM,0,0,0,0,10,39,15,86.4823203087 +59,,,,,,,,,, +60,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,0,12,1,27.8608810902 +60,CUP,SUM,0,0,0,0,0,101,2,36.6035819054 +60,SPOON,SUM,0,0,0,0,0,2,1,30.6950380802 +60,,SUM,0,0,0,0,0,115,4,95.1595010757 +60,,,,,,,,,, +61,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,2,5,0,24.4513149261 +61,CUP,SUM,0,0,0,0,8,29,8,30.2048289776 +61,SPOON,SUM,0,0,0,0,20,704,0,137.5585179329 +61,,SUM,0,0,0,0,30,738,8,192.2146618366 +61,,,,,,,,,, +62,,,,,,,,,, +62,BOWL,SUM,0,0,0,0,0,22,0,24.5587189198 +62,CUP,SUM,0,0,0,0,0,104,26,65.3001048565 +62,SPOON,SUM,0,0,0,0,0,212,0,54.885324955 +62,,SUM,0,0,0,0,0,338,26,144.7441487312 +62,,,,,,,,,, +63,,,,,,,,,, +63,BOWL,SUM,0,0,0,0,0,22,8,56.9815850258 +63,CUP,SUM,0,0,0,0,0,146,18,47.6941969395 +63,SPOON,SUM,0,0,0,0,0,70,2,36.7326760292 +63,,SUM,0,0,0,0,0,238,28,141.4084579945 +63,,,,,,,,,, +64,,,,,,,,,, +64,BOWL,SUM,0,0,0,0,0,13,3,28.2540800571 +64,CUP,SUM,1,0,1,0,8,732,83,0 +64,SPOON,SUM,0,0,0,0,0,15,0,27.2941269875 +64,,SUM,1,0,1,0,8,760,86,55.5482070446 +64,,,,,,,,,, +65,,,,,,,,,, +65,BOWL,SUM,0,0,0,0,0,181,6,67.5725009441 +65,CUP,SUM,0,0,0,0,0,15,5,27.0746839046 +65,SPOON,SUM,0,0,0,0,40,22,1,64.2712130547 +65,,SUM,0,0,0,0,40,218,12,158.9183979034 +65,,,,,,,,,, +66,,,,,,,,,, +66,BOWL,SUM,0,0,0,0,4,1,0,24.7752959728 +66,CUP,SUM,1,0,1,0,0,138,101,0 +66,SPOON,SUM,0,0,0,0,0,200,1,58.0958769321 +66,,SUM,1,0,1,0,4,339,102,82.871172905 +66,,,,,,,,,, +67,,,,,,,,,, +67,BOWL,SUM,0,0,0,0,0,39,2,24.0880470276 +67,CUP,SUM,0,0,0,0,12,15,2,30.3406538963 +67,SPOON,SUM,0,0,0,0,0,72,2,44.2663228512 +67,,SUM,0,0,0,0,12,126,6,98.6950237751 +67,,,,,,,,,, +68,,,,,,,,,, +68,BOWL,SUM,1,0,1,0,2,1083,76,0 +68,CUP,SUM,0,0,0,0,0,793,24,209.6676089764 +68,SPOON,SUM,0,0,0,0,2,18,1,31.9318881035 +68,,SUM,1,0,1,0,4,1894,101,241.5994970799 +68,,,,,,,,,, +69,,,,,,,,,, +69,BOWL,SUM,0,0,0,0,22,840,2,152.0486588478 +69,CUP,SUM,0,0,0,0,0,51,3,31.8037548065 +69,SPOON,SUM,0,0,0,0,0,67,0,36.5603148937 +69,,SUM,0,0,0,0,22,958,5,220.4127285481 +69,,,,,,,,,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_urdf_kitchen_var_data_new_all_offset_22.csv b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_urdf_kitchen_var_data_new_all_offset_22.csv new file mode 100644 index 0000000000..ca04445bd9 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/VR_PR2_urdf_kitchen_var_data_new_all_offset_22.csv @@ -0,0 +1,603 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,130,31,68.0375299454 +0,CUP,SUM,0,0,0,0,0,9,0,15.6873588562 +0,SPOON,SUM,0,0,0,0,2,31,3,22.011649847 +0,,SUM,0,0,0,0,2,170,34,105.7365386486 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,0,19,12,30.0659418106 +1,CUP,SUM,0,0,0,0,0,147,57,133.4649322033 +1,SPOON,SUM,0,0,0,0,0,46,11,33.6780619621 +1,,SUM,0,0,0,0,0,212,80,197.208935976 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,1,0,1,0,0,1477,14,0 +2,CUP,SUM,0,0,0,0,0,16,3,16.047216177 +2,SPOON,SUM,0,0,0,0,0,16,2,18.7901089191 +2,,SUM,1,0,1,0,0,1509,19,34.8373250961 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,0,174,26,54.5206429958 +3,CUP,SUM,0,0,0,0,2,21,6,24.0472230911 +3,SPOON,SUM,0,0,0,0,0,11,2,18.5468239784 +3,,SUM,0,0,0,0,2,206,34,97.1146900654 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,36,4,20.6987190247 +4,CUP,SUM,0,0,0,0,0,36,3,16.6568830013 +4,SPOON,SUM,0,0,0,0,2,20,2,19.2005131245 +4,,SUM,0,0,0,0,2,92,9,56.5561151505 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,0,105,3,28.2280170918 +5,CUP,SUM,0,0,0,0,0,9,3,18.3762609959 +5,SPOON,SUM,1,0,1,0,0,1582,0,0 +5,,SUM,1,0,1,0,0,1696,6,46.6042780876 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,2,1170,3,119.549052 +6,CUP,SUM,0,0,0,0,0,17,3,21.0605540276 +6,SPOON,SUM,0,0,0,0,0,77,0,24.3955419064 +6,,SUM,0,0,0,0,2,1264,6,165.005147934 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,0,41,8,25.8328850269 +7,CUP,SUM,1,0,1,0,0,255,111,0 +7,SPOON,SUM,0,0,0,0,0,259,0,40.5887970924 +7,,SUM,1,0,1,0,0,555,119,66.4216821194 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,0,13,4,20.0293140411 +8,CUP,SUM,0,0,0,0,0,37,8,21.4222989082 +8,SPOON,SUM,1,0,1,0,0,1582,0,0 +8,,SUM,1,0,1,0,0,1632,12,41.4516129494 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,6,71,3,23.0035641193 +9,CUP,SUM,0,0,0,0,0,19,7,19.01364398 +9,SPOON,SUM,0,0,0,0,6,36,0,23.213973999 +9,,SUM,0,0,0,0,12,126,10,65.2311820984 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,143,0,23.9165399075 +10,CUP,SUM,0,0,0,0,6,16,9,18.1731829643 +10,SPOON,SUM,0,0,0,0,0,47,0,21.5368328094 +10,,SUM,0,0,0,0,6,206,9,63.6265556812 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,70,748,2,113.6054489613 +11,CUP,SUM,0,0,0,0,2,47,2,17.4887537956 +11,SPOON,SUM,1,0,1,0,0,1614,0,0 +11,,SUM,1,0,1,0,72,2409,4,131.0942027569 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,0,9,4,19.9984149933 +12,CUP,SUM,0,0,0,0,0,48,7,21.7371199131 +12,SPOON,SUM,1,0,1,0,2,1581,0,0 +12,,SUM,1,0,1,0,2,1638,11,41.7355349064 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,0,14,5,20.1631989479 +13,CUP,SUM,1,0,1,0,100,455,0,0 +13,SPOON,SUM,0,0,0,0,0,40,1,21.8561089039 +13,,SUM,1,0,1,0,100,509,6,42.0193078518 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,1,0,1,0,0,1586,0,0 +14,CUP,SUM,0,0,0,0,0,19,2,14.4789319038 +14,SPOON,SUM,0,0,0,0,0,24,4,21.9724218845 +14,,SUM,1,0,1,0,0,1629,6,36.4513537884 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,0,130,31,61.0815448761 +15,CUP,SUM,0,0,0,0,0,9,0,13.7119879723 +15,SPOON,SUM,0,0,0,0,2,31,3,21.6119880676 +15,,SUM,0,0,0,0,2,170,34,96.405520916 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,19,12,29.6273350716 +16,CUP,SUM,0,0,0,0,0,147,57,133.8976099491 +16,SPOON,SUM,0,0,0,0,0,46,11,33.6437489986 +16,,SUM,0,0,0,0,0,212,80,197.1686940193 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,1,0,1,0,0,1477,14,0 +17,CUP,SUM,0,0,0,0,0,16,3,15.9483311176 +17,SPOON,SUM,0,0,0,0,0,16,2,19.1904919147 +17,,SUM,1,0,1,0,0,1509,19,35.1388230324 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,0,174,26,54.6319921017 +18,CUP,SUM,0,0,0,0,2,21,6,24.1182119846 +18,SPOON,SUM,0,0,0,0,0,11,2,18.7927830219 +18,,SUM,0,0,0,0,2,206,34,97.5429871082 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,36,4,20.4185819626 +19,CUP,SUM,0,0,0,0,0,36,3,16.4010519981 +19,SPOON,SUM,0,0,0,0,2,20,2,19.2390680313 +19,,SUM,0,0,0,0,2,92,9,56.058701992 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,0,105,3,28.3866660595 +20,CUP,SUM,0,0,0,0,0,9,3,18.2824831009 +20,SPOON,SUM,1,0,1,0,0,1582,0,0 +20,,SUM,1,0,1,0,0,1696,6,46.6691491604 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,2,1170,3,119.7014360428 +21,CUP,SUM,0,0,0,0,0,17,3,20.8866870403 +21,SPOON,SUM,0,0,0,0,0,77,0,24.5977511406 +21,,SUM,0,0,0,0,2,1264,6,165.1858742237 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,0,41,8,25.9304919243 +22,CUP,SUM,1,0,1,0,0,255,111,0 +22,SPOON,SUM,0,0,0,0,0,259,0,41.4552350044 +22,,SUM,1,0,1,0,0,555,119,67.3857269287 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,13,4,20.0562009811 +23,CUP,SUM,0,0,0,0,0,37,8,21.6500229836 +23,SPOON,SUM,1,0,1,0,0,1582,0,0 +23,,SUM,1,0,1,0,0,1632,12,41.7062239647 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,6,71,3,23.0472669601 +24,CUP,SUM,0,0,0,0,0,19,7,18.710226059 +24,SPOON,SUM,0,0,0,0,6,36,0,23.5025758743 +24,,SUM,0,0,0,0,12,126,10,65.2600688934 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,0,143,0,24.2529449463 +25,CUP,SUM,0,0,0,0,6,16,9,18.2590792179 +25,SPOON,SUM,0,0,0,0,0,47,0,21.5057399273 +25,,SUM,0,0,0,0,6,206,9,64.0177640915 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,70,748,2,113.1435139179 +26,CUP,SUM,0,0,0,0,2,47,2,17.3831501007 +26,SPOON,SUM,1,0,1,0,0,1614,0,0 +26,,SUM,1,0,1,0,72,2409,4,130.5266640186 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,0,9,4,19.874119997 +27,CUP,SUM,0,0,0,0,0,48,7,21.5837521553 +27,SPOON,SUM,1,0,1,0,2,1581,0,0 +27,,SUM,1,0,1,0,2,1638,11,41.4578721523 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,0,14,5,19.9247090816 +28,CUP,SUM,1,0,1,0,100,455,0,0 +28,SPOON,SUM,0,0,0,0,0,40,1,22.1191899776 +28,,SUM,1,0,1,0,100,509,6,42.0438990593 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,1,0,1,0,0,1586,0,0 +29,CUP,SUM,0,0,0,0,0,19,2,14.4776420593 +29,SPOON,SUM,0,0,0,0,0,24,4,22.0457510948 +29,,SUM,1,0,1,0,0,1629,6,36.5233931541 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,1,0,1,0,0,1566,8,0 +30,CUP,SUM,0,0,0,0,8,59,5,25.1807720661 +30,SPOON,SUM,0,0,0,0,4,5,6,25.1357810497 +30,,SUM,1,0,1,0,12,1630,19,50.3165531158 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,0,289,2,39.9941298962 +31,CUP,SUM,0,0,0,0,0,8,2,13.624147892 +31,SPOON,SUM,0,0,0,0,0,1,2,23.2968249321 +31,,SUM,0,0,0,0,0,298,6,76.9151027203 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,166,164,2,115.441380024 +32,CUP,SUM,0,0,0,0,0,29,9,26.4049658775 +32,SPOON,SUM,0,0,0,0,0,125,2,28.7360889912 +32,,SUM,0,0,0,0,166,318,13,170.5824348927 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,1,0,1,0,4,1567,0,0 +33,CUP,SUM,0,0,0,0,0,28,2,14.2335178852 +33,SPOON,SUM,0,0,0,0,4,47,2,23.8595280647 +33,,SUM,1,0,1,0,8,1642,4,38.0930459499 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,1,0,1,0,0,1611,0,0 +34,CUP,SUM,0,0,0,0,0,7,4,14.0408079624 +34,SPOON,SUM,0,0,0,0,0,144,1,32.4879431725 +34,,SUM,1,0,1,0,0,1762,5,46.5287511349 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,6,29,5,21.8864648342 +35,CUP,SUM,0,0,0,0,0,39,6,28.3693521023 +35,SPOON,SUM,1,0,1,0,0,1581,0,0 +35,,SUM,1,0,1,0,6,1649,11,50.2558169365 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,0,60,12,37.4750578403 +36,CUP,SUM,0,0,0,0,0,116,9,27.7958860397 +36,SPOON,SUM,0,0,0,0,60,421,2,81.9477119446 +36,,SUM,0,0,0,0,60,597,23,147.2186558247 +36,,,,,,,,,, +37,,,,,,,,,, +37,BOWL,SUM,0,0,0,0,0,137,2,26.6325078011 +37,CUP,SUM,0,0,0,0,0,43,11,33.8725149632 +37,SPOON,SUM,0,0,0,0,0,312,8,51.6174581051 +37,,SUM,0,0,0,0,0,492,21,112.1224808693 +37,,,,,,,,,, +38,,,,,,,,,, +38,BOWL,SUM,0,0,0,0,32,55,2,39.0136208534 +38,CUP,SUM,0,0,0,0,6,118,10,37.8796560764 +38,SPOON,SUM,0,0,0,0,0,31,2,24.2358920574 +38,,SUM,0,0,0,0,38,204,14,101.1291689873 +38,,,,,,,,,, +39,,,,,,,,,, +39,BOWL,SUM,1,0,1,0,0,858,78,0 +39,CUP,SUM,0,0,0,0,0,25,5,14.7122371197 +39,SPOON,SUM,0,0,0,0,0,175,0,32.7892611027 +39,,SUM,1,0,1,0,0,1058,83,47.5014982224 +39,,,,,,,,,, +40,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,0,152,0,27.0566921234 +40,CUP,SUM,0,0,0,0,0,11,0,13.7891280651 +40,SPOON,SUM,1,0,1,0,8,1497,0,0 +40,,SUM,1,0,1,0,8,1660,0,40.8458201885 +40,,,,,,,,,, +41,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,0,7,4,20.2192850113 +41,CUP,SUM,0,0,0,0,0,39,11,41.226211071 +41,SPOON,SUM,0,0,0,0,0,12,3,21.6942179203 +41,,SUM,0,0,0,0,0,58,18,83.1397140026 +41,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,2,35,9,26.0847501755 +42,CUP,SUM,0,0,0,0,0,38,6,19.1836631298 +42,SPOON,SUM,1,0,1,0,26,1450,0,0 +42,,SUM,1,0,1,0,28,1523,15,45.2684133053 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,6,66,0,22.5776557922 +43,CUP,SUM,0,0,0,0,8,19,21,29.2733588219 +43,SPOON,SUM,0,0,0,0,0,70,0,24.3284900188 +43,,SUM,0,0,0,0,14,155,21,76.1795046329 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,0,23,1,18.4435808659 +44,CUP,SUM,0,0,0,0,0,36,10,33.276170969 +44,SPOON,SUM,0,0,0,0,0,26,0,19.4871320724 +44,,SUM,0,0,0,0,0,85,11,71.2068839073 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,0,3,2,15.5094008446 +45,CUP,SUM,1,0,1,0,94,674,0,0 +45,SPOON,SUM,0,0,0,0,2,118,0,28.1974890232 +45,,SUM,1,0,1,0,96,795,2,43.7068898678 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,0,59,0,18.4647068977 +46,CUP,SUM,0,0,0,0,0,28,4,18.9589447975 +46,SPOON,SUM,0,0,0,0,0,1,0,18.8812758923 +46,,SUM,0,0,0,0,0,88,4,56.3049275875 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,0,0,0,0,58,41,1,50.3031220436 +47,CUP,SUM,0,0,0,0,0,34,3,21.2455790043 +47,SPOON,SUM,0,0,0,0,0,230,0,37.9570879936 +47,,SUM,0,0,0,0,58,305,4,109.5057890415 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,1,0,1,0,6,1471,12,0 +48,CUP,SUM,0,0,0,0,0,37,2,16.5818719864 +48,SPOON,SUM,0,0,0,0,0,105,1,29.8548300266 +48,,SUM,1,0,1,0,6,1613,15,46.436702013 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,0,46,0,18.299022913 +49,CUP,SUM,0,0,0,0,0,31,9,30.931399107 +49,SPOON,SUM,0,0,0,0,0,28,1,21.5693471432 +49,,SUM,0,0,0,0,0,105,10,70.7997691631 +49,,,,,,,,,, +50,,,,,,,,,, +50,BOWL,SUM,0,0,0,0,0,107,27,49.3279647827 +50,CUP,SUM,0,0,0,0,0,11,6,18.8559138775 +50,SPOON,SUM,1,0,1,0,10,1533,6,0 +50,,SUM,1,0,1,0,10,1651,39,68.1838786602 +50,,,,,,,,,, +51,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,2,529,70,124.389788866 +51,CUP,SUM,1,0,0,1,0,112,58,0 +51,SPOON,SUM,0,0,0,0,0,507,0,64.9290709496 +51,,SUM,1,0,0,1,2,1148,128,189.3188598156 +51,,,,,,,,,, +52,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,0,75,2,25.729557991 +52,CUP,SUM,0,0,0,0,2,15,2,14.3738029003 +52,SPOON,SUM,0,0,0,0,0,752,3,87.6067111492 +52,,SUM,0,0,0,0,2,842,7,127.7100720406 +52,,,,,,,,,, +53,,,,,,,,,, +53,BOWL,SUM,0,0,0,0,0,18,3,22.1036789417 +53,CUP,SUM,0,0,0,0,0,185,4,28.9333400726 +53,SPOON,SUM,0,0,0,0,0,75,8,30.0037350655 +53,,SUM,0,0,0,0,0,278,15,81.0407540798 +53,,,,,,,,,, +54,,,,,,,,,, +54,BOWL,SUM,0,0,0,0,0,50,0,18.6359770298 +54,CUP,SUM,0,0,0,0,0,12,2,14.0639050007 +54,SPOON,SUM,1,0,1,0,0,1312,36,0 +54,,SUM,1,0,1,0,0,1374,38,32.6998820305 +54,,,,,,,,,, +55,,,,,,,,,, +55,BOWL,SUM,0,0,0,0,10,51,1,25.7180979252 +55,CUP,SUM,1,0,0,1,0,199,61,0 +55,SPOON,SUM,0,0,0,0,0,24,0,19.2342031002 +55,,SUM,1,0,0,1,10,274,62,44.9523010254 +55,,,,,,,,,, +56,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,0,6,1,17.6278240681 +56,CUP,SUM,0,0,0,0,0,112,3,24.4525542259 +56,SPOON,SUM,0,0,0,0,22,29,2,30.6522948742 +56,,SUM,0,0,0,0,22,147,6,72.7326731682 +56,,,,,,,,,, +57,,,,,,,,,, +57,BOWL,SUM,1,0,1,0,0,1393,40,0 +57,CUP,SUM,0,0,0,0,0,28,16,43.2320179939 +57,SPOON,SUM,0,0,0,0,22,376,1,63.3735609055 +57,,SUM,1,0,1,0,22,1797,57,106.6055788994 +57,,,,,,,,,, +58,,,,,,,,,, +58,BOWL,SUM,0,0,0,0,0,94,5,24.678342104 +58,CUP,SUM,0,0,0,0,2,17,6,15.0086669922 +58,SPOON,SUM,0,0,0,0,0,139,2,32.9508390427 +58,,SUM,0,0,0,0,2,250,13,72.6378481388 +58,,,,,,,,,, +59,,,,,,,,,, +59,BOWL,SUM,1,0,1,0,0,1573,10,0 +59,CUP,SUM,0,0,0,0,20,46,4,31.6874480247 +59,SPOON,SUM,0,0,0,0,0,62,0,22.7774038315 +59,,SUM,1,0,1,0,20,1681,14,54.4648518562 +59,,,,,,,,,, +60,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,0,37,8,23.6682140827 +60,CUP,SUM,0,0,0,0,0,25,3,14.204474926 +60,SPOON,SUM,1,0,1,0,32,1582,0,0 +60,,SUM,1,0,1,0,32,1644,11,37.8726890087 +60,,,,,,,,,, +61,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,0,15,1,17.9156808853 +61,CUP,SUM,1,0,0,1,0,162,58,0 +61,SPOON,SUM,0,0,0,0,2,118,2,28.6651358604 +61,,SUM,1,0,0,1,2,295,61,46.5808167458 +61,,,,,,,,,, +62,,,,,,,,,, +62,BOWL,SUM,0,0,0,0,6,51,12,32.3734500408 +62,CUP,SUM,0,0,0,0,8,8,6,18.4388051033 +62,SPOON,SUM,0,0,0,0,2,367,0,50.9590260983 +62,,SUM,0,0,0,0,16,426,18,101.7712812424 +62,,,,,,,,,, +63,,,,,,,,,, +63,BOWL,SUM,0,0,0,0,0,45,6,21.4987468719 +63,CUP,SUM,0,0,0,0,0,22,4,14.2838590145 +63,SPOON,SUM,1,0,1,0,0,1795,0,0 +63,,SUM,1,0,1,0,0,1862,10,35.7826058865 +63,,,,,,,,,, +64,,,,,,,,,, +64,BOWL,SUM,1,0,1,0,0,1591,0,0 +64,CUP,SUM,0,0,0,0,0,7,9,17.2952649593 +64,SPOON,SUM,0,0,0,0,0,59,1,25.0411140919 +64,,SUM,1,0,1,0,0,1657,10,42.3363790512 +64,,,,,,,,,, +65,,,,,,,,,, +65,BOWL,SUM,0,0,0,0,0,12,4,20.5350580215 +65,CUP,SUM,0,0,0,0,0,11,2,13.994051218 +65,SPOON,SUM,0,0,0,0,0,128,24,51.9663259983 +65,,SUM,0,0,0,0,0,151,30,86.4954352379 +65,,,,,,,,,, +66,,,,,,,,,, +66,BOWL,SUM,0,0,0,0,0,20,0,15.525829792 +66,CUP,SUM,0,0,0,0,34,52,5,36.2882721424 +66,SPOON,SUM,0,0,0,0,0,36,0,21.8804490566 +66,,SUM,0,0,0,0,34,108,5,73.6945509911 +66,,,,,,,,,, +67,,,,,,,,,, +67,BOWL,SUM,0,0,0,0,0,80,10,29.2305469513 +67,CUP,SUM,1,0,1,0,0,443,105,0 +67,SPOON,SUM,0,0,0,0,0,7,8,31.2879681587 +67,,SUM,1,0,1,0,0,530,123,60.51851511 +67,,,,,,,,,, +68,,,,,,,,,, +68,BOWL,SUM,1,0,1,0,0,1531,10,0 +68,CUP,SUM,0,0,0,0,0,7,4,13.7232840061 +68,SPOON,SUM,0,0,0,0,0,101,1,27.6945571899 +68,,SUM,1,0,1,0,0,1639,15,41.4178411961 +68,,,,,,,,,, +69,,,,,,,,,, +69,BOWL,SUM,0,0,0,0,0,6,5,22.6429889202 +69,CUP,SUM,0,0,0,0,2,44,4,17.5418848991 +69,SPOON,SUM,0,0,0,0,0,93,0,27.2794959545 +69,,SUM,0,0,0,0,2,143,9,67.4643697739 +69,,,,,,,,,, +70,,,,,,,,,, +70,BOWL,SUM,0,0,0,0,2,79,5,26.6828830242 +70,CUP,SUM,0,0,0,0,16,30,11,38.6267991066 +70,SPOON,SUM,1,0,1,0,0,1601,0,0 +70,,SUM,1,0,1,0,18,1710,16,65.3096821308 +70,,,,,,,,,, +71,,,,,,,,,, +71,BOWL,SUM,1,0,1,0,0,1582,0,0 +71,CUP,SUM,0,0,0,0,0,8,4,13.9921321869 +71,SPOON,SUM,0,0,0,0,0,92,0,25.2553768158 +71,,SUM,1,0,1,0,0,1682,4,39.2475090027 +71,,,,,,,,,, +72,,,,,,,,,, +72,BOWL,SUM,1,0,1,0,0,1585,0,0 +72,CUP,SUM,0,0,0,0,0,13,7,23.6414330006 +72,SPOON,SUM,0,0,0,0,0,1,0,18.9530909061 +72,,SUM,1,0,1,0,0,1599,7,42.5945239067 +72,,,,,,,,,, +73,,,,,,,,,, +73,BOWL,SUM,0,0,0,0,0,46,8,24.2603981495 +73,CUP,SUM,0,0,0,0,22,147,7,48.3233499527 +73,SPOON,SUM,0,0,0,0,0,6,1,21.4612910748 +73,,SUM,0,0,0,0,22,199,16,94.0450391769 +73,,,,,,,,,, +74,,,,,,,,,, +74,BOWL,SUM,0,0,0,0,0,37,0,18.2857768536 +74,CUP,SUM,0,0,0,0,0,8,9,19.1046800613 +74,SPOON,SUM,0,0,0,0,6,246,0,41.2658560276 +74,,SUM,0,0,0,0,6,291,9,78.6563129425 +74,,,,,,,,,, +75,,,,,,,,,, +75,BOWL,SUM,0,0,0,0,0,37,6,21.7862870693 +75,CUP,SUM,0,0,0,0,0,37,6,17.7534241676 +75,SPOON,SUM,0,0,0,0,0,1,1,21.3957300186 +75,,SUM,0,0,0,0,0,75,13,60.9354412556 +75,,,,,,,,,, +76,,,,,,,,,, +76,BOWL,SUM,0,0,0,0,0,130,31,64.7759170532 +76,CUP,SUM,0,0,0,0,0,9,0,14.08968997 +76,SPOON,SUM,0,0,0,0,2,31,3,21.894824028 +76,,SUM,0,0,0,0,2,170,34,100.7604310513 +76,,,,,,,,,, +77,,,,,,,,,, +77,BOWL,SUM,0,0,0,0,0,19,12,29.8696122169 +77,CUP,SUM,0,0,0,0,0,147,57,134.6404728889 +77,SPOON,SUM,0,0,0,0,0,46,11,33.7446298599 +77,,SUM,0,0,0,0,0,212,80,198.2547149658 +77,,,,,,,,,, +78,,,,,,,,,, +78,BOWL,SUM,1,0,1,0,0,1477,14,0 +78,CUP,SUM,0,0,0,0,0,16,3,15.9400811195 +78,SPOON,SUM,0,0,0,0,0,16,2,19.3291890621 +78,,SUM,1,0,1,0,0,1509,19,35.2692701817 +78,,,,,,,,,, +79,,,,,,,,,, +79,BOWL,SUM,0,0,0,0,0,174,26,54.5864388943 +79,CUP,SUM,0,0,0,0,2,21,6,24.4062380791 +79,SPOON,SUM,0,0,0,0,0,11,2,19.0845191479 +79,,SUM,0,0,0,0,2,206,34,98.0771961212 +79,,,,,,,,,, +80,,,,,,,,,, +80,BOWL,SUM,0,0,0,0,0,36,4,20.6893429756 +80,CUP,SUM,0,0,0,0,0,36,3,16.6071140766 +80,SPOON,SUM,0,0,0,0,2,20,2,19.695982933 +80,,SUM,0,0,0,0,2,92,9,56.9924399853 +80,,,,,,,,,, +81,,,,,,,,,, +81,BOWL,SUM,0,0,0,0,0,105,3,28.591119051 +81,CUP,SUM,0,0,0,0,0,9,3,18.4378888607 +81,SPOON,SUM,1,0,1,0,0,1582,0,0 +81,,SUM,1,0,1,0,0,1696,6,47.0290079117 +81,,,,,,,,,, +82,,,,,,,,,, +82,BOWL,SUM,0,0,0,0,2,1170,3,119.1299071312 +82,CUP,SUM,0,0,0,0,0,17,3,20.7940340042 +82,SPOON,SUM,0,0,0,0,0,77,0,24.3500208855 +82,,SUM,0,0,0,0,2,1264,6,164.2739620209 +82,,,,,,,,,, +83,,,,,,,,,, +83,BOWL,SUM,0,0,0,0,0,41,8,25.8201160431 +83,CUP,SUM,1,0,1,0,0,255,111,0 +83,SPOON,SUM,0,0,0,0,0,259,0,41.3348650932 +83,,SUM,1,0,1,0,0,555,119,67.1549811363 +83,,,,,,,,,, +84,,,,,,,,,, +84,BOWL,SUM,0,0,0,0,0,13,4,20.1828711033 +84,CUP,SUM,0,0,0,0,0,37,8,21.4092459679 +84,SPOON,SUM,1,0,1,0,0,1582,0,0 +84,,SUM,1,0,1,0,0,1632,12,41.5921170712 +84,,,,,,,,,, +85,,,,,,,,,, +85,BOWL,SUM,0,0,0,0,6,71,3,22.8170399666 +85,CUP,SUM,0,0,0,0,0,19,7,19.0902180672 +85,SPOON,SUM,0,0,0,0,6,36,0,23.1229441166 +85,,SUM,0,0,0,0,12,126,10,65.0302021503 +85,,,,,,,,,, +86,,,,,,,,,, +86,BOWL,SUM,0,0,0,0,0,143,0,24.5008039474 +86,CUP,SUM,0,0,0,0,6,16,9,18.3959059715 +86,SPOON,SUM,0,0,0,0,0,47,0,21.4499211311 +86,,SUM,0,0,0,0,6,206,9,64.3466310501 +86,,,,,,,,,, +87,,,,,,,,,, +87,BOWL,SUM,0,0,0,0,70,748,2,113.3973009586 +87,CUP,SUM,0,0,0,0,2,47,2,17.3669681549 +87,SPOON,SUM,1,0,1,0,0,1614,0,0 +87,,SUM,1,0,1,0,72,2409,4,130.7642691135 +87,,,,,,,,,, +88,,,,,,,,,, +88,BOWL,SUM,0,0,0,0,0,9,4,19.6235599518 +88,CUP,SUM,0,0,0,0,0,48,7,21.9208021164 +88,SPOON,SUM,1,0,1,0,2,1581,0,0 +88,,SUM,1,0,1,0,2,1638,11,41.5443620682 +88,,,,,,,,,, +89,,,,,,,,,, +89,BOWL,SUM,0,0,0,0,0,14,5,20.0572481155 +89,CUP,SUM,1,0,1,0,100,455,0,0 +89,SPOON,SUM,0,0,0,0,0,40,1,22.0526349545 +89,,SUM,1,0,1,0,100,509,6,42.10988307 +89,,,,,,,,,, +90,,,,,,,,,, +90,BOWL,SUM,1,0,1,0,0,1586,0,0 +90,CUP,SUM,0,0,0,0,0,19,2,14.4101359844 +90,SPOON,SUM,0,0,0,0,0,24,4,21.3671360016 +90,,SUM,1,0,1,0,0,1629,6,35.777271986 +90,,,,,,,,,, +91,,,,,,,,,, +91,BOWL,SUM,1,0,1,0,0,1566,8,0 +91,CUP,SUM,0,0,0,0,8,59,5,24.8815181255 +91,SPOON,SUM,0,0,0,0,4,5,6,25.0803768635 +91,,SUM,1,0,1,0,12,1630,19,49.961894989 +91,,,,,,,,,, +92,,,,,,,,,, +92,BOWL,SUM,0,0,0,0,0,289,2,39.1787760258 +92,CUP,SUM,0,0,0,0,0,8,2,13.6297841072 +92,SPOON,SUM,0,0,0,0,0,1,2,22.7459630966 +92,,SUM,0,0,0,0,0,298,6,75.5545232296 +92,,,,,,,,,, +93,, +93,BOWL,SUM,0,0,0,0,0,130,31,60.96377515792847 +93,CUP,SUM,0,0,0,0,0,9,0,14.056469917297363 +93,SPOON,SUM,0,0,0,0,2,31,3,22.38870406150818 +93,,SUM,0,0,0,0,2,170,34,97.40894913673401 +93,, +94,, +94,BOWL,SUM,0,0,0,0,0,19,12,30.291822910308838 +94,CUP,SUM,0,0,0,0,0,147,57,135.76652908325195 +94,SPOON,SUM,0,0,0,0,0,46,11,33.95965385437012 +94,,SUM,0,0,0,0,0,212,80,200.0180058479309 +94,, +95,, +95,BOWL,SUM,1,0,1,0,0,1477,14,0.0 +95,CUP,SUM,0,0,0,0,0,16,3,16.094357013702393 +95,SPOON,SUM,0,0,0,0,0,16,2,19.313014030456543 +95,,SUM,1,0,1,0,0,1509,19,35.407371044158936 +95,, +96,, +96,BOWL,SUM,0,0,0,0,0,174,26,55.34837293624878 +96,CUP,SUM,0,0,0,0,2,21,6,24.588814973831177 +96,SPOON,SUM,0,0,0,0,0,11,2,18.748605012893677 +96,,SUM,0,0,0,0,2,206,34,98.68579292297363 +96,, +97,, +97,BOWL,SUM,0,0,0,0,0,36,4,20.606644868850708 +97,CUP,SUM,0,0,0,0,0,36,3,16.72837805747986 +97,SPOON,SUM,0,0,0,0,2,20,2,19.661919832229614 +97,,SUM,0,0,0,0,2,92,9,56.99694275856018 +97,, +98,, +98,BOWL,SUM,0,0,0,0,0,105,3,28.346001863479614 +98,CUP,SUM,0,0,0,0,0,9,3,18.439265966415405 +98,SPOON,SUM,1,0,1,0,0,1582,0,0.0 +98,,SUM,1,0,1,0,0,1696,6,46.78526782989502 +98,, +99,, +99,BOWL,SUM,0,0,0,0,2,1170,3,119.05117797851563 +99,CUP,SUM,0,0,0,0,0,17,3,20.875847101211548 +99,SPOON,SUM,0,0,0,0,0,77,0,24.303093910217285 +99,,SUM,0,0,0,0,2,1264,6,164.23011898994446 +99,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/failures_VR_continue_later_orig_kitchen_20_offset_new_var_data.csv b/cram_knowrob/cram_knowrob_vr/experiments/failures_VR_continue_later_orig_kitchen_20_offset_new_var_data.csv new file mode 100644 index 0000000000..af12052682 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/failures_VR_continue_later_orig_kitchen_20_offset_new_var_data.csv @@ -0,0 +1,124 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,0,53,15,27.887158155441284 +0,CUP,SUM,0,0,0,0,0,24,14,13.1420578956604 +0,SPOON,SUM,0,0,0,0,2,118,3,23.69696807861328 +0,,SUM,0,0,0,0,2,195,32,64.72618412971497 +0,, +1,, +1,BOWL,SUM,0,0,0,0,0,13,0,11.937226057052612 +1,CUP,SUM,1,0,1,0,0,77,112,0.0 +1,SPOON,SUM,0,0,0,0,0,127,2,25.1113760471344 +1,,SUM,1,0,1,0,0,217,114,37.04860210418701 +1,, +2,, +2,BOWL,SUM,0,0,0,0,60,42,0,42.01776909828186 +2,CUP,SUM,1,0,0,1,0,435,54,0.0 +2,SPOON,SUM,0,0,0,0,0,31,1,15.232048034667969 +2,,SUM,1,0,0,1,60,508,55,57.24981713294983 +2,, +3,, +3,BOWL,SUM,0,0,0,0,2,7,0,11.73085618019104 +3,CUP,SUM,0,0,0,0,0,9,0,9.533756971359253 +3,SPOON,SUM,0,0,0,0,0,54,3,20.917349100112915 +3,,SUM,0,0,0,0,2,70,3,42.18196225166321 +3,, +4,, +4,BOWL,SUM,0,0,0,0,0,97,1,16.888303995132446 +4,CUP,SUM,1,0,1,0,62,154,68,0.0 +4,SPOON,SUM,0,0,0,0,0,368,0,36.58705997467041 +4,,SUM,1,0,1,0,62,619,69,53.475363969802856 +4,, +5,, +5,BOWL,SUM,1,0,1,0,0,1109,56,0.0 +5,CUP,SUM,0,0,0,0,0,13,6,11.200937032699585 +5,SPOON,SUM,0,0,0,0,2,76,0,19.7018940448761 +5,,SUM,1,0,1,0,2,1198,62,30.902831077575684 +5,, +6,, +6,BOWL,SUM,1,0,1,0,2,770,38,0.0 +6,CUP,SUM,0,0,0,0,0,14,7,10.496561050415039 +6,SPOON,SUM,0,0,0,0,0,137,3,27.68877601623535 +6,,SUM,1,0,1,0,2,921,48,38.18533706665039 +6,, +7,, +7,BOWL,SUM,0,0,0,0,0,16,0,12.083591938018799 +7,CUP,SUM,0,0,0,0,0,7,6,10.263035774230957 +7,SPOON,SUM,0,0,0,0,8,148,0,25.607982873916626 +7,,SUM,0,0,0,0,8,171,6,47.95461058616638 +7,, +8,, +8,BOWL,SUM,1,0,1,0,10,1292,18,0.0 +8,CUP,SUM,0,0,0,0,0,12,0,10.314388990402222 +8,SPOON,SUM,0,0,0,0,0,137,0,21.960097789764404 +8,,SUM,1,0,1,0,10,1441,18,32.274486780166626 +8,, +9,, +9,BOWL,SUM,0,0,0,0,0,64,2,15.615957021713257 +9,CUP,SUM,0,0,0,0,0,127,22,41.823365926742554 +9,SPOON,SUM,0,0,0,0,0,7,2,17.82087993621826 +9,,SUM,0,0,0,0,0,198,26,75.26020288467407 +9,, +10,, +10,BOWL,SUM,0,0,0,0,0,2,0,11.32550597190857 +10,CUP,SUM,0,0,0,0,0,22,5,12.128080129623413 +10,SPOON,SUM,0,0,0,0,6,90,3,24.71474003791809 +10,,SUM,0,0,0,0,6,114,8,48.16832613945007 +10,, +11,, +11,BOWL,SUM,0,0,0,0,2,45,0,14.067331075668335 +11,CUP,SUM,1,0,1,0,72,613,20,0.0 +11,SPOON,SUM,0,0,0,0,10,19,1,21.370594024658203 +11,,SUM,1,0,1,0,84,677,21,35.43792510032654 +11,, +12,, +12,BOWL,SUM,0,0,0,0,0,128,4,19.8647940158844 +12,CUP,SUM,1,0,0,1,0,299,59,0.0 +12,SPOON,SUM,0,0,0,0,0,28,1,16.43572998046875 +12,,SUM,1,0,0,1,0,455,64,36.30052399635315 +12,, +13,, +13,BOWL,SUM,1,0,1,0,44,580,30,0.0 +13,CUP,SUM,0,0,0,0,2,7,4,11.24937891960144 +13,SPOON,SUM,0,0,0,0,0,137,0,23.303306818008423 +13,,SUM,1,0,1,0,46,724,34,34.55268573760986 +13,, +14,, +14,BOWL,SUM,0,0,0,0,0,12,0,11.837409019470215 +14,CUP,SUM,0,0,0,0,0,26,2,10.579829931259155 +14,SPOON,SUM,0,0,0,0,2,0,1,16.650381803512573 +14,,SUM,0,0,0,0,2,38,3,39.06762075424194 +14,, +15,, +15,BOWL,SUM,0,0,0,0,0,54,24,32.89515209197998 +15,CUP,SUM,0,0,0,0,0,9,18,16.101927995681763 +15,SPOON,SUM,0,0,0,0,2,2,4,18.0538330078125 +15,,SUM,0,0,0,0,2,65,46,67.05091309547424 +15,, +16,, +16,BOWL,SUM,1,0,1,0,0,622,44,0.0 +16,CUP,SUM,0,0,0,0,0,32,10,17.837135076522827 +16,SPOON,SUM,0,0,0,0,0,741,26,76.37925887107849 +16,,SUM,1,0,1,0,0,1395,80,94.21639394760132 +16,, +17,, +17,BOWL,SUM,1,0,1,0,6,1108,50,0.0 +17,CUP,SUM,0,0,0,0,0,20,10,12.335167169570923 +17,SPOON,SUM,0,0,0,0,0,39,2,17.45169997215271 +17,,SUM,1,0,1,0,6,1167,62,29.786867141723633 +17,, +18,, +18,BOWL,SUM,0,0,0,0,40,122,9,52.80563187599182 +18,CUP,SUM,0,0,0,0,0,14,4,9.993349075317383 +18,SPOON,SUM,0,0,0,0,0,95,4,21.208834171295166 +18,,SUM,0,0,0,0,40,231,17,84.00781512260437 +18,, +19,, +19,BOWL,SUM,1,0,1,0,2,1294,44,0.0 +19,CUP,SUM,0,0,0,0,16,14,8,18.972774028778076 +19,SPOON,SUM,0,0,0,0,0,318,0,34.432390213012695 +19,,SUM,1,0,1,0,18,1626,52,53.40516424179077 +19,, +20,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/heur_boxy_new.csv b/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/heur_boxy_new.csv new file mode 100644 index 0000000000..2838427ce5 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/heur_boxy_new.csv @@ -0,0 +1,1206 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,6,6,15.7989089489 +0,CUP,SUM,0,0,0,0,2,3,8,8.3967828751 +0,SPOON,SUM,0,0,0,0,0,1,0,11.3606410027 +0,,SUM,0,0,0,0,2,10,14,35.5563328266 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,16,11,0,15.0820300579 +1,CUP,SUM,0,0,0,0,0,3,20,14.1886210442 +1,SPOON,SUM,0,0,0,0,0,1,0,11.2034759521 +1,,SUM,0,0,0,0,16,15,20,40.4741270542 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,8,5,0,11.8901760578 +2,CUP,SUM,0,0,0,0,0,3,8,7.711370945 +2,SPOON,SUM,0,0,0,0,8,17,0,14.9883639812 +2,,SUM,0,0,0,0,16,25,8,34.589910984 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,16,7,41,32.0300071239 +3,CUP,SUM,0,0,0,0,0,5,77,27.8288981915 +3,SPOON,SUM,1,0,1,0,0,23,19,0 +3,,SUM,1,0,1,0,16,35,137,59.8589053154 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,3,0,7.6659319401 +4,CUP,SUM,0,0,0,0,2,5,38,15.7413299084 +4,SPOON,SUM,1,0,1,0,0,342,0,0 +4,,SUM,1,0,1,0,2,350,38,23.4072618484 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,0,2,1,10.6052951813 +5,CUP,SUM,0,0,0,0,8,6,17,15.5771460533 +5,SPOON,SUM,1,0,1,0,0,9,11,0 +5,,SUM,1,0,1,0,8,17,29,26.1824412346 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,24,5,0,19.4739069939 +6,CUP,SUM,0,0,0,0,0,8,8,7.7932510376 +6,SPOON,SUM,1,0,1,0,0,20,11,0 +6,,SUM,1,0,1,0,24,33,19,27.2671580315 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,0,5,12,11.8866109848 +7,CUP,SUM,0,0,0,0,0,6,8,7.5841121674 +7,SPOON,SUM,1,0,1,0,0,41,10,0 +7,,SUM,1,0,1,0,0,52,30,19.4707231522 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,0,8,21,18.0371940136 +8,CUP,SUM,0,0,0,0,0,10,23,13.657638073 +8,SPOON,SUM,1,0,1,0,0,66,10,0 +8,,SUM,1,0,1,0,0,84,54,31.6948320866 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,1,0,7.8348038197 +9,CUP,SUM,0,0,0,0,8,6,8,11.8644549847 +9,SPOON,SUM,0,0,0,0,0,12,1,12.2061028481 +9,,SUM,0,0,0,0,8,19,9,31.9053616524 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,4,7,15.7883968353 +10,CUP,SUM,0,0,0,0,0,12,8,9.3832139969 +10,SPOON,SUM,0,0,0,0,0,3,0,11.7502429485 +10,,SUM,0,0,0,0,0,19,15,36.9218537807 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,0,1,1,8.5644159317 +11,CUP,SUM,0,0,0,0,0,10,28,19.3353888988 +11,SPOON,SUM,0,0,0,0,0,3,2,13.7747700214 +11,,SUM,0,0,0,0,0,14,31,41.674574852 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,1,0,1,0,8,12,20,0 +12,CUP,SUM,0,0,0,0,0,4,16,16.2316439152 +12,SPOON,SUM,0,0,0,0,2,2,4,13.7078499794 +12,,SUM,1,0,1,0,10,18,40,29.9394938946 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,0,6,4,10.5884041786 +13,CUP,SUM,1,0,1,0,0,10,55,0 +13,SPOON,SUM,0,0,0,0,0,0,0,10.3811428547 +13,,SUM,1,0,1,0,0,16,59,20.9695470333 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,0,8,32,18.9185340405 +14,CUP,SUM,0,0,0,0,0,1,8,7.8663451672 +14,SPOON,SUM,0,0,0,0,0,5,7,16.8005578518 +14,,SUM,0,0,0,0,0,14,47,43.5854370594 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,0,5,0,8.3545849323 +15,CUP,SUM,1,0,1,0,24,8,114,0 +15,SPOON,SUM,0,0,0,0,0,5,0,11.1025650501 +15,,SUM,1,0,1,0,24,18,114,19.4571499825 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,1,1,0,0,0,42,0,0 +16,CUP,SUM,1,1,0,0,0,42,0,0 +16,SPOON,SUM,1,1,0,0,0,42,0,0 +16,,SUM,3,3,0,0,0,126,0,0 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,8,27,21,25.2107310295 +17,CUP,SUM,1,1,0,0,0,42,0,0 +17,SPOON,SUM,0,0,0,0,16,28,0,23.3357667923 +17,,SUM,1,1,0,0,24,97,21,48.5464978218 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,0,3,0,8.2551240921 +18,CUP,SUM,0,0,0,0,0,5,54,25.2994511127 +18,SPOON,SUM,0,0,0,0,0,1,0,10.6246819496 +18,,SUM,0,0,0,0,0,9,54,44.1792571545 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,0,0,8.556732893 +19,CUP,SUM,0,0,0,0,0,5,9,9.7596869469 +19,SPOON,SUM,1,0,1,0,8,9,11,0 +19,,SUM,1,0,1,0,8,14,20,18.3164198399 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,0,6,0,7.9355909824 +20,CUP,SUM,0,0,0,0,0,19,47,22.8868961334 +20,SPOON,SUM,0,0,0,0,0,0,0,10.7301909924 +20,,SUM,0,0,0,0,0,25,47,41.5526781082 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,1,0,1,0,2,11,44,0 +21,CUP,SUM,0,0,0,0,0,8,9,9.1454179287 +21,SPOON,SUM,0,0,0,0,0,5,0,10.8612658978 +21,,SUM,1,0,1,0,2,24,53,20.0066838264 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,8,22,0,12.7297110558 +22,CUP,SUM,0,0,0,0,32,6,21,29.9222960472 +22,SPOON,SUM,1,0,1,0,0,15,11,0 +22,,SUM,1,0,1,0,40,43,32,42.652007103 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,2,8,17.9260070324 +23,CUP,SUM,1,0,1,0,0,38,40,0 +23,SPOON,SUM,0,0,0,0,0,2,0,10.7280480862 +23,,SUM,1,0,1,0,0,42,48,28.6540551186 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,0,3,0,8.613795042 +24,CUP,SUM,0,0,0,0,0,1,9,9.6961321831 +24,SPOON,SUM,0,0,0,0,0,2,0,10.6809098721 +24,,SUM,0,0,0,0,0,6,9,28.9908370972 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,1,1,0,0,0,42,0,0 +25,CUP,SUM,1,0,1,0,0,19,60,0 +25,SPOON,SUM,0,0,0,0,0,5,17,26.0749690533 +25,,SUM,2,1,1,0,0,66,77,26.0749690533 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,0,6,12,13.8332350254 +26,CUP,SUM,0,0,0,0,0,6,14,10.3836598396 +26,SPOON,SUM,0,0,0,0,0,1,0,11.5986471176 +26,,SUM,0,0,0,0,0,13,26,35.8155419827 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,0,0,1,9.1369149685 +27,CUP,SUM,0,0,0,0,0,24,14,12.5124130249 +27,SPOON,SUM,1,0,1,0,0,341,0,0 +27,,SUM,1,0,1,0,0,365,15,21.6493279934 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,16,1,0,14.2331030369 +28,CUP,SUM,1,0,1,0,0,73,81,0 +28,SPOON,SUM,0,0,0,0,0,7,20,19.1855859756 +28,,SUM,1,0,1,0,16,81,101,33.4186890125 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,0,0,0,7.7040529251 +29,CUP,SUM,0,0,0,0,0,3,32,15.3843021393 +29,SPOON,SUM,1,0,1,0,0,20,44,0 +29,,SUM,1,0,1,0,0,23,76,23.0883550644 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,48,4,4,29.9289579391 +30,CUP,SUM,0,0,0,0,0,3,8,8.5302209854 +30,SPOON,SUM,1,0,1,0,8,57,10,0 +30,,SUM,1,0,1,0,56,64,22,38.4591789246 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,1,0,1,0,0,53,30,0 +31,CUP,SUM,0,0,0,0,0,8,9,9.8512098789 +31,SPOON,SUM,0,0,0,0,0,3,0,11.2837209702 +31,,SUM,1,0,1,0,0,64,39,21.1349308491 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,2,26,9,15.8571550846 +32,CUP,SUM,0,0,0,0,0,11,15,11.2879869938 +32,SPOON,SUM,0,0,0,0,2,0,0,11.4098339081 +32,,SUM,0,0,0,0,4,37,24,38.5549759865 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,5,1,9.4858760834 +33,CUP,SUM,0,0,0,0,8,6,9,14.161864996 +33,SPOON,SUM,0,0,0,0,16,28,10,29.0999810696 +33,,SUM,0,0,0,0,24,39,20,52.7477221489 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,0,2,16,14.5165309906 +34,CUP,SUM,1,0,1,0,10,24,125,0 +34,SPOON,SUM,0,0,0,0,16,5,4,19.2714159489 +34,,SUM,1,0,1,0,26,31,145,33.7879469395 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,0,3,0,8.1997702122 +35,CUP,SUM,0,0,0,0,0,11,8,8.203690052 +35,SPOON,SUM,0,0,0,0,0,0,0,11.3666920662 +35,,SUM,0,0,0,0,0,14,8,27.7701523304 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,0,14,1,11.3382301331 +36,CUP,SUM,1,0,1,0,0,4,38,0 +36,SPOON,SUM,0,0,0,0,0,0,0,10.2406609058 +36,,SUM,1,0,1,0,0,18,39,21.5788910389 +36,,,,,,,,,, +37,,,,,,,,,, +37,BOWL,SUM,1,0,1,0,8,10,41,0 +37,CUP,SUM,0,0,0,0,0,2,8,9.0133681297 +37,SPOON,SUM,0,0,0,0,0,2,8,15.4804620743 +37,,SUM,1,0,1,0,8,14,57,24.493830204 +37,,,,,,,,,, +38,,,,,,,,,, +38,BOWL,SUM,0,0,0,0,0,0,0,7.6489210129 +38,CUP,SUM,0,0,0,0,0,2,20,11.286206007 +38,SPOON,SUM,0,0,0,0,0,7,0,10.8063669205 +38,,SUM,0,0,0,0,0,9,20,29.7414939404 +38,,,,,,,,,, +39,,,,,,,,,, +39,BOWL,SUM,0,0,0,0,8,61,0,15.7717840672 +39,CUP,SUM,0,0,0,0,0,2,25,13.7106769085 +39,SPOON,SUM,0,0,0,0,16,11,0,19.0684878826 +39,,SUM,0,0,0,0,24,74,25,48.5509488583 +39,,,,,,,,,, +40,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,0,4,9,12.2625281811 +40,CUP,SUM,0,0,0,0,0,8,10,9.947715044 +40,SPOON,SUM,0,0,0,0,0,4,8,11.8111031055 +40,,SUM,0,0,0,0,0,16,27,34.0213463306 +40,,,,,,,,,, +41,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,8,2,0,12.0384340286 +41,CUP,SUM,0,0,0,0,0,5,8,9.573007822 +41,SPOON,SUM,1,0,1,0,2,120,8,0 +41,,SUM,1,0,1,0,10,127,16,21.6114418507 +41,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,0,15,0,8.8791720867 +42,CUP,SUM,0,0,0,0,0,1,18,13.2037460804 +42,SPOON,SUM,0,0,0,0,0,1,0,10.9812421799 +42,,SUM,0,0,0,0,0,17,18,33.064160347 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,8,6,16,17.123814106 +43,CUP,SUM,0,0,0,0,0,8,29,20.8613641262 +43,SPOON,SUM,0,0,0,0,0,12,0,11.2136998177 +43,,SUM,0,0,0,0,8,26,45,49.1988780499 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,0,6,4,12.8930578232 +44,CUP,SUM,1,0,1,0,0,10,91,0 +44,SPOON,SUM,0,0,0,0,0,5,0,10.8758749962 +44,,SUM,1,0,1,0,0,21,95,23.7689328194 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,0,25,1,11.1726751328 +45,CUP,SUM,0,0,0,0,0,11,84,33.2223689556 +45,SPOON,SUM,1,1,0,0,0,72,0,0 +45,,SUM,1,1,0,0,0,108,85,44.3950440884 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,0,1,5,10.3954000473 +46,CUP,SUM,1,0,1,0,0,14,77,0 +46,SPOON,SUM,0,0,0,0,0,2,0,11.46935606 +46,,SUM,1,0,1,0,0,17,82,21.8647561073 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,1,1,0,0,0,42,0,0 +47,CUP,SUM,1,1,0,0,0,42,0,0 +47,SPOON,SUM,0,0,0,0,0,5,4,12.9049758911 +47,,SUM,2,2,0,0,0,89,4,12.9049758911 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,0,1,0,7.9808881283 +48,CUP,SUM,0,0,0,0,0,2,12,12.1390988827 +48,SPOON,SUM,0,0,0,0,0,11,0,11.8105919361 +48,,SUM,0,0,0,0,0,14,12,31.9305789471 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,0,10,0,8.1406919956 +49,CUP,SUM,0,0,0,0,2,9,8,10.4428071976 +49,SPOON,SUM,0,0,0,0,0,3,0,11.1029160023 +49,,SUM,0,0,0,0,2,22,8,29.6864151955 +49,,,,,,,,,, +50,,,,,,,,,, +50,BOWL,SUM,1,0,1,0,2,7,44,0 +50,CUP,SUM,1,0,1,0,0,4,61,0 +50,SPOON,SUM,0,0,0,0,8,1,2,14.6231129169 +50,,SUM,2,0,2,0,10,12,107,14.6231129169 +50,,,,,,,,,, +51,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,0,3,0,9.517457962 +51,CUP,SUM,0,0,0,0,0,18,108,40.1570248604 +51,SPOON,SUM,0,0,0,0,0,2,0,11.0952630043 +51,,SUM,0,0,0,0,0,23,108,60.7697458267 +51,,,,,,,,,, +52,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,2,2,1,9.1849300861 +52,CUP,SUM,0,0,0,0,2,4,12,8.7280049324 +52,SPOON,SUM,0,0,0,0,40,14,0,28.5264849663 +52,,SUM,0,0,0,0,44,20,13,46.4394199848 +52,,,,,,,,,, +53,,,,,,,,,, +53,BOWL,SUM,0,0,0,0,0,18,4,12.4301438332 +53,CUP,SUM,0,0,0,0,0,4,8,7.7957139015 +53,SPOON,SUM,1,1,0,0,0,72,0,0 +53,,SUM,1,1,0,0,0,94,12,20.2258577347 +53,,,,,,,,,, +54,,,,,,,,,, +54,BOWL,SUM,0,0,0,0,24,29,0,19.955477953 +54,CUP,SUM,1,0,0,1,0,20,53,0 +54,SPOON,SUM,1,0,1,0,0,26,44,0 +54,,SUM,2,0,1,1,24,75,97,19.955477953 +54,,,,,,,,,, +55,,,,,,,,,, +55,BOWL,SUM,0,0,0,0,0,2,0,8.2090289593 +55,CUP,SUM,0,0,0,0,0,5,9,10.2763059139 +55,SPOON,SUM,0,0,0,0,0,1,8,15.3454201221 +55,,SUM,0,0,0,0,0,8,17,33.8307549953 +55,,,,,,,,,, +56,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,10,43,4,17.6249010563 +56,CUP,SUM,1,0,1,0,0,9,46,0 +56,SPOON,SUM,0,0,0,0,0,3,0,10.68334198 +56,,SUM,1,0,1,0,10,55,50,28.3082430363 +56,,,,,,,,,, +57,,,,,,,,,, +57,BOWL,SUM,0,0,0,0,4,5,0,9.7522201538 +57,CUP,SUM,0,0,0,0,0,0,8,7.8045890331 +57,SPOON,SUM,0,0,0,0,0,8,0,11.6346371174 +57,,SUM,0,0,0,0,4,13,8,29.1914463043 +57,,,,,,,,,, +58,,,,,,,,,, +58,BOWL,SUM,0,0,0,0,0,0,4,14.4267239571 +58,CUP,SUM,0,0,0,0,0,3,23,13.5170929432 +58,SPOON,SUM,1,0,1,0,0,53,10,0 +58,,SUM,1,0,1,0,0,56,37,27.9438169003 +58,,,,,,,,,, +59,,,,,,,,,, +59,BOWL,SUM,0,0,0,0,0,4,1,9.4996738434 +59,CUP,SUM,0,0,0,0,0,31,50,27.3361949921 +59,SPOON,SUM,0,0,0,0,8,9,0,14.4981529713 +59,,SUM,0,0,0,0,8,44,51,51.3340218067 +59,,,,,,,,,, +60,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,0,7,7,11.9396460056 +60,CUP,SUM,0,0,0,0,8,29,49,35.7933499813 +60,SPOON,SUM,1,0,1,0,0,342,0,0 +60,,SUM,1,0,1,0,8,378,56,47.7329959869 +60,,,,,,,,,, +61,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,0,2,1,9.1835758686 +61,CUP,SUM,1,0,1,0,8,18,165,0 +61,SPOON,SUM,0,0,0,0,8,2,1,14.9727959633 +61,,SUM,1,0,1,0,16,22,167,24.1563718319 +61,,,,,,,,,, +62,,,,,,,,,, +62,BOWL,SUM,0,0,0,0,0,0,0,8.4736099243 +62,CUP,SUM,1,0,1,0,10,12,132,0 +62,SPOON,SUM,0,0,0,0,8,1,0,15.6323661804 +62,,SUM,1,0,1,0,18,13,132,24.1059761047 +62,,,,,,,,,, +63,,,,,,,,,, +63,BOWL,SUM,1,0,1,0,0,6,44,0 +63,CUP,SUM,0,0,0,0,16,3,15,19.9689090252 +63,SPOON,SUM,0,0,0,0,0,4,12,16.4342830181 +63,,SUM,1,0,1,0,16,13,71,36.4031920433 +63,,,,,,,,,, +64,,,,,,,,,, +64,BOWL,SUM,1,0,1,0,0,9,38,0 +64,CUP,SUM,0,0,0,0,0,1,20,11.6264269352 +64,SPOON,SUM,0,0,0,0,0,1,0,11.3121669292 +64,,SUM,1,0,1,0,0,11,58,22.9385938644 +64,,,,,,,,,, +65,,,,,,,,,, +65,BOWL,SUM,1,0,0,1,0,9,39,0 +65,CUP,SUM,1,0,1,0,24,15,11,0 +65,SPOON,SUM,0,0,0,0,0,4,0,11.4336879253 +65,,SUM,2,0,1,1,24,28,50,11.4336879253 +65,,,,,,,,,, +66,,,,,,,,,, +66,BOWL,SUM,0,0,0,0,8,5,0,11.3199560642 +66,CUP,SUM,0,0,0,0,0,11,16,12.1162080765 +66,SPOON,SUM,1,0,1,0,16,342,0,0 +66,,SUM,1,0,1,0,24,358,16,23.4361641407 +66,,,,,,,,,, +67,,,,,,,,,, +67,BOWL,SUM,0,0,0,0,0,3,1,9.0403380394 +67,CUP,SUM,1,0,1,0,0,9,120,0 +67,SPOON,SUM,0,0,0,0,16,1,0,17.8474371433 +67,,SUM,1,0,1,0,16,13,121,26.8877751827 +67,,,,,,,,,, +68,,,,,,,,,, +68,BOWL,SUM,0,0,0,0,16,18,9,20.1750719547 +68,CUP,SUM,0,0,0,0,0,3,14,11.3902609348 +68,SPOON,SUM,0,0,0,0,0,10,6,13.7627129555 +68,,SUM,0,0,0,0,16,31,29,45.328045845 +68,,,,,,,,,, +69,,,,,,,,,, +69,BOWL,SUM,0,0,0,0,2,3,5,11.9049670696 +69,CUP,SUM,0,0,0,0,0,4,8,8.1408231258 +69,SPOON,SUM,0,0,0,0,0,0,0,10.791675806 +69,,SUM,0,0,0,0,2,7,13,30.8374660015 +69,,,,,,,,,, +70,,,,,,,,,, +70,BOWL,SUM,0,0,0,0,0,5,20,15.617194891 +70,CUP,SUM,1,0,1,0,8,311,12,0 +70,SPOON,SUM,1,1,0,0,0,42,0,0 +70,,SUM,2,1,1,0,8,358,32,15.617194891 +70,,,,,,,,,, +71,,,,,,,,,, +71,BOWL,SUM,0,0,0,0,0,4,0,8.889605999 +71,CUP,SUM,1,0,1,0,2,22,55,0 +71,SPOON,SUM,0,0,0,0,0,0,0,11.9026219845 +71,,SUM,1,0,1,0,2,26,55,20.7922279835 +71,,,,,,,,,, +72,,,,,,,,,, +72,BOWL,SUM,0,0,0,0,0,3,0,8.3523201942 +72,CUP,SUM,0,0,0,0,0,11,9,11.3410670757 +72,SPOON,SUM,1,0,1,0,0,14,11,0 +72,,SUM,1,0,1,0,0,28,20,19.69338727 +72,,,,,,,,,, +73,,,,,,,,,, +73,BOWL,SUM,0,0,0,0,0,1,0,8.1731960773 +73,CUP,SUM,0,0,0,0,0,5,57,23.8641250134 +73,SPOON,SUM,0,0,0,0,0,2,0,11.1556720734 +73,,SUM,0,0,0,0,0,8,57,43.1929931641 +73,,,,,,,,,, +74,,,,,,,,,, +74,BOWL,SUM,0,0,0,0,0,0,0,8.307060957 +74,CUP,SUM,1,1,0,0,0,42,0,0 +74,SPOON,SUM,0,0,0,0,0,12,0,13.5193171501 +74,,SUM,1,1,0,0,0,54,0,21.8263781071 +74,,,,,,,,,, +75,,,,,,,,,, +75,BOWL,SUM,1,0,1,0,2,49,10,0 +75,CUP,SUM,0,0,0,0,8,3,22,19.3627328873 +75,SPOON,SUM,0,0,0,0,0,3,0,11.9470798969 +75,,SUM,1,0,1,0,10,55,32,31.3098127842 +75,,,,,,,,,, +76,,,,,,,,,, +76,BOWL,SUM,0,0,0,0,0,1,0,7.545732975 +76,CUP,SUM,0,0,0,0,2,5,48,25.6370260715 +76,SPOON,SUM,1,0,1,0,0,29,14,0 +76,,SUM,1,0,1,0,2,35,62,33.1827590466 +76,,,,,,,,,, +77,,,,,,,,,, +77,BOWL,SUM,0,0,0,0,0,13,31,26.2335560322 +77,CUP,SUM,1,0,1,0,0,8,42,0 +77,SPOON,SUM,0,0,0,0,0,6,0,10.8221240044 +77,,SUM,1,0,1,0,0,27,73,37.0556800365 +77,,,,,,,,,, +78,,,,,,,,,, +78,BOWL,SUM,0,0,0,0,24,19,0,22.076818943 +78,CUP,SUM,1,0,1,0,0,20,99,0 +78,SPOON,SUM,0,0,0,0,8,5,0,16.2747468948 +78,,SUM,1,0,1,0,32,44,99,38.3515658379 +78,,,,,,,,,, +79,,,,,,,,,, +79,BOWL,SUM,1,0,1,0,0,69,9,0 +79,CUP,SUM,0,0,0,0,0,2,8,8.0221960545 +79,SPOON,SUM,0,0,0,0,8,5,5,18.5069761276 +79,,SUM,1,0,1,0,8,76,22,26.5291721821 +79,,,,,,,,,, +80,,,,,,,,,, +80,BOWL,SUM,0,0,0,0,4,3,8,14.3890018463 +80,CUP,SUM,1,1,0,0,0,42,0,0 +80,SPOON,SUM,1,1,0,0,0,72,0,0 +80,,SUM,2,2,0,0,4,117,8,14.3890018463 +80,,,,,,,,,, +81,,,,,,,,,, +81,BOWL,SUM,0,0,0,0,0,5,17,17.2387650013 +81,CUP,SUM,1,0,1,0,16,9,47,0 +81,SPOON,SUM,0,0,0,0,0,5,0,11.7413449287 +81,,SUM,1,0,1,0,16,19,64,28.98010993 +81,,,,,,,,,, +82,,,,,,,,,, +82,BOWL,SUM,0,0,0,0,0,6,21,17.9587540627 +82,CUP,SUM,0,0,0,0,0,3,9,10.4868311882 +82,SPOON,SUM,0,0,0,0,0,8,0,10.6558570862 +82,,SUM,0,0,0,0,0,17,30,39.101442337 +82,,,,,,,,,, +83,,,,,,,,,, +83,BOWL,SUM,1,0,1,0,0,46,11,0 +83,CUP,SUM,0,0,0,0,0,6,8,8.8584330082 +83,SPOON,SUM,0,0,0,0,8,2,0,14.8223791122 +83,,SUM,1,0,1,0,8,54,19,23.6808121204 +83,,,,,,,,,, +84,,,,,,,,,, +84,BOWL,SUM,0,0,0,0,8,1,4,16.7374031544 +84,CUP,SUM,0,0,0,0,8,6,14,15.8277690411 +84,SPOON,SUM,0,0,0,0,0,3,0,10.1969761848 +84,,SUM,0,0,0,0,16,10,18,42.7621483803 +84,,,,,,,,,, +85,,,,,,,,,, +85,BOWL,SUM,1,0,1,0,0,314,6,0 +85,CUP,SUM,1,1,0,0,0,42,0,0 +85,SPOON,SUM,0,0,0,0,0,2,0,12.738120079 +85,,SUM,2,1,1,0,0,358,6,12.738120079 +85,,,,,,,,,, +86,,,,,,,,,, +86,BOWL,SUM,1,1,0,0,0,42,0,0 +86,CUP,SUM,0,0,0,0,0,5,16,11.9750409126 +86,SPOON,SUM,0,0,0,0,24,4,0,23.8428771496 +86,,SUM,1,1,0,0,24,51,16,35.8179180622 +86,,,,,,,,,, +87,,,,,,,,,, +87,BOWL,SUM,0,0,0,0,0,29,12,15.8929898739 +87,CUP,SUM,0,0,0,0,24,9,32,33.3028659821 +87,SPOON,SUM,0,0,0,0,0,9,0,11.6347029209 +87,,SUM,0,0,0,0,24,47,44,60.8305587769 +87,,,,,,,,,, +88,,,,,,,,,, +88,BOWL,SUM,0,0,0,0,8,1,4,13.2198240757 +88,CUP,SUM,0,0,0,0,0,3,8,9.7535300255 +88,SPOON,SUM,0,0,0,0,8,9,20,22.9323379993 +88,,SUM,0,0,0,0,16,13,32,45.9056921005 +88,,,,,,,,,, +89,,,,,,,,,, +89,BOWL,SUM,0,0,0,0,8,18,8,28.5738799572 +89,CUP,SUM,0,0,0,0,0,7,10,10.3885629177 +89,SPOON,SUM,1,0,0,1,0,12,55,0 +89,,SUM,1,0,0,1,8,37,73,38.9624428749 +89,,,,,,,,,, +90,,,,,,,,,, +90,BOWL,SUM,1,0,1,0,32,45,30,0 +90,CUP,SUM,0,0,0,0,32,4,8,21.4391958714 +90,SPOON,SUM,0,0,0,0,2,3,0,12.1154930592 +90,,SUM,1,0,1,0,66,52,38,33.5546889305 +90,,,,,,,,,, +91,,,,,,,,,, +91,BOWL,SUM,0,0,0,0,0,4,16,16.1027719975 +91,CUP,SUM,0,0,0,0,0,3,8,8.0849909782 +91,SPOON,SUM,1,1,0,0,0,42,0,0 +91,,SUM,1,1,0,0,0,49,24,24.1877629757 +91,,,,,,,,,, +92,,,,,,,,,, +92,BOWL,SUM,0,0,0,0,0,5,0,9.307874918 +92,CUP,SUM,0,0,0,0,0,9,9,10.2494652271 +92,SPOON,SUM,1,1,0,0,96,20,0,0 +92,,SUM,1,1,0,0,96,34,9,19.5573401451 +92,,,,,,,,,, +93,,,,,,,,,, +93,BOWL,SUM,0,0,0,0,2,2,0,9.1924538612 +93,CUP,SUM,0,0,0,0,40,54,30,35.8064169884 +93,SPOON,SUM,0,0,0,0,8,8,0,18.4042019844 +93,,SUM,0,0,0,0,50,64,30,63.403072834 +93,,,,,,,,,, +94,,,,,,,,,, +94,BOWL,SUM,0,0,0,0,40,16,0,25.1938471794 +94,CUP,SUM,0,0,0,0,4,7,11,14.4121940136 +94,SPOON,SUM,1,0,1,0,0,361,0,0 +94,,SUM,1,0,1,0,44,384,11,39.606041193 +94,,,,,,,,,, +95,,,,,,,,,, +95,BOWL,SUM,0,0,0,0,24,1,0,18.373552084 +95,CUP,SUM,0,0,0,0,0,2,27,16.5521068573 +95,SPOON,SUM,0,0,0,0,0,3,0,11.6442029476 +95,,SUM,0,0,0,0,24,6,27,46.5698618889 +95,,,,,,,,,, +96,,,,,,,,,, +96,BOWL,SUM,1,0,1,0,0,22,38,0 +96,CUP,SUM,0,0,0,0,0,2,8,9.1134240627 +96,SPOON,SUM,0,0,0,0,0,2,0,11.5625269413 +96,,SUM,1,0,1,0,0,26,46,20.675951004 +96,,,,,,,,,, +97,,,,,,,,,, +97,BOWL,SUM,0,0,0,0,0,2,0,9.0327119827 +97,CUP,SUM,0,0,0,0,18,6,8,16.0756151676 +97,SPOON,SUM,0,0,0,0,0,2,0,11.3403460979 +97,,SUM,0,0,0,0,18,10,8,36.4486732483 +97,,,,,,,,,, +98,,,,,,,,,, +98,BOWL,SUM,0,0,0,0,0,0,0,7.7469608784 +98,CUP,SUM,1,0,1,0,8,13,79,0 +98,SPOON,SUM,0,0,0,0,0,0,0,10.4791748524 +98,,SUM,1,0,1,0,8,13,79,18.2261357307 +98,,,,,,,,,, +99,,,,,,,,,, +99,BOWL,SUM,0,0,0,0,0,20,16,20.2070548534 +99,CUP,SUM,0,0,0,0,0,3,8,8.6429131031 +99,SPOON,SUM,0,0,0,0,2,3,12,18.0320868492 +99,,SUM,0,0,0,0,2,26,36,46.8820548058 +99,,,,,,,,,, +100,,,,,,,,,, +100,BOWL,SUM,1,0,1,0,0,51,30,0 +100,CUP,SUM,0,0,0,0,0,9,59,28.5886909962 +100,SPOON,SUM,0,0,0,0,2,2,0,12.2631449699 +100,,SUM,1,0,1,0,2,62,89,40.8518359661 +100,,,,,,,,,, +101,,,,,,,,,, +101,BOWL,SUM,0,0,0,0,0,6,0,8.8281478882 +101,CUP,SUM,0,0,0,0,16,8,29,24.9434189796 +101,SPOON,SUM,0,0,0,0,8,8,1,17.1204330921 +101,,SUM,0,0,0,0,24,22,30,50.8919999599 +101,,,,,,,,,, +102,,,,,,,,,, +102,BOWL,SUM,1,0,1,0,0,12,44,0 +102,CUP,SUM,0,0,0,0,0,3,19,12.2765171528 +102,SPOON,SUM,0,0,0,0,0,3,0,11.5999081135 +102,,SUM,1,0,1,0,0,18,63,23.8764252663 +102,,,,,,,,,, +103,,,,,,,,,, +103,BOWL,SUM,1,0,1,0,0,9,44,0 +103,CUP,SUM,0,0,0,0,0,2,8,8.0685369968 +103,SPOON,SUM,0,0,0,0,0,1,0,11.3350570202 +103,,SUM,1,0,1,0,0,12,52,19.403594017 +103,,,,,,,,,, +104,,,,,,,,,, +104,BOWL,SUM,0,0,0,0,0,5,28,18.596875906 +104,CUP,SUM,0,0,0,0,16,5,9,16.3705711365 +104,SPOON,SUM,0,0,0,0,0,1,0,11.3912630081 +104,,SUM,0,0,0,0,16,11,37,46.3587100506 +104,,,,,,,,,, +105,,,,,,,,,, +105,BOWL,SUM,0,0,0,0,8,7,1,13.6029539108 +105,CUP,SUM,0,0,0,0,0,7,47,21.2515428066 +105,SPOON,SUM,0,0,0,0,16,4,0,19.3931949139 +105,,SUM,0,0,0,0,24,18,48,54.2476916313 +105,,,,,,,,,, +106,,,,,,,,,, +106,BOWL,SUM,0,0,0,0,0,1,0,8.7409307957 +106,CUP,SUM,0,0,0,0,0,7,21,15.7069048882 +106,SPOON,SUM,0,0,0,0,0,4,4,13.6534910202 +106,,SUM,0,0,0,0,0,12,25,38.101326704 +106,,,,,,,,,, +107,,,,,,,,,, +107,BOWL,SUM,0,0,0,0,0,2,1,9.7461419106 +107,CUP,SUM,1,0,0,1,0,11,19,0 +107,SPOON,SUM,0,0,0,0,0,24,9,17.9580130577 +107,,SUM,1,0,0,1,0,37,29,27.7041549683 +107,,,,,,,,,, +108,,,,,,,,,, +108,BOWL,SUM,0,0,0,0,0,1,1,10.3801178932 +108,CUP,SUM,0,0,0,0,24,6,10,21.3853509426 +108,,,,,,,,,, +108,BOWL,SUM,0,0,0,0,4,10,0,10.7576980591 +108,CUP,SUM,0,0,0,0,8,14,59,30.788880825 +108,SPOON,SUM,0,0,0,0,0,1,0,10.881677866 +108,,SUM,0,0,0,0,12,25,59,52.4282567501 +108,,,,,,,,,, +109,,,,,,,,,, +109,BOWL,SUM,0,0,0,0,16,3,1,16.4841089249 +109,CUP,SUM,0,0,0,0,0,0,8,8.2346510887 +109,SPOON,SUM,1,1,0,0,40,12,0,0 +109,,SUM,1,1,0,0,56,15,9,24.7187600136 +109,,,,,,,,,, +110,,,,,,,,,, +110,BOWL,SUM,0,0,0,0,0,3,0,9.3827819824 +110,CUP,SUM,0,0,0,0,2,10,18,19.2549309731 +110,SPOON,SUM,0,0,0,0,8,5,0,16.1870911121 +110,,SUM,0,0,0,0,10,18,18,44.8248040676 +110,,,,,,,,,, +111,,,,,,,,,, +111,BOWL,SUM,1,1,0,0,48,9,0,0 +111,CUP,SUM,1,0,1,0,0,15,82,0 +111,SPOON,SUM,0,0,0,0,0,2,0,10.657889843 +111,,SUM,2,1,1,0,48,26,82,10.657889843 +111,,,,,,,,,, +112,,,,,,,,,, +112,BOWL,SUM,0,0,0,0,0,2,6,8.7813270092 +112,CUP,SUM,0,0,0,0,0,17,108,44.0257298946 +112,SPOON,SUM,0,0,0,0,0,1,0,11.0253348351 +112,,SUM,0,0,0,0,0,20,114,63.8323917389 +112,,,,,,,,,, +113,,,,,,,,,, +113,BOWL,SUM,0,0,0,0,16,1,0,16.831649065 +113,CUP,SUM,0,0,0,0,2,12,49,29.4508709908 +113,SPOON,SUM,0,0,0,0,0,1,0,10.8326590061 +113,,SUM,0,0,0,0,18,14,49,57.1151790619 +113,,,,,,,,,, +114,,,,,,,,,, +114,BOWL,SUM,0,0,0,0,0,10,1,10.4362258911 +114,CUP,SUM,0,0,0,0,10,4,8,13.4629919529 +114,SPOON,SUM,0,0,0,0,0,0,0,10.7700150013 +114,,SUM,0,0,0,0,10,14,9,34.6692328453 +114,,,,,,,,,, +115,,,,,,,,,, +115,BOWL,SUM,0,0,0,0,0,0,0,8.5033340454 +115,CUP,SUM,0,0,0,0,0,5,57,27.0560419559 +115,SPOON,SUM,1,0,1,0,12,341,0,0 +115,,SUM,1,0,1,0,12,346,57,35.5593760014 +115,,,,,,,,,, +116,,,,,,,,,, +116,BOWL,SUM,0,0,0,0,0,9,0,9.5714070797 +116,CUP,SUM,0,0,0,0,0,30,12,14.8506498337 +116,SPOON,SUM,0,0,0,0,2,6,12,17.9250040054 +116,,SUM,0,0,0,0,2,45,24,42.3470609188 +116,,,,,,,,,, +117,,,,,,,,,, +117,BOWL,SUM,0,0,0,0,0,3,2,8.4649291039 +117,CUP,SUM,0,0,0,0,0,7,15,13.3390471935 +117,SPOON,SUM,0,0,0,0,0,0,4,12.6347830296 +117,,SUM,0,0,0,0,0,10,21,34.4387593269 +117,,,,,,,,,, +118,,,,,,,,,, +118,BOWL,SUM,1,1,0,0,0,42,0,0 +118,CUP,SUM,0,0,0,0,0,2,8,9.0611100197 +118,SPOON,SUM,0,0,0,0,0,5,0,12.9496879578 +118,,SUM,1,1,0,0,0,49,8,22.0107979774 +118,,,,,,,,,, +119,,,,,,,,,, +119,BOWL,SUM,1,0,1,0,2,5,50,0 +119,CUP,SUM,0,0,0,0,0,4,9,9.1399791241 +119,SPOON,SUM,1,0,1,0,0,342,0,0 +119,,SUM,2,0,2,0,2,351,59,9.1399791241 +119,,,,,,,,,, +120,,,,,,,,,, +120,BOWL,SUM,0,0,0,0,0,2,1,9.1138739586 +120,CUP,SUM,0,0,0,0,8,7,20,16.5214138031 +120,SPOON,SUM,0,0,0,0,0,6,0,11.1972098351 +120,,SUM,0,0,0,0,8,15,21,36.8324975967 +120,,,,,,,,,, +121,,,,,,,,,, +121,BOWL,SUM,1,0,1,0,0,19,11,0 +121,CUP,SUM,0,0,0,0,0,6,8,9.2009871006 +121,SPOON,SUM,0,0,0,0,8,10,0,15.7024199963 +121,,SUM,1,0,1,0,8,35,19,24.9034070969 +121,,,,,,,,,, +122,,,,,,,,,, +122,BOWL,SUM,0,0,0,0,0,4,1,9.0722010136 +122,CUP,SUM,1,0,1,0,0,10,33,0 +122,SPOON,SUM,0,0,0,0,0,0,0,10.9185729027 +122,,SUM,1,0,1,0,0,14,34,19.9907739162 +122,,,,,,,,,, +123,,,,,,,,,, +123,BOWL,SUM,0,0,0,0,0,3,20,18.418582201 +123,CUP,SUM,0,0,0,0,0,9,48,23.9578020573 +123,SPOON,SUM,1,1,0,0,0,42,0,0 +123,,SUM,1,1,0,0,0,54,68,42.3763842583 +123,,,,,,,,,, +124,,,,,,,,,, +124,BOWL,SUM,1,0,1,0,0,18,44,0 +124,CUP,SUM,0,0,0,0,0,4,9,8.8620390892 +124,SPOON,SUM,0,0,0,0,8,5,0,15.1320450306 +124,,SUM,1,0,1,0,8,27,53,23.9940841198 +124,,,,,,,,,, +125,,,,,,,,,, +125,BOWL,SUM,0,0,0,0,0,3,6,11.5709300041 +125,CUP,SUM,0,0,0,0,16,6,20,20.8550000191 +125,SPOON,SUM,1,0,1,0,0,93,9,0 +125,,SUM,1,0,1,0,16,102,35,32.4259300232 +125,,,,,,,,,, +126,,,,,,,,,, +126,BOWL,SUM,0,0,0,0,0,8,0,9.8833200932 +126,CUP,SUM,0,0,0,0,0,11,87,43.4661738873 +126,SPOON,SUM,0,0,0,0,0,3,4,13.7089869976 +126,,SUM,0,0,0,0,0,22,91,67.058480978 +126,,,,,,,,,, +127,,,,,,,,,, +127,BOWL,SUM,1,0,1,0,0,41,44,0 +127,CUP,SUM,0,0,0,0,0,2,13,12.3954589367 +127,SPOON,SUM,0,0,0,0,0,2,0,11.9779598713 +127,,SUM,1,0,1,0,0,45,57,24.373418808 +127,,,,,,,,,, +128,,,,,,,,,, +128,BOWL,SUM,0,0,0,0,0,1,0,8.0316560268 +128,CUP,SUM,0,0,0,0,0,4,28,15.4799580574 +128,SPOON,SUM,1,0,1,0,8,342,0,0 +128,,SUM,1,0,1,0,8,347,28,23.5116140842 +128,,,,,,,,,, +129,,,,,,,,,, +129,BOWL,SUM,0,0,0,0,2,2,0,9.8502550125 +129,CUP,SUM,0,0,0,0,0,8,34,20.0191850662 +129,SPOON,SUM,0,0,0,0,0,3,0,10.942964077 +129,,SUM,0,0,0,0,2,13,34,40.8124041557 +129,,,,,,,,,, +130,,,,,,,,,, +130,BOWL,SUM,0,0,0,0,0,6,1,10.0340189934 +130,CUP,SUM,0,0,0,0,0,5,9,10.0756111145 +130,SPOON,SUM,0,0,0,0,0,2,0,11.1657710075 +130,,SUM,0,0,0,0,0,13,10,31.2754011154 +130,,,,,,,,,, +131,,,,,,,,,, +131,BOWL,SUM,0,0,0,0,2,3,0,15.1406280994 +131,CUP,SUM,1,0,1,0,0,13,101,0 +131,SPOON,SUM,0,0,0,0,16,7,12,24.9761459827 +131,,SUM,1,0,1,0,18,23,113,40.1167740822 +131,,,,,,,,,, +132,,,,,,,,,, +132,BOWL,SUM,1,0,1,0,0,310,6,0 +132,CUP,SUM,0,0,0,0,0,18,38,20.8264279366 +132,SPOON,SUM,1,1,0,0,0,42,0,0 +132,,SUM,2,1,1,0,0,370,44,20.8264279366 +132,,,,,,,,,, +133,,,,,,,,,, +133,BOWL,SUM,1,0,1,0,0,212,20,0 +133,CUP,SUM,0,0,0,0,8,7,8,12.9781098366 +133,SPOON,SUM,0,0,0,0,0,7,10,16.2347621918 +133,,SUM,1,0,1,0,8,226,38,29.2128720284 +133,,,,,,,,,, +134,,,,,,,,,, +134,BOWL,SUM,1,0,1,0,0,8,38,0 +134,CUP,SUM,0,0,0,0,0,2,8,8.2135541439 +134,SPOON,SUM,0,0,0,0,0,2,0,11.0819818974 +134,,SUM,1,0,1,0,0,12,46,19.2955360413 +134,,,,,,,,,, +135,,,,,,,,,, +135,BOWL,SUM,0,0,0,0,0,4,8,12.0925822258 +135,CUP,SUM,0,0,0,0,0,9,94,36.1058969498 +135,SPOON,SUM,0,0,0,0,8,8,8,21.1426010132 +135,,SUM,0,0,0,0,8,21,110,69.3410801888 +135,,,,,,,,,, +136,,,,,,,,,, +136,BOWL,SUM,1,0,0,1,8,7,19,0 +136,CUP,SUM,0,0,0,0,32,24,9,26.795814991 +136,SPOON,SUM,0,0,0,0,0,18,19,33.696449995 +136,,SUM,1,0,0,1,40,49,47,60.492264986 +136,,,,,,,,,, +137,,,,,,,,,, +137,BOWL,SUM,0,0,0,0,0,1,0,9.9491641521 +137,CUP,SUM,0,0,0,0,0,3,8,7.7106821537 +137,SPOON,SUM,1,0,1,0,8,19,11,0 +137,,SUM,1,0,1,0,8,23,19,17.6598463058 +137,,,,,,,,,, +138,,,,,,,,,, +138,BOWL,SUM,0,0,0,0,0,3,0,9.0378501415 +138,CUP,SUM,0,0,0,0,2,10,8,10.4377419949 +138,SPOON,SUM,0,0,0,0,8,4,0,16.6773099899 +138,,SUM,0,0,0,0,10,17,8,36.1529021263 +138,,,,,,,,,, +139,,,,,,,,,, +139,BOWL,SUM,0,0,0,0,0,4,0,9.5939559937 +139,CUP,SUM,0,0,0,0,0,2,40,20.5960559845 +139,SPOON,SUM,0,0,0,0,0,3,0,11.9254970551 +139,,SUM,0,0,0,0,0,9,40,42.1155090332 +139,,,,,,,,,, +140,,,,,,,,,, +140,BOWL,SUM,1,0,1,0,0,342,0,0 +140,CUP,SUM,0,0,0,0,0,3,8,9.4786419868 +140,SPOON,SUM,0,0,0,0,0,0,0,12.455739975 +140,,SUM,1,0,1,0,0,345,8,21.9343819618 +140,,,,,,,,,, +141,,,,,,,,,, +141,BOWL,SUM,0,0,0,0,8,11,0,17.7361288071 +141,CUP,SUM,0,0,0,0,8,5,8,12.6336388588 +141,SPOON,SUM,0,0,0,0,0,10,0,12.7326850891 +141,,SUM,0,0,0,0,16,26,8,43.102452755 +141,,,,,,,,,, +142,,,,,,,,,, +142,BOWL,SUM,1,0,1,0,2,36,10,0 +142,CUP,SUM,0,0,0,0,0,3,65,26.8453950882 +142,SPOON,SUM,0,0,0,0,0,1,0,11.6833760738 +142,,SUM,1,0,1,0,2,40,75,38.528771162 +142,,,,,,,,,, +143,,,,,,,,,, +143,BOWL,SUM,0,0,0,0,0,4,0,9.954406023 +143,CUP,SUM,1,0,0,1,0,13,19,0 +143,SPOON,SUM,1,0,1,0,0,341,0,0 +143,,SUM,2,0,1,1,0,358,19,9.954406023 +143,,,,,,,,,, +144,,,,,,,,,, +144,BOWL,SUM,0,0,0,0,0,2,10,13.8585529327 +144,CUP,SUM,0,0,0,0,0,14,69,29.1017830372 +144,SPOON,SUM,0,0,0,0,0,0,0,10.9305579662 +144,,SUM,0,0,0,0,0,16,79,53.8908939362 +144,,,,,,,,,, +145,,,,,,,,,, +145,BOWL,SUM,0,0,0,0,0,7,0,9.9729058743 +145,CUP,SUM,1,0,1,0,0,11,88,0 +145,SPOON,SUM,0,0,0,0,8,4,0,15.4520478249 +145,,SUM,1,0,1,0,8,22,88,25.4249536991 +145,,,,,,,,,, +146,,,,,,,,,, +146,BOWL,SUM,1,0,1,0,2,312,4,0 +146,CUP,SUM,1,0,0,1,0,10,29,0 +146,SPOON,SUM,0,0,0,0,0,3,0,11.6363310814 +146,,SUM,2,0,1,1,2,325,33,11.6363310814 +146,,,,,,,,,, +147,,,,,,,,,, +147,BOWL,SUM,0,0,0,0,0,0,0,8.9174051285 +147,CUP,SUM,0,0,0,0,0,21,129,45.5053060055 +147,SPOON,SUM,0,0,0,0,0,1,0,11.7565159798 +147,,SUM,0,0,0,0,0,22,129,66.1792271137 +147,,,,,,,,,, +148,,,,,,,,,, +148,BOWL,SUM,0,0,0,0,0,3,0,8.7557418346 +148,CUP,SUM,0,0,0,0,8,4,23,23.3109471798 +148,SPOON,SUM,1,0,1,0,0,246,5,0 +148,,SUM,1,0,1,0,8,253,28,32.0666890144 +148,,,,,,,,,, +149,,,,,,,,,, +149,BOWL,SUM,0,0,0,0,0,1,1,9.2679650784 +149,CUP,SUM,0,0,0,0,16,5,8,16.1122260094 +149,SPOON,SUM,1,1,0,0,0,42,0,0 +149,,SUM,1,1,0,0,16,48,9,25.3801910877 +149,,,,,,,,,, +150,,,,,,,,,, +150,BOWL,SUM,0,0,0,0,0,5,0,8.4575488567 +150,CUP,SUM,0,0,0,0,0,3,8,7.8124678135 +150,SPOON,SUM,1,0,1,0,8,53,40,0 +150,,SUM,1,0,1,0,8,61,48,16.2700166702 +150,,,,,,,,,, +151,,,,,,,,,, +151,BOWL,SUM,1,0,1,0,0,12,11,0 +151,CUP,SUM,1,0,1,0,0,13,39,0 +151,SPOON,SUM,0,0,0,0,0,5,0,11.354501009 +151,,SUM,2,0,2,0,0,30,50,11.354501009 +151,,,,,,,,,, +152,,,,,,,,,, +152,BOWL,SUM,1,1,0,0,0,43,0,0 +152,CUP,SUM,1,1,0,0,0,42,0,0 +152,SPOON,SUM,0,0,0,0,24,5,2,23.744063139 +152,,SUM,2,2,0,0,24,90,2,23.744063139 +152,,,,,,,,,, +153,,,,,,,,,, +153,BOWL,SUM,0,0,0,0,0,6,1,9.4277830124 +153,CUP,SUM,1,0,1,0,0,15,33,0 +153,SPOON,SUM,0,0,0,0,24,2,0,21.9531230927 +153,,SUM,1,0,1,0,24,23,34,31.380906105 +153,,,,,,,,,, +154,,,,,,,,,, +154,BOWL,SUM,1,0,1,0,0,38,40,0 +154,CUP,SUM,0,0,0,0,0,2,8,7.8469769955 +154,SPOON,SUM,0,0,0,0,0,0,0,11.0993199348 +154,,SUM,1,0,1,0,0,40,48,18.9462969303 +154,,,,,,,,,, +155,,,,,,,,,, +155,BOWL,SUM,1,0,1,0,8,17,11,0 +155,CUP,SUM,0,0,0,0,0,8,8,8.7488908768 +155,SPOON,SUM,0,0,0,0,8,26,7,27.9686660767 +155,,SUM,1,0,1,0,16,51,26,36.7175569534 +155,,,,,,,,,, +156,,,,,,,,,, +156,BOWL,SUM,0,0,0,0,0,6,17,14.7358009815 +156,CUP,SUM,0,0,0,0,0,5,8,8.2655608654 +156,SPOON,SUM,0,0,0,0,22,5,0,23.0830249786 +156,,SUM,0,0,0,0,22,16,25,46.0843868256 +156,,,,,,,,,, +157,,,,,,,,,, +157,BOWL,SUM,0,0,0,0,0,2,1,11.0366919041 +157,CUP,SUM,0,0,0,0,0,5,8,8.8306121826 +157,SPOON,SUM,0,0,0,0,0,1,11,16.6490578651 +157,,SUM,0,0,0,0,0,8,20,36.5163619518 +157,,,,,,,,,, +158,,,,,,,,,, +158,BOWL,SUM,0,0,0,0,0,2,0,8.6347930431 +158,CUP,SUM,1,0,1,0,0,9,82,0 +158,SPOON,SUM,0,0,0,0,8,0,4,16.6217780113 +158,,SUM,1,0,1,0,8,11,86,25.2565710545 +158,,,,,,,,,, +159,,,,,,,,,, +159,BOWL,SUM,0,0,0,0,0,39,0,12.9550199509 +159,CUP,SUM,1,0,1,0,0,30,78,0 +159,SPOON,SUM,0,0,0,0,24,7,0,21.7975959778 +159,,SUM,1,0,1,0,24,76,78,34.7526159286 +159,,,,,,,,,, +160,,,,,,,,,, +160,BOWL,SUM,0,0,0,0,0,2,0,8.6811981201 +160,CUP,SUM,0,0,0,0,0,13,19,14.9480919838 +160,SPOON,SUM,0,0,0,0,0,5,0,11.6102280617 +160,,SUM,0,0,0,0,0,20,19,35.2395181656 +160,,,,,,,,,, +161,,,,,,,,,, +161,BOWL,SUM,0,0,0,0,8,16,1,14.205275774 +161,CUP,SUM,1,0,1,0,0,32,55,0 +161,SPOON,SUM,0,0,0,0,0,4,0,11.4811360836 +161,,SUM,1,0,1,0,8,52,56,25.6864118576 +161,,,,,,,,,, +162,,,,,,,,,, +162,BOWL,SUM,0,0,0,0,0,3,0,8.6149880886 +162,CUP,SUM,0,0,0,0,0,18,24,17.0443739891 +162,SPOON,SUM,0,0,0,0,16,2,0,18.350383997 +162,,SUM,0,0,0,0,16,23,24,44.0097460747 +162,,,,,,,,,, +163,,,,,,,,,, +163,BOWL,SUM,0,0,0,0,0,1,5,10.0289349556 +163,CUP,SUM,0,0,0,0,0,6,15,12.0761761665 +163,SPOON,SUM,1,1,0,0,0,42,0,0 +163,,SUM,1,1,0,0,0,49,20,22.1051111221 +163,,,,,,,,,, +164,,,,,,,,,, +164,BOWL,SUM,0,0,0,0,0,4,35,24.4752209187 +164,CUP,SUM,0,0,0,0,0,6,17,11.9829611778 +164,SPOON,SUM,0,0,0,0,0,0,0,10.9920251369 +164,,SUM,0,0,0,0,0,10,52,47.4502072334 +164,,,,,,,,,, +165,,,,,,,,,, +165,BOWL,SUM,0,0,0,0,0,1,7,14.0200760365 +165,CUP,SUM,1,0,1,0,0,12,44,0 +165,SPOON,SUM,0,0,0,0,0,3,6,13.6580021381 +165,,SUM,1,0,1,0,0,16,57,27.6780781746 +165,,,,,,,,,, +166,,,,,,,,,, +166,BOWL,SUM,0,0,0,0,8,35,13,21.7541248798 +166,CUP,SUM,0,0,0,0,8,3,28,20.1614391804 +166,SPOON,SUM,1,0,1,0,0,12,23,0 +166,,SUM,1,0,1,0,16,50,64,41.9155640602 +166,,,,,,,,,, +167,,,,,,,,,, +167,BOWL,SUM,0,0,0,0,12,9,6,23.2574300766 +167,CUP,SUM,1,0,0,1,0,17,25,0 +167,SPOON,SUM,0,0,0,0,0,2,0,11.5566151142 +167,,SUM,1,0,0,1,12,28,31,34.8140451908 +167,,,,,,,,,, +168,,,,,,,,,, +168,BOWL,SUM,0,0,0,0,0,5,8,11.9835910797 +168,CUP,SUM,0,0,0,0,2,30,96,42.4896190166 +168,SPOON,SUM,1,0,0,1,0,6,17,0 +168,,SUM,1,0,0,1,2,41,121,54.4732100964 +168,,,,,,,,,, +169,,,,,,,,,, +169,BOWL,SUM,0,0,0,0,8,3,1,14.0096969604 +169,CUP,SUM,1,0,1,0,34,18,90,0 +169,SPOON,SUM,0,0,0,0,0,0,0,11.0295181274 +169,,SUM,1,0,1,0,42,21,91,25.0392150879 +169,,,,,,,,,, +170,,,,,,,,,, +170,BOWL,SUM,1,0,1,0,8,314,4,0 +170,CUP,SUM,0,0,0,0,0,4,69,29.6658730507 +170,SPOON,SUM,0,0,0,0,2,4,4,15.3396978378 +170,,SUM,1,0,1,0,10,322,77,45.0055708885 +170,,,,,,,,,, +171,,,,,,,,,, +171,BOWL,SUM,0,0,0,0,0,2,24,20.7709648609 +171,CUP,SUM,0,0,0,0,0,4,8,8.7038669586 +171,SPOON,SUM,0,0,0,0,24,3,4,23.8422141075 +171,,SUM,0,0,0,0,24,9,36,53.317045927 +171,,,,,,,,,, +172,,,,,,,,,, +172,BOWL,SUM,0,0,0,0,0,1,0,8.9295430183 +172,CUP,SUM,0,0,0,0,0,4,33,18.9539880753 +172,SPOON,SUM,1,0,1,0,0,341,0,0 +172,,SUM,1,0,1,0,0,346,33,27.8835310936 +172,,,,,,,,,, +173,,,,,,,,,, +173,BOWL,SUM,0,0,0,0,0,5,1,9.3530399799 +173,CUP,SUM,0,0,0,0,0,4,16,16.4590559006 +173,SPOON,SUM,1,0,1,0,16,160,6,0 +173,,SUM,1,0,1,0,16,169,23,25.8120958805 +173,,,,,,,,,, +174,,,,,,,,,, +174,BOWL,SUM,0,0,0,0,32,3,0,25.162209034 +174,CUP,SUM,0,0,0,0,0,11,13,12.3132190704 +174,SPOON,SUM,1,0,1,0,8,32,44,0 +174,,SUM,1,0,1,0,40,46,57,37.4754281044 +174,,,,,,,,,, +175,,,,,,,,,, +175,BOWL,SUM,1,0,1,0,8,17,26,0 +175,CUP,SUM,0,0,0,0,0,4,9,9.0225539207 +175,SPOON,SUM,0,0,0,0,0,1,0,11.7374610901 +175,,SUM,1,0,1,0,8,22,35,20.7600150108 +175,,,,,,,,,, +176,,,,,,,,,, +176,BOWL,SUM,0,0,0,0,0,2,0,8.6301648617 +176,CUP,SUM,0,0,0,0,0,2,23,13.4372601509 +176,SPOON,SUM,0,0,0,0,0,3,0,11.3744459152 +176,,SUM,0,0,0,0,0,7,23,33.4418709278 +176,,,,,,,,,, +177,,,,,,,,,, +177,BOWL,SUM,0,0,0,0,0,1,0,9.6303358078 +177,CUP,SUM,0,0,0,0,4,1,18,13.4696350098 +177,SPOON,SUM,0,0,0,0,32,13,0,24.945982933 +177,,SUM,0,0,0,0,36,15,18,48.0459537506 +177,,,,,,,,,, +178,,,,,,,,,, +178,BOWL,SUM,0,0,0,0,0,8,34,22.274171114 +178,CUP,SUM,0,0,0,0,8,31,8,14.3191080093 +178,SPOON,SUM,0,0,0,0,0,1,0,11.0167181492 +178,,SUM,0,0,0,0,8,40,42,47.6099972725 +178,,,,,,,,,, +179,,,,,,,,,, +179,BOWL,SUM,0,0,0,0,0,0,0,8.9029471874 +179,CUP,SUM,1,0,1,0,0,10,11,0 +179,SPOON,SUM,0,0,0,0,0,1,0,11.6876502037 +179,,SUM,1,0,1,0,0,11,11,20.5905973911 +179,,,,,,,,,, +180,,,,,,,,,, +180,BOWL,SUM,0,0,0,0,16,4,13,20.5839710236 +180,CUP,SUM,1,0,1,0,0,189,90,0 +180,SPOON,SUM,0,0,0,0,0,3,4,12.9913170338 +180,,SUM,1,0,1,0,16,196,107,33.5752880573 +180,,,,,,,,,, +181,,,,,,,,,, +181,BOWL,SUM,0,0,0,0,0,2,4,14.7504971027 +181,CUP,SUM,0,0,0,0,0,1,8,7.8154909611 +181,SPOON,SUM,0,0,0,0,8,2,4,16.3284499645 +181,,SUM,0,0,0,0,8,5,16,38.8944380283 +181,,,,,,,,,, +182,,,,,,,,,, +182,BOWL,SUM,0,0,0,0,0,2,1,10.2859611511 +182,CUP,SUM,0,0,0,0,0,1,8,7.9186599255 +182,SPOON,SUM,0,0,0,0,0,12,6,16.406744957 +182,,SUM,0,0,0,0,0,15,15,34.6113660336 +182,,,,,,,,,, +183,,,,,,,,,, +183,BOWL,SUM,0,0,0,0,4,26,16,18.0001749992 +183,CUP,SUM,0,0,0,0,2,3,8,9.6655068398 +183,SPOON,SUM,0,0,0,0,8,4,0,15.3916289806 +183,,SUM,0,0,0,0,14,33,24,43.0573108196 +183,,,,,,,,,, +184,,,,,,,,,, +184,BOWL,SUM,1,0,1,0,0,20,34,0 +184,CUP,SUM,1,0,1,0,0,4,71,0 +184,SPOON,SUM,0,0,0,0,0,3,0,12.0019099712 +184,,SUM,2,0,2,0,0,27,105,12.0019099712 +184,,,,,,,,,, +185,,,,,,,,,, +185,BOWL,SUM,1,1,0,0,0,42,0,0 +185,CUP,SUM,0,0,0,0,0,18,8,10.152641058 +185,SPOON,SUM,0,0,0,0,24,12,0,21.2039091587 +185,,SUM,1,1,0,0,24,72,8,31.3565502167 +185,,,,,,,,,, +186,,,,,,,,,, +186,BOWL,SUM,0,0,0,0,0,9,12,14.8376431465 +186,CUP,SUM,0,0,0,0,0,3,17,13.4184381962 +186,SPOON,SUM,0,0,0,0,0,0,0,11.7017118931 +186,,SUM,0,0,0,0,0,12,29,39.9577932358 +186,,,,,,,,,, +187,,,,,,,,,, +187,BOWL,SUM,0,0,0,0,0,0,0,9.7001399994 +187,CUP,SUM,0,0,0,0,16,4,9,17.4645328522 +187,SPOON,SUM,0,0,0,0,2,3,0,12.2501251698 +187,,SUM,0,0,0,0,18,7,9,39.4147980213 +187,,,,,,,,,, +188,,,,,,,,,, +188,BOWL,SUM,1,1,0,0,0,72,0,0 +188,CUP,SUM,0,0,0,0,24,111,8,27.7974998951 +188,SPOON,SUM,0,0,0,0,0,22,20,20.8323979378 +188,,SUM,1,1,0,0,24,205,28,48.6298978329 +188,,,,,,,,,, +189,,,,,,,,,, +189,BOWL,SUM,0,0,0,0,0,3,0,8.5945119858 +189,CUP,SUM,0,0,0,0,24,3,8,18.4282598495 +189,SPOON,SUM,0,0,0,0,0,1,8,15.73686409 +189,,SUM,0,0,0,0,24,7,16,42.7596359253 +189,,,,,,,,,, +190,,,,,,,,,, +190,BOWL,SUM,0,0,0,0,2,0,0,10.1482059956 +190,CUP,SUM,0,0,0,0,24,4,18,22.8122620583 +190,SPOON,SUM,0,0,0,0,8,2,4,16.3566961288 +190,,SUM,0,0,0,0,34,6,22,49.3171641827 +190,,,,,,,,,, +191,,,,,,,,,, +191,BOWL,SUM,0,0,0,0,0,3,0,10.7414991856 +191,CUP,SUM,0,0,0,0,0,2,9,9.4464211464 +191,SPOON,SUM,0,0,0,0,0,7,0,11.0649299622 +191,,SUM,0,0,0,0,0,12,9,31.2528502941 +191,,,,,,,,,, +192,,,,,,,,,, +192,BOWL,SUM,0,0,0,0,0,1,0,7.8895831108 +192,CUP,SUM,0,0,0,0,0,6,44,28.6548631191 +192,SPOON,SUM,0,0,0,0,8,0,0,14.8078248501 +192,,SUM,0,0,0,0,8,7,44,51.35227108 +192,,,,,,,,,, +193,,,,,,,,,, +193,BOWL,SUM,0,0,0,0,2,3,9,16.1422801018 +193,CUP,SUM,0,0,0,0,24,7,8,19.4897119999 +193,SPOON,SUM,0,0,0,0,8,8,8,17.3715538979 +193,,SUM,0,0,0,0,34,18,25,53.0035459995 +193,,,,,,,,,, +194,,,,,,,,,, +194,BOWL,SUM,0,0,0,0,8,3,0,11.8641891479 +194,CUP,SUM,0,0,0,0,8,1,12,15.9840319157 +194,SPOON,SUM,0,0,0,0,0,4,0,11.1842370033 +194,,SUM,0,0,0,0,16,8,12,39.0324580669 +194,,,,,,,,,, +195,,,,,,,,,, +195,BOWL,SUM,0,0,0,0,0,36,35,25.696696043 +195,CUP,SUM,0,0,0,0,0,7,49,23.7543320656 +195,SPOON,SUM,0,0,0,0,0,1,0,11.3550732136 +195,,SUM,0,0,0,0,0,44,84,60.8061013222 +195,,,,,,,,,, +196,,,,,,,,,, +196,BOWL,SUM,0,0,0,0,8,7,29,24.3789548874 +196,CUP,SUM,0,0,0,0,0,5,12,11.5825619698 +196,SPOON,SUM,0,0,0,0,24,3,7,24.6045107841 +196,,SUM,0,0,0,0,32,15,48,60.5660276413 +196,,,,,,,,,, +197,,,,,,,,,, +197,BOWL,SUM,1,0,1,0,8,7,26,0 +197,CUP,SUM,0,0,0,0,0,6,10,10.5314278603 +197,SPOON,SUM,0,0,0,0,16,1,0,17.8695468903 +197,,SUM,1,0,1,0,24,14,36,28.4009747505 +197,,,,,,,,,, +198,,,,,,,,,, +198,BOWL,SUM,0,0,0,0,0,1,0,8.0187740326 +198,CUP,SUM,0,0,0,0,0,3,16,13.2952549458 +198,SPOON,SUM,0,0,0,0,0,22,2,14.4820871353 +198,,SUM,0,0,0,0,0,26,18,35.7961161137 +198,,,,,,,,,, +199,,,,,,,,,, +199,BOWL,SUM,0,0,0,0,8,9,34,27.9556062222 +199,CUP,SUM,1,0,0,1,0,11,31,0 +199,SPOON,SUM,0,0,0,0,0,19,1,14.6248419285 +199,,SUM,1,0,0,1,8,39,66,42.5804481506 +199,,,,,,,,,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/heur_boxy_orig.csv b/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/heur_boxy_orig.csv new file mode 100644 index 0000000000..5cb237b941 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/heur_boxy_orig.csv @@ -0,0 +1,1203 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,2,9,9,16.9717421532 +0,CUP,SUM,0,0,0,0,0,0,9,9.3507969379 +0,SPOON,SUM,0,0,0,0,0,2,0,11.3196239471 +0,,SUM,0,0,0,0,2,11,18,37.6421630383 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,14,3,2,20.4612090588 +1,CUP,SUM,0,0,0,0,0,2,37,19.2070088387 +1,SPOON,SUM,0,0,0,0,0,1,0,12.7714338303 +1,,SUM,0,0,0,0,14,6,39,52.4396517277 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,0,1,0,7.7722299099 +2,CUP,SUM,0,0,0,0,0,6,9,9.5963861942 +2,SPOON,SUM,0,0,0,0,0,16,0,14.573086977 +2,,SUM,0,0,0,0,0,23,9,31.9417030811 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,0,3,0,8.2646989822 +3,CUP,SUM,0,0,0,0,0,1,27,13.6423377991 +3,SPOON,SUM,0,0,0,0,0,1,0,11.5122010708 +3,,SUM,0,0,0,0,0,5,27,33.4192378521 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,8,10,34,23.7731590271 +4,CUP,SUM,0,0,0,0,2,0,9,10.6240410805 +4,SPOON,SUM,0,0,0,0,0,5,6,14.2518231869 +4,,SUM,0,0,0,0,10,15,49,48.6490232944 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,8,6,9,16.1566970348 +5,CUP,SUM,0,0,0,0,0,3,21,12.8821470737 +5,SPOON,SUM,0,0,0,0,8,3,0,15.3631789684 +5,,SUM,0,0,0,0,16,12,30,44.402023077 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,1,0,1,0,0,8,44,0 +6,CUP,SUM,0,0,0,0,8,4,28,19.1580660343 +6,SPOON,SUM,0,0,0,0,8,1,0,16.1478590965 +6,,SUM,1,0,1,0,16,13,72,35.3059251308 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,0,1,0,9.707310915 +7,CUP,SUM,0,0,0,0,2,2,8,9.6947798729 +7,SPOON,SUM,0,0,0,0,0,4,0,13.0249509811 +7,,SUM,0,0,0,0,2,7,8,32.427041769 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,16,2,1,15.8578429222 +8,CUP,SUM,1,0,1,0,16,9,51,0 +8,SPOON,SUM,0,0,0,0,0,0,0,10.6815829277 +8,,SUM,1,0,1,0,32,11,52,26.5394258499 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,8,5,1,16.6525259018 +9,CUP,SUM,1,0,1,0,0,8,77,0 +9,SPOON,SUM,0,0,0,0,2,8,5,17.160061121 +9,,SUM,1,0,1,0,10,21,83,33.8125870228 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,1,4,11.2783408165 +10,CUP,SUM,0,0,0,0,2,2,9,10.6009430885 +10,SPOON,SUM,1,0,1,0,8,11,46,0 +10,,SUM,1,0,1,0,10,14,59,21.879283905 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,8,1,0,12.5772099495 +11,CUP,SUM,0,0,0,0,16,13,21,26.2377009392 +11,SPOON,SUM,0,0,0,0,2,4,4,14.1772770882 +11,,SUM,0,0,0,0,26,18,25,52.9921879768 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,2,2,0,8.9823708534 +12,CUP,SUM,0,0,0,0,0,0,8,8.8555550575 +12,SPOON,SUM,0,0,0,0,0,2,0,11.5703251362 +12,,SUM,0,0,0,0,2,4,8,29.4082510471 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,0,4,12,14.0004370213 +13,CUP,SUM,0,0,0,0,0,1,18,11.6863739491 +13,SPOON,SUM,0,0,0,0,0,3,13,26.2072279453 +13,,SUM,0,0,0,0,0,8,43,51.8940389156 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,8,7,0,20.3477108479 +14,CUP,SUM,0,0,0,0,0,4,8,9.0264968872 +14,SPOON,SUM,0,0,0,0,0,0,0,11.8731069565 +14,,SUM,0,0,0,0,8,11,8,41.2473146915 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,16,0,0,17.3071060181 +15,CUP,SUM,1,0,1,0,0,22,135,0 +15,SPOON,SUM,0,0,0,0,0,3,4,11.158069849 +15,,SUM,1,0,1,0,16,25,139,28.4651758671 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,2,1,10.1254820824 +16,CUP,SUM,0,0,0,0,0,2,8,8.728292942 +16,SPOON,SUM,0,0,0,0,0,3,0,11.8376059532 +16,,SUM,0,0,0,0,0,7,9,30.6913809776 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,0,21,0,10.954241991 +17,CUP,SUM,1,0,1,0,0,17,119,0 +17,SPOON,SUM,0,0,0,0,8,1,0,18.6359820366 +17,,SUM,1,0,1,0,8,39,119,29.5902240276 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,2,0,0,9.6949870586 +18,CUP,SUM,0,0,0,0,16,8,23,27.3437838554 +18,SPOON,SUM,0,0,0,0,0,3,0,11.921710968 +18,,SUM,0,0,0,0,18,11,23,48.9604818821 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,2,16,15.3963210583 +19,CUP,SUM,0,0,0,0,8,3,8,13.2041780949 +19,SPOON,SUM,0,0,0,0,8,8,0,16.7728919983 +19,,SUM,0,0,0,0,16,13,24,45.3733911514 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,8,17,4,14.6609909534 +20,CUP,SUM,0,0,0,0,0,0,8,8.3860759735 +20,SPOON,SUM,0,0,0,0,0,2,2,12.1838591099 +20,,SUM,0,0,0,0,8,19,14,35.2309260368 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,5,0,9.230670929 +21,CUP,SUM,0,0,0,0,0,1,9,9.5877718925 +21,SPOON,SUM,0,0,0,0,0,1,0,12.4756240845 +21,,SUM,0,0,0,0,0,7,9,31.294066906 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,1,0,1,0,0,10,42,0 +22,CUP,SUM,0,0,0,0,0,3,28,20.4541969299 +22,SPOON,SUM,0,0,0,0,0,11,28,31.9305028915 +22,,SUM,1,0,1,0,0,24,98,52.3846998215 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,2,8,11.4138410091 +23,CUP,SUM,0,0,0,0,0,4,8,8.707971096 +23,SPOON,SUM,0,0,0,0,0,7,0,12.1867408752 +23,,SUM,0,0,0,0,0,13,16,32.3085529804 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,8,21,11,20.2077829838 +24,CUP,SUM,1,0,1,0,0,8,53,0 +24,SPOON,SUM,0,0,0,0,0,11,4,15.0933139324 +24,,SUM,1,0,1,0,8,40,68,35.3010969162 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,0,1,1,10.5093741417 +25,CUP,SUM,0,0,0,0,0,5,20,13.6296570301 +25,SPOON,SUM,0,0,0,0,0,3,0,12.8190040588 +25,,SUM,0,0,0,0,0,9,21,36.9580352306 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,0,2,0,8.7630689144 +26,CUP,SUM,0,0,0,0,0,6,67,29.5159230232 +26,SPOON,SUM,0,0,0,0,2,5,0,14.0800030231 +26,,SUM,0,0,0,0,2,13,67,52.3589949608 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,0,12,15,15.7760391235 +27,CUP,SUM,1,0,1,0,4,7,63,0 +27,SPOON,SUM,0,0,0,0,0,1,0,11.1880750656 +27,,SUM,1,0,1,0,4,20,78,26.9641141891 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,8,0,0,12.2287199497 +28,CUP,SUM,0,0,0,0,2,5,14,15.2370860577 +28,SPOON,SUM,0,0,0,0,0,1,0,11.9742369652 +28,,SUM,0,0,0,0,10,6,14,39.4400429726 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,0,1,12,12.2445600033 +29,CUP,SUM,0,0,0,0,2,3,8,9.5869560242 +29,SPOON,SUM,0,0,0,0,0,1,0,11.8435199261 +29,,SUM,0,0,0,0,2,5,20,33.6750359535 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,8,2,0,13.2759017944 +30,CUP,SUM,1,0,1,0,8,9,78,0 +30,SPOON,SUM,0,0,0,0,0,0,0,11.5793261528 +30,,SUM,1,0,1,0,16,11,78,24.8552279472 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,0,5,1,10.5650980473 +31,CUP,SUM,0,0,0,0,56,7,13,39.4731760025 +31,SPOON,SUM,0,0,0,0,0,6,5,15.2004930973 +31,,SUM,0,0,0,0,56,18,19,65.2387671471 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,0,6,4,9.5678398609 +32,CUP,SUM,0,0,0,0,0,4,17,13.4210259914 +32,SPOON,SUM,0,0,0,0,0,10,19,21.6733129025 +32,,SUM,0,0,0,0,0,20,40,44.6621787548 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,7,1,11.9677848816 +33,CUP,SUM,0,0,0,0,0,0,8,8.0657060146 +33,SPOON,SUM,0,0,0,0,0,3,0,12.6144011021 +33,,SUM,0,0,0,0,0,10,9,32.6478919983 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,0,22,12,17.4163069725 +34,CUP,SUM,0,0,0,0,0,16,20,15.4738252163 +34,SPOON,SUM,0,0,0,0,2,9,0,13.774533987 +34,,SUM,0,0,0,0,2,47,32,46.6646661758 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,0,4,12,13.4264099598 +35,CUP,SUM,0,0,0,0,0,7,42,20.0566101074 +35,SPOON,SUM,0,0,0,0,0,1,0,11.6704871655 +35,,SUM,0,0,0,0,0,12,54,45.1535072327 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,18,5,28,27.5118420124 +36,CUP,SUM,0,0,0,0,0,9,8,9.7879698277 +36,SPOON,SUM,0,0,0,0,0,7,0,12.2516438961 +36,,SUM,0,0,0,0,18,21,36,49.5514557362 +36,,,,,,,,,, +37,,,,,,,,,, +37,BOWL,SUM,0,0,0,0,0,5,14,15.6454558372 +37,CUP,SUM,0,0,0,0,0,14,8,10.7782480717 +37,SPOON,SUM,1,0,1,0,0,14,11,0 +37,,SUM,1,0,1,0,0,33,33,26.4237039089 +37,,,,,,,,,, +38,,,,,,,,,, +38,BOWL,SUM,0,0,0,0,0,4,5,14.1167960167 +38,CUP,SUM,0,0,0,0,4,1,13,12.5199439526 +38,SPOON,SUM,0,0,0,0,16,13,4,36.6234500408 +38,,SUM,0,0,0,0,20,18,22,63.2601900101 +38,,,,,,,,,, +39,,,,,,,,,, +39,BOWL,SUM,0,0,0,0,0,6,0,10.3418669701 +39,CUP,SUM,0,0,0,0,24,16,34,32.7770171165 +39,SPOON,SUM,0,0,0,0,0,3,2,16.1665430069 +39,,SUM,0,0,0,0,24,25,36,59.2854270935 +39,,,,,,,,,, +40,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,2,9,9,16.9705109596 +40,CUP,SUM,0,0,0,0,0,0,9,9.6154749393 +40,SPOON,SUM,0,0,0,0,0,2,0,11.5821318626 +40,,SUM,0,0,0,0,2,11,18,38.1681177616 +40,,,,,,,,,, +41,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,14,3,2,20.8754580021 +41,CUP,SUM,0,0,0,0,0,2,37,19.9478378296 +41,SPOON,SUM,0,0,0,0,0,1,0,12.5008699894 +41,,SUM,0,0,0,0,14,6,39,53.3241658211 +41,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,0,1,0,7.5073490143 +42,CUP,SUM,0,0,0,0,0,6,9,9.8881540298 +42,SPOON,SUM,0,0,0,0,0,16,0,14.7964019775 +42,,SUM,0,0,0,0,0,23,9,32.1919050217 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,0,3,0,7.903952837 +43,CUP,SUM,0,0,0,0,0,1,27,13.9570481777 +43,SPOON,SUM,0,0,0,0,0,1,0,11.8767831326 +43,,SUM,0,0,0,0,0,5,27,33.7377841473 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,8,10,34,24.576764822 +44,CUP,SUM,0,0,0,0,2,0,9,11.0100951195 +44,SPOON,SUM,0,0,0,0,0,5,6,14.1839520931 +44,,SUM,0,0,0,0,10,15,49,49.7708120346 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,8,6,9,16.3589339256 +45,CUP,SUM,0,0,0,0,0,3,21,12.9235911369 +45,SPOON,SUM,0,0,0,0,8,3,0,15.5897431374 +45,,SUM,0,0,0,0,16,12,30,44.8722681999 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,1,0,1,0,0,8,44,0 +46,CUP,SUM,0,0,0,0,8,4,28,19.3622040749 +46,SPOON,SUM,0,0,0,0,8,1,0,16.2506937981 +46,,SUM,1,0,1,0,16,13,72,35.6128978729 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,0,0,0,0,0,1,0,9.3366611004 +47,CUP,SUM,0,0,0,0,2,2,8,9.9086480141 +47,SPOON,SUM,0,0,0,0,0,4,0,13.2733139992 +47,,SUM,0,0,0,0,2,7,8,32.5186231136 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,16,2,1,15.4800958633 +48,CUP,SUM,1,0,1,0,16,9,51,0 +48,SPOON,SUM,0,0,0,0,0,0,0,10.7432470322 +48,,SUM,1,0,1,0,32,11,52,26.2233428955 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,8,5,1,15.9619131088 +49,CUP,SUM,1,0,1,0,0,8,77,0 +49,SPOON,SUM,0,0,0,0,2,8,5,16.8286688328 +49,,SUM,1,0,1,0,10,21,83,32.7905819416 +49,,,,,,,,,, +50,,,,,,,,,, +50,BOWL,SUM,0,0,0,0,0,1,4,11.3818280697 +50,CUP,SUM,0,0,0,0,2,2,9,10.2579791546 +50,SPOON,SUM,1,0,1,0,8,11,46,0 +50,,SUM,1,0,1,0,10,14,59,21.6398072243 +50,,,,,,,,,, +51,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,8,1,0,12.1865301132 +51,CUP,SUM,0,0,0,0,16,13,21,26.327188015 +51,SPOON,SUM,0,0,0,0,2,4,4,14.2243080139 +51,,SUM,0,0,0,0,26,18,25,52.7380261421 +51,,,,,,,,,, +52,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,2,2,0,8.9843690395 +52,CUP,SUM,0,0,0,0,0,0,8,8.7611358166 +52,SPOON,SUM,0,0,0,0,0,2,0,12.0582890511 +52,,SUM,0,0,0,0,2,4,8,29.8037939072 +52,,,,,,,,,, +53,,,,,,,,,, +53,BOWL,SUM,0,0,0,0,0,4,12,13.9443809986 +53,CUP,SUM,0,0,0,0,0,1,18,11.4342019558 +53,SPOON,SUM,0,0,0,0,0,3,13,26.958147049 +53,,SUM,0,0,0,0,0,8,43,52.3367300034 +53,,,,,,,,,, +54,,,,,,,,,, +54,BOWL,SUM,0,0,0,0,8,7,0,20.0399370193 +54,CUP,SUM,0,0,0,0,0,4,8,9.0392341614 +54,SPOON,SUM,0,0,0,0,0,0,0,11.9590539932 +54,,SUM,0,0,0,0,8,11,8,41.038225174 +54,,,,,,,,,, +55,,,,,,,,,, +55,BOWL,SUM,0,0,0,0,16,0,0,17.2234749794 +55,CUP,SUM,1,0,1,0,0,22,135,0 +55,SPOON,SUM,0,0,0,0,0,3,4,11.0856480598 +55,,SUM,1,0,1,0,16,25,139,28.3091230392 +55,,,,,,,,,, +56,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,0,2,1,10.0545377731 +56,CUP,SUM,0,0,0,0,0,2,8,8.7348787785 +56,SPOON,SUM,0,0,0,0,0,3,0,11.915060997 +56,,SUM,0,0,0,0,0,7,9,30.7044775486 +56,,,,,,,,,, +57,,,,,,,,,, +57,BOWL,SUM,0,0,0,0,0,21,0,10.7666630745 +57,CUP,SUM,1,0,1,0,0,17,119,0 +57,SPOON,SUM,0,0,0,0,8,1,0,18.182464838 +57,,SUM,1,0,1,0,8,39,119,28.9491279125 +57,,,,,,,,,, +58,,,,,,,,,, +58,BOWL,SUM,0,0,0,0,2,0,0,9.4779970646 +58,CUP,SUM,0,0,0,0,16,8,23,27.578758955 +58,SPOON,SUM,0,0,0,0,0,3,0,12.3301131725 +58,,SUM,0,0,0,0,18,11,23,49.3868691921 +58,,,,,,,,,, +59,,,,,,,,,, +59,BOWL,SUM,0,0,0,0,0,2,16,15.3572249413 +59,CUP,SUM,0,0,0,0,8,3,8,13.2178461552 +59,SPOON,SUM,0,0,0,0,8,8,0,16.7570710182 +59,,SUM,0,0,0,0,16,13,24,45.3321421146 +59,,,,,,,,,, +60,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,8,17,4,14.5749878883 +60,CUP,SUM,0,0,0,0,0,0,8,8.6219570637 +60,SPOON,SUM,0,0,0,0,0,2,2,12.4710600376 +60,,SUM,0,0,0,0,8,19,14,35.6680049896 +60,,,,,,,,,, +61,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,0,5,0,9.4131758213 +61,CUP,SUM,0,0,0,0,0,1,9,9.2570340633 +61,SPOON,SUM,0,0,0,0,0,1,0,12.6277678013 +61,,SUM,0,0,0,0,0,7,9,31.2979776859 +61,,,,,,,,,, +62,,,,,,,,,, +62,BOWL,SUM,1,0,1,0,0,10,42,0 +62,CUP,SUM,0,0,0,0,0,3,28,21.1628861427 +62,SPOON,SUM,0,0,0,0,0,11,28,32.5177648067 +62,,SUM,1,0,1,0,0,24,98,53.6806509495 +62,,,,,,,,,, +63,,,,,,,,,, +63,BOWL,SUM,0,0,0,0,0,2,8,11.7775421143 +63,CUP,SUM,0,0,0,0,0,4,8,8.9378311634 +63,SPOON,SUM,0,0,0,0,0,7,0,12.4155600071 +63,,SUM,0,0,0,0,0,13,16,33.1309332848 +63,,,,,,,,,, +64,,,,,,,,,, +64,BOWL,SUM,0,0,0,0,8,21,11,20.5141060352 +64,CUP,SUM,1,0,1,0,0,8,53,0 +64,SPOON,SUM,0,0,0,0,0,11,4,14.9224128723 +64,,SUM,1,0,1,0,8,40,68,35.4365189075 +64,,,,,,,,,, +65,,,,,,,,,, +65,BOWL,SUM,0,0,0,0,0,1,1,10.4428038597 +65,CUP,SUM,0,0,0,0,0,5,20,14.1611599922 +65,SPOON,SUM,0,0,0,0,0,3,0,12.5926070213 +65,,SUM,0,0,0,0,0,9,21,37.1965708733 +65,,,,,,,,,, +66,,,,,,,,,, +66,BOWL,SUM,0,0,0,0,0,2,0,8.6577911377 +66,CUP,SUM,0,0,0,0,0,6,67,30.5818729401 +66,SPOON,SUM,0,0,0,0,2,5,0,13.8763139248 +66,,SUM,0,0,0,0,2,13,67,53.1159780025 +66,,,,,,,,,, +67,,,,,,,,,, +67,BOWL,SUM,0,0,0,0,0,12,15,15.9300789833 +67,CUP,SUM,1,0,1,0,4,7,63,0 +67,SPOON,SUM,0,0,0,0,0,1,0,11.2523219585 +67,,SUM,1,0,1,0,4,20,78,27.1824009418 +67,,,,,,,,,, +68,,,,,,,,,, +68,BOWL,SUM,0,0,0,0,8,0,0,11.6198208332 +68,CUP,SUM,0,0,0,0,2,5,14,15.6083889008 +68,SPOON,SUM,0,0,0,0,0,1,0,12.0422189236 +68,,SUM,0,0,0,0,10,6,14,39.2704286575 +68,,,,,,,,,, +69,,,,,,,,,, +69,BOWL,SUM,0,0,0,0,0,1,12,12.202881813 +69,CUP,SUM,0,0,0,0,2,3,8,9.9741330147 +69,SPOON,SUM,0,0,0,0,0,1,0,11.9872598648 +69,,SUM,0,0,0,0,2,5,20,34.1642746925 +69,,,,,,,,,, +70,,,,,,,,,, +70,BOWL,SUM,0,0,0,0,8,2,0,13.1749141216 +70,CUP,SUM,1,0,1,0,8,9,78,0 +70,SPOON,SUM,0,0,0,0,0,0,0,11.2089328766 +70,,SUM,1,0,1,0,16,11,78,24.3838469982 +70,,,,,,,,,, +71,,,,,,,,,, +71,BOWL,SUM,0,0,0,0,0,5,1,10.6148161888 +71,CUP,SUM,0,0,0,0,56,7,13,39.7586920261 +71,SPOON,SUM,0,0,0,0,0,6,5,15.0494308472 +71,,SUM,0,0,0,0,56,18,19,65.4229390621 +71,,,,,,,,,, +72,,,,,,,,,, +72,BOWL,SUM,0,0,0,0,0,6,4,9.8789288998 +72,CUP,SUM,0,0,0,0,0,4,17,13.5467891693 +72,SPOON,SUM,0,0,0,0,0,10,19,22.0361969471 +72,,SUM,0,0,0,0,0,20,40,45.4619150162 +72,,,,,,,,,, +73,,,,,,,,,, +73,BOWL,SUM,0,0,0,0,0,7,1,11.9781820774 +73,CUP,SUM,0,0,0,0,0,0,8,8.0586650372 +73,SPOON,SUM,0,0,0,0,0,3,0,12.7171919346 +73,,SUM,0,0,0,0,0,10,9,32.7540390491 +73,,,,,,,,,, +74,,,,,,,,,, +74,BOWL,SUM,0,0,0,0,8,8,0,13.1716458797 +74,CUP,SUM,0,0,0,0,0,16,26,17.0292191505 +74,SPOON,SUM,0,0,0,0,2,0,0,12.8939201832 +74,,SUM,0,0,0,0,10,24,26,43.0947852135 +74,,,,,,,,,, +75,,,,,,,,,, +75,BOWL,SUM,1,0,0,1,8,8,35,0 +75,CUP,SUM,0,0,0,0,10,7,52,32.3454859257 +75,SPOON,SUM,0,0,0,0,0,3,9,16.6799402237 +75,,SUM,1,0,0,1,18,18,96,49.0254261494 +75,,,,,,,,,, +76,,,,,,,,,, +76,BOWL,SUM,0,0,0,0,0,2,8,17.6890158653 +76,CUP,SUM,0,0,0,0,0,2,31,18.3480980396 +76,SPOON,SUM,0,0,0,0,0,2,0,11.5113668442 +76,,SUM,0,0,0,0,0,6,39,47.5484807491 +76,,,,,,,,,, +77,,,,,,,,,, +77,BOWL,SUM,0,0,0,0,0,1,0,8.2897741795 +77,CUP,SUM,0,0,0,0,8,0,8,11.8973419666 +77,SPOON,SUM,0,0,0,0,0,16,22,20.7913160324 +77,,SUM,0,0,0,0,8,17,30,40.9784321785 +77,,,,,,,,,, +78,,,,,,,,,, +78,BOWL,SUM,0,0,0,0,2,2,3,13.7646708488 +78,CUP,SUM,0,0,0,0,0,6,8,10.6656548977 +78,SPOON,SUM,0,0,0,0,0,3,0,12.6343328953 +78,,SUM,0,0,0,0,2,11,11,37.0646586418 +78,,,,,,,,,, +79,,,,,,,,,, +79,BOWL,SUM,0,0,0,0,0,13,10,12.8353478909 +79,CUP,SUM,0,0,0,0,8,7,8,13.6929280758 +79,SPOON,SUM,0,0,0,0,8,8,5,24.2914118767 +79,,SUM,0,0,0,0,16,28,23,50.8196878433 +79,,,,,,,,,, +80,,,,,,,,,, +80,BOWL,SUM,0,0,0,0,0,0,0,8.8202590942 +80,CUP,SUM,0,0,0,0,10,6,46,29.2234630585 +80,SPOON,SUM,0,0,0,0,8,0,0,16.5579969883 +80,,SUM,0,0,0,0,18,6,46,54.601719141 +80,,,,,,,,,, +81,,,,,,,,,, +81,BOWL,SUM,0,0,0,0,0,3,0,9.3924088478 +81,CUP,SUM,0,0,0,0,0,1,9,9.9047038555 +81,SPOON,SUM,0,0,0,0,0,7,1,14.0745661259 +81,,SUM,0,0,0,0,0,11,10,33.3716788292 +81,,,,,,,,,, +82,,,,,,,,,, +82,BOWL,SUM,0,0,0,0,16,1,8,21.037596941 +82,CUP,SUM,0,0,0,0,2,5,8,10.0474328995 +82,SPOON,SUM,0,0,0,0,0,0,4,13.4084510803 +82,,SUM,0,0,0,0,18,6,20,44.4934809208 +82,,,,,,,,,, +83,,,,,,,,,, +83,BOWL,SUM,0,0,0,0,0,1,0,9.2715330124 +83,CUP,SUM,0,0,0,0,0,2,9,9.9233140945 +83,SPOON,SUM,0,0,0,0,0,7,0,13.6907441616 +83,,SUM,0,0,0,0,0,10,9,32.8855912685 +83,,,,,,,,,, +84,,,,,,,,,, +84,BOWL,SUM,1,0,1,0,0,7,50,0 +84,CUP,SUM,0,0,0,0,0,6,46,21.3091490269 +84,SPOON,SUM,0,0,0,0,0,5,0,13.0033919811 +84,,SUM,1,0,1,0,0,18,96,34.312541008 +84,,,,,,,,,, +85,,,,,,,,,, +85,BOWL,SUM,0,0,0,0,0,1,2,9.81153512 +85,CUP,SUM,1,0,1,0,2,7,82,0 +85,SPOON,SUM,0,0,0,0,0,7,24,22.0011050701 +85,,SUM,1,0,1,0,2,15,108,31.8126401901 +85,,,,,,,,,, +86,,,,,,,,,, +86,BOWL,SUM,0,0,0,0,20,4,24,30.3210780621 +86,CUP,SUM,0,0,0,0,0,6,67,31.7467520237 +86,SPOON,SUM,0,0,0,0,2,3,0,12.543628931 +86,,SUM,0,0,0,0,22,13,91,74.6114590168 +86,,,,,,,,,, +87,,,,,,,,,, +87,BOWL,SUM,0,0,0,0,0,3,0,8.8535299301 +87,CUP,SUM,0,0,0,0,0,6,10,11.5513458252 +87,SPOON,SUM,0,0,0,0,8,10,1,18.9038031101 +87,,SUM,0,0,0,0,8,19,11,39.3086788654 +87,,,,,,,,,, +88,,,,,,,,,, +88,BOWL,SUM,0,0,0,0,0,2,0,8.176787138 +88,CUP,SUM,0,0,0,0,0,7,25,14.5087330341 +88,SPOON,SUM,0,0,0,0,0,3,1,14.4591498375 +88,,SUM,0,0,0,0,0,12,26,37.1446700096 +88,,,,,,,,,, +89,,,,,,,,,, +89,BOWL,SUM,0,0,0,0,0,1,1,10.9441628456 +89,CUP,SUM,0,0,0,0,0,2,8,8.7023880482 +89,SPOON,SUM,0,0,0,0,0,0,0,11.8025960922 +89,,SUM,0,0,0,0,0,3,9,31.449146986 +89,,,,,,,,,, +90,,,,,,,,,, +90,BOWL,SUM,0,0,0,0,10,13,2,17.6294960976 +90,CUP,SUM,0,0,0,0,2,0,8,9.3437690735 +90,SPOON,SUM,0,0,0,0,0,3,4,15.9582970142 +90,,SUM,0,0,0,0,12,16,14,42.9315621853 +90,,,,,,,,,, +91,,,,,,,,,, +91,BOWL,SUM,0,0,0,0,8,4,18,21.1909818649 +91,CUP,SUM,0,0,0,0,2,5,49,26.1136558056 +91,SPOON,SUM,0,0,0,0,0,7,17,23.8210988045 +91,,SUM,0,0,0,0,10,16,84,71.125736475 +91,,,,,,,,,, +92,,,,,,,,,, +92,BOWL,SUM,0,0,0,0,0,9,0,9.7193210125 +92,CUP,SUM,0,0,0,0,8,3,8,13.6172029972 +92,SPOON,SUM,0,0,0,0,14,5,0,22.2221279144 +92,,SUM,0,0,0,0,22,17,8,45.5586519241 +92,,,,,,,,,, +93,,,,,,,,,, +93,BOWL,SUM,1,0,1,0,0,6,44,0 +93,CUP,SUM,0,0,0,0,0,1,11,10.3774721622 +93,SPOON,SUM,0,0,0,0,0,1,0,11.7362718582 +93,,SUM,1,0,1,0,0,8,55,22.1137440205 +93,,,,,,,,,, +94,,,,,,,,,, +94,BOWL,SUM,0,0,0,0,2,0,4,9.5504350662 +94,CUP,SUM,0,0,0,0,0,4,17,12.5650060177 +94,SPOON,SUM,0,0,0,0,0,1,8,14.831182003 +94,,SUM,0,0,0,0,2,5,29,36.9466230869 +94,,,,,,,,,, +95,,,,,,,,,, +95,BOWL,SUM,0,0,0,0,2,9,9,16.8295280933 +95,CUP,SUM,0,0,0,0,0,0,9,9.8726351261 +95,SPOON,SUM,0,0,0,0,0,2,0,11.1721999645 +95,,SUM,0,0,0,0,2,11,18,37.874363184 +95,,,,,,,,,, +96,,,,,,,,,, +96,BOWL,SUM,0,0,0,0,14,3,2,21.2055969238 +96,CUP,SUM,0,0,0,0,0,2,37,20.6349389553 +96,SPOON,SUM,0,0,0,0,0,1,0,12.838547945 +96,,SUM,0,0,0,0,14,6,39,54.6790838242 +96,,,,,,,,,, +97,,,,,,,,,, +97,BOWL,SUM,0,0,0,0,0,1,0,7.5711941719 +97,CUP,SUM,0,0,0,0,0,6,9,9.9341030121 +97,SPOON,SUM,0,0,0,0,0,16,0,14.9681229591 +97,,SUM,0,0,0,0,0,23,9,32.4734201431 +97,,,,,,,,,, +98,,,,,,,,,, +98,BOWL,SUM,0,0,0,0,0,3,0,8.077917099 +98,CUP,SUM,0,0,0,0,0,1,27,14.1048429012 +98,SPOON,SUM,0,0,0,0,0,1,0,12.1434412003 +98,,SUM,0,0,0,0,0,5,27,34.3262012005 +98,,,,,,,,,, +99,,,,,,,,,, +99,BOWL,SUM,0,0,0,0,8,10,34,24.9848151207 +99,CUP,SUM,0,0,0,0,2,0,9,11.6440911293 +99,SPOON,SUM,0,0,0,0,0,5,6,14.6617000103 +99,,SUM,0,0,0,0,10,15,49,51.2906062603 +99,,,,,,,,,, +100,,,,,,,,,, +100,BOWL,SUM,0,0,0,0,8,6,9,16.6319000721 +100,CUP,SUM,0,0,0,0,0,3,21,13.7950179577 +100,SPOON,SUM,0,0,0,0,8,3,0,16.1928889751 +100,,SUM,0,0,0,0,16,12,30,46.6198070049 +100,,,,,,,,,, +101,,,,,,,,,, +101,BOWL,SUM,1,0,1,0,0,8,44,0 +101,CUP,SUM,0,0,0,0,8,4,28,20.0306360722 +101,SPOON,SUM,0,0,0,0,8,1,0,16.71179986 +101,,SUM,1,0,1,0,16,13,72,36.7424359322 +101,,,,,,,,,, +102,,,,,,,,,, +102,BOWL,SUM,0,0,0,0,0,1,0,9.5115101337 +102,CUP,SUM,0,0,0,0,2,2,8,9.9822981358 +102,SPOON,SUM,0,0,0,0,0,4,0,13.7404060364 +102,,SUM,0,0,0,0,2,7,8,33.2342143059 +102,,,,,,,,,, +103,,,,,,,,,, +103,BOWL,SUM,0,0,0,0,16,2,1,15.6639871597 +103,CUP,SUM,1,0,1,0,16,9,51,0 +103,SPOON,SUM,0,0,0,0,0,0,0,11.109803915 +103,,SUM,1,0,1,0,32,11,52,26.7737910748 +103,,,,,,,,,, +104,,,,,,,,,, +104,BOWL,SUM,0,0,0,0,8,5,1,16.3822968006 +104,CUP,SUM,1,0,1,0,0,8,77,0 +104,SPOON,SUM,0,0,0,0,2,8,5,17.3608489037 +104,,SUM,1,0,1,0,10,21,83,33.7431457043 +104,,,,,,,,,, +105,,,,,,,,,, +105,BOWL,SUM,0,0,0,0,0,1,4,11.5469229221 +105,CUP,SUM,0,0,0,0,2,2,9,10.271479845 +105,SPOON,SUM,1,0,1,0,8,11,46,0 +105,,SUM,1,0,1,0,10,14,59,21.8184027672 +105,,,,,,,,,, +106,,,,,,,,,, +106,BOWL,SUM,0,0,0,0,8,1,0,12.520072937 +106,CUP,SUM,0,0,0,0,16,13,21,26.7877368927 +106,SPOON,SUM,0,0,0,0,2,4,4,14.6401979923 +106,,SUM,0,0,0,0,26,18,25,53.948007822 +106,,,,,,,,,, +107,,,,,,,,,, +107,BOWL,SUM,0,0,0,0,2,2,0,8.8939509392 +107,CUP,SUM,0,0,0,0,0,0,8,8.7469089031 +107,SPOON,SUM,0,0,0,0,0,2,0,12.1294250488 +107,,SUM,0,0,0,0,2,4,8,29.7702848911 +107,,,,,,,,,, +108,,,,,,,,,, +108,BOWL,SUM,0,0,0,0,0,4,12,14.0969569683 +108,CUP,SUM,0,0,0,0,0,1,18,11.749614954 +108,SPOON,SUM,0,0,0,0,0,3,13,26.8417870998 +108,,SUM,0,0,0,0,0,8,43,52.6883590221 +108,,,,,,,,,, +109,,,,,,,,,, +109,BOWL,SUM,0,0,0,0,8,7,0,20.296364069 +109,CUP,SUM,0,0,0,0,0,4,8,9.1306929588 +109,SPOON,SUM,0,0,0,0,0,0,0,12.1252682209 +109,,SUM,0,0,0,0,8,11,8,41.5523252487 +109,,,,,,,,,, +110,,,,,,,,,, +110,BOWL,SUM,0,0,0,0,16,0,0,17.5314068794 +110,CUP,SUM,1,0,1,0,0,22,135,0 +110,SPOON,SUM,0,0,0,0,0,3,4,11.5408620834 +110,,SUM,1,0,1,0,16,25,139,29.0722689629 +110,,,,,,,,,, +111,,,,,,,,,, +111,BOWL,SUM,0,0,0,0,0,2,1,10.2117409706 +111,CUP,SUM,0,0,0,0,0,2,8,9.0250599384 +111,SPOON,SUM,0,0,0,0,0,3,0,11.8206629753 +111,,SUM,0,0,0,0,0,7,9,31.0574638844 +111,,,,,,,,,, +112,,,,,,,,,, +112,BOWL,SUM,0,0,0,0,0,21,0,10.8600468636 +112,CUP,SUM,1,0,1,0,0,17,119,0 +112,SPOON,SUM,0,0,0,0,8,1,0,18.4818348885 +112,,SUM,1,0,1,0,8,39,119,29.341881752 +112,,,,,,,,,, +113,,,,,,,,,, +113,BOWL,SUM,0,0,0,0,2,0,0,9.8451619148 +113,CUP,SUM,0,0,0,0,16,8,23,27.0057740211 +113,SPOON,SUM,0,0,0,0,0,3,0,12.8208341599 +113,,SUM,0,0,0,0,18,11,23,49.6717700958 +113,,,,,,,,,, +114,,,,,,,,,, +114,BOWL,SUM,0,0,0,0,0,2,16,15.5217041969 +114,CUP,SUM,0,0,0,0,8,3,8,14.0651209354 +114,SPOON,SUM,0,0,0,0,8,8,0,16.9467549324 +114,,SUM,0,0,0,0,16,13,24,46.5335800648 +114,,,,,,,,,, +115,,,,,,,,,, +115,BOWL,SUM,0,0,0,0,8,17,4,15.1020817757 +115,CUP,SUM,0,0,0,0,0,0,8,8.5815749168 +115,SPOON,SUM,0,0,0,0,0,2,2,12.7029480934 +115,,SUM,0,0,0,0,8,19,14,36.3866047859 +115,,,,,,,,,, +116,,,,,,,,,, +116,BOWL,SUM,0,0,0,0,0,5,0,9.5931780338 +116,CUP,SUM,0,0,0,0,0,1,9,9.3947200775 +116,SPOON,SUM,0,0,0,0,0,1,0,13.0033590794 +116,,SUM,0,0,0,0,0,7,9,31.9912571907 +116,,,,,,,,,, +117,,,,,,,,,, +117,BOWL,SUM,1,0,1,0,0,10,42,0 +117,CUP,SUM,0,0,0,0,0,3,28,21.7019751072 +117,SPOON,SUM,0,0,0,0,0,11,28,33.0930240154 +117,,SUM,1,0,1,0,0,24,98,54.7949991226 +117,,,,,,,,,, +118,,,,,,,,,, +118,BOWL,SUM,0,0,0,0,0,2,8,12.1588830948 +118,CUP,SUM,0,0,0,0,0,4,8,9.0444731712 +118,SPOON,SUM,0,0,0,0,0,7,0,12.9072160721 +118,,SUM,0,0,0,0,0,13,16,34.1105723381 +118,,,,,,,,,, +119,,,,,,,,,, +119,BOWL,SUM,0,0,0,0,8,21,11,20.5797851086 +119,CUP,SUM,1,0,1,0,0,8,53,0 +119,SPOON,SUM,0,0,0,0,0,11,4,15.5039110184 +119,,SUM,1,0,1,0,8,40,68,36.0836961269 +119,,,,,,,,,, +120,,,,,,,,,, +120,BOWL,SUM,0,0,0,0,0,1,1,10.6489179134 +120,CUP,SUM,0,0,0,0,0,5,20,14.144382 +120,SPOON,SUM,0,0,0,0,0,3,0,12.9957549572 +120,,SUM,0,0,0,0,0,9,21,37.7890548706 +120,,,,,,,,,, +121,,,,,,,,,, +121,BOWL,SUM,0,0,0,0,0,2,0,8.9371979237 +121,CUP,SUM,0,0,0,0,0,6,67,30.8375749588 +121,SPOON,SUM,0,0,0,0,2,5,0,14.4463419914 +121,,SUM,0,0,0,0,2,13,67,54.2211148739 +121,,,,,,,,,, +122,,,,,,,,,, +122,BOWL,SUM,0,0,0,0,0,12,15,15.8068780899 +122,CUP,SUM,1,0,1,0,4,7,63,0 +122,SPOON,SUM,0,0,0,0,0,1,0,11.5770280361 +122,,SUM,1,0,1,0,4,20,78,27.383906126 +122,,,,,,,,,, +123,,,,,,,,,, +123,BOWL,SUM,0,0,0,0,8,0,0,12.0141150951 +123,CUP,SUM,0,0,0,0,2,5,14,15.7797811031 +123,SPOON,SUM,0,0,0,0,0,1,0,12.3976700306 +123,,SUM,0,0,0,0,10,6,14,40.1915662289 +123,,,,,,,,,, +124,,,,,,,,,, +124,BOWL,SUM,0,0,0,0,0,1,12,12.3331639767 +124,CUP,SUM,0,0,0,0,2,3,8,10.0667610168 +124,SPOON,SUM,0,0,0,0,0,1,0,12.356896162 +124,,SUM,0,0,0,0,2,5,20,34.7568211555 +124,,,,,,,,,, +125,,,,,,,,,, +125,BOWL,SUM,0,0,0,0,8,2,0,13.2340250015 +125,CUP,SUM,1,0,1,0,8,9,78,0 +125,SPOON,SUM,0,0,0,0,0,0,0,11.1414489746 +125,,SUM,1,0,1,0,16,11,78,24.3754739761 +125,,,,,,,,,, +126,,,,,,,,,, +126,BOWL,SUM,0,0,0,0,0,5,1,10.7816548347 +126,CUP,SUM,0,0,0,0,56,7,13,40.2000989914 +126,SPOON,SUM,0,0,0,0,0,6,5,15.1644020081 +126,,SUM,0,0,0,0,56,18,19,66.1461558342 +126,,,,,,,,,, +127,,,,,,,,,, +127,BOWL,SUM,0,0,0,0,0,6,4,9.8695020676 +127,CUP,SUM,0,0,0,0,0,4,17,13.8128650188 +127,SPOON,SUM,0,0,0,0,0,10,19,21.8556649685 +127,,SUM,0,0,0,0,0,20,40,45.5380320549 +127,,,,,,,,,, +128,,,,,,,,,, +128,BOWL,SUM,0,0,0,0,0,7,1,12.3377430439 +128,CUP,SUM,0,0,0,0,0,0,8,8.1055619717 +128,SPOON,SUM,0,0,0,0,0,3,0,13.2631878853 +128,,SUM,0,0,0,0,0,10,9,33.7064929008 +128,,,,,,,,,, +129,,,,,,,,,, +129,BOWL,SUM,0,0,0,0,0,22,12,17.484167099 +129,CUP,SUM,0,0,0,0,0,16,20,15.8541278839 +129,SPOON,SUM,0,0,0,0,2,9,0,14.2880139351 +129,,SUM,0,0,0,0,2,47,32,47.626308918 +129,,,,,,,,,, +130,,,,,,,,,, +130,BOWL,SUM,0,0,0,0,0,4,12,13.7268381119 +130,CUP,SUM,0,0,0,0,0,7,42,21.0261740685 +130,SPOON,SUM,0,0,0,0,0,1,0,11.6369509697 +130,,SUM,0,0,0,0,0,12,54,46.38996315 +130,,,,,,,,,, +131,,,,,,,,,, +131,BOWL,SUM,0,0,0,0,18,5,28,26.8971281052 +131,CUP,SUM,0,0,0,0,0,9,8,10.7678720951 +131,SPOON,SUM,0,0,0,0,0,7,0,12.0308258533 +131,,SUM,0,0,0,0,18,21,36,49.6958260536 +131,,,,,,,,,, +132,,,,,,,,,, +132,BOWL,SUM,0,0,0,0,0,5,14,15.9205322266 +132,CUP,SUM,0,0,0,0,0,14,8,10.7989420891 +132,SPOON,SUM,1,0,1,0,0,14,11,0 +132,,SUM,1,0,1,0,0,33,33,26.7194743156 +132,,,,,,,,,, +133,,,,,,,,,, +133,BOWL,SUM,0,0,0,0,0,4,5,14.1082930565 +133,CUP,SUM,0,0,0,0,4,1,13,12.7270030975 +133,SPOON,SUM,0,0,0,0,16,13,4,36.9019489288 +133,,SUM,0,0,0,0,20,18,22,63.7372450829 +133,,,,,,,,,, +134,,,,,,,,,, +134,BOWL,SUM,0,0,0,0,0,6,0,10.4737198353 +134,CUP,SUM,0,0,0,0,24,16,34,33.523555994 +134,SPOON,SUM,0,0,0,0,0,3,2,15.5895130634 +134,,SUM,0,0,0,0,24,25,36,59.5867888927 +134,,,,,,,,,, +135,,,,,,,,,, +135,BOWL,SUM,0,0,0,0,0,2,0,9.5275111198 +135,CUP,SUM,0,0,0,0,2,2,23,16.0832350254 +135,SPOON,SUM,0,0,0,0,2,5,10,18.8270280361 +135,,SUM,0,0,0,0,4,9,33,44.4377741814 +135,,,,,,,,,, +136,,,,,,,,,, +136,BOWL,SUM,0,0,0,0,0,15,4,16.9680140018 +136,CUP,SUM,1,0,1,0,0,9,106,0 +136,SPOON,SUM,0,0,0,0,24,7,4,24.1122329235 +136,,SUM,1,0,1,0,24,31,114,41.0802469254 +136,,,,,,,,,, +137,,,,,,,,,, +137,BOWL,SUM,0,0,0,0,22,3,2,23.3682181835 +137,CUP,SUM,0,0,0,0,2,8,8,10.9837861061 +137,SPOON,SUM,0,0,0,0,0,3,0,13.0956449509 +137,,SUM,0,0,0,0,24,14,10,47.4476492405 +137,,,,,,,,,, +138,,,,,,,,,, +138,BOWL,SUM,0,0,0,0,0,0,4,9.4308941364 +138,CUP,SUM,0,0,0,0,0,3,8,10.1117010117 +138,SPOON,SUM,0,0,0,0,8,0,0,17.3162419796 +138,,SUM,0,0,0,0,8,3,12,36.8588371277 +138,,,,,,,,,, +139,,,,,,,,,, +139,BOWL,SUM,0,0,0,0,0,1,0,9.2899258137 +139,CUP,SUM,0,0,0,0,16,12,71,42.8380079269 +139,SPOON,SUM,0,0,0,0,0,8,19,22.1764428616 +139,,SUM,0,0,0,0,16,21,90,74.3043766022 +139,,,,,,,,,, +140,,,,,,,,,, +140,BOWL,SUM,0,0,0,0,8,3,9,16.3059420586 +140,CUP,SUM,0,0,0,0,10,8,49,33.7361040115 +140,SPOON,SUM,1,0,1,0,0,9,11,0 +140,,SUM,1,0,1,0,18,20,69,50.0420460701 +140,,,,,,,,,, +141,,,,,,,,,, +141,BOWL,SUM,0,0,0,0,8,1,0,16.6043851376 +141,CUP,SUM,1,0,1,0,20,7,126,0 +141,SPOON,SUM,1,0,1,0,32,12,11,0 +141,,SUM,2,0,2,0,60,20,137,16.6043851376 +141,,,,,,,,,, +142,,,,,,,,,, +142,BOWL,SUM,0,0,0,0,8,0,0,17.4152309895 +142,CUP,SUM,0,0,0,0,0,7,109,45.5534880161 +142,SPOON,SUM,0,0,0,0,0,18,7,17.5913360119 +142,,SUM,0,0,0,0,8,25,116,80.5600550175 +142,,,,,,,,,, +143,,,,,,,,,, +143,BOWL,SUM,0,0,0,0,8,17,12,20.6115529537 +143,CUP,SUM,0,0,0,0,0,1,11,10.9092340469 +143,SPOON,SUM,0,0,0,0,2,3,1,13.686756134 +143,,SUM,0,0,0,0,10,21,24,45.2075431347 +143,,,,,,,,,, +144,,,,,,,,,, +144,BOWL,SUM,0,0,0,0,0,2,0,8.893504858 +144,CUP,SUM,0,0,0,0,0,1,29,18.4887700081 +144,SPOON,SUM,0,0,0,0,0,12,7,18.5192329884 +144,,SUM,0,0,0,0,0,15,36,45.9015078545 +144,,,,,,,,,, +145,,,,,,,,,, +145,BOWL,SUM,0,0,0,0,0,5,4,13.5352010727 +145,CUP,SUM,0,0,0,0,2,6,13,19.6412708759 +145,SPOON,SUM,0,0,0,0,8,1,0,20.3212730885 +145,,SUM,0,0,0,0,10,12,17,53.4977450371 +145,,,,,,,,,, +146,,,,,,,,,, +146,BOWL,SUM,0,0,0,0,0,1,1,10.1164069176 +146,CUP,SUM,0,0,0,0,16,7,8,20.7620549202 +146,SPOON,SUM,1,0,1,0,0,11,11,0 +146,,SUM,1,0,1,0,16,19,20,30.8784618378 +146,,,,,,,,,, +147,,,,,,,,,, +147,BOWL,SUM,0,0,0,0,8,9,30,29.637816906 +147,CUP,SUM,0,0,0,0,0,1,9,10.688603878 +147,SPOON,SUM,0,0,0,0,8,2,0,17.4911358356 +147,,SUM,0,0,0,0,16,12,39,57.8175566196 +147,,,,,,,,,, +148,,,,,,,,,, +148,BOWL,SUM,0,0,0,0,0,7,9,13.0492727757 +148,CUP,SUM,0,0,0,0,8,1,10,14.2250959873 +148,SPOON,SUM,0,0,0,0,0,5,11,21.153922081 +148,,SUM,0,0,0,0,8,13,30,48.428290844 +148,,,,,,,,,, +149,,,,,,,,,, +149,BOWL,SUM,0,0,0,0,2,9,9,16.5710780621 +149,CUP,SUM,0,0,0,0,0,0,9,9.7253911495 +149,SPOON,SUM,0,0,0,0,0,2,0,10.9943780899 +149,,SUM,0,0,0,0,2,11,18,37.2908473015 +149,,,,,,,,,, +150,,,,,,,,,, +150,BOWL,SUM,0,0,0,0,14,3,2,20.5547230244 +150,CUP,SUM,0,0,0,0,0,2,37,18.9707920551 +150,SPOON,SUM,0,0,0,0,0,1,0,13.0611550808 +150,,SUM,0,0,0,0,14,6,39,52.5866701603 +150,,,,,,,,,, +151,,,,,,,,,, +151,BOWL,SUM,0,0,0,0,0,1,0,7.5482809544 +151,CUP,SUM,0,0,0,0,0,6,9,9.5270559788 +151,SPOON,SUM,0,0,0,0,0,16,0,14.7426860332 +151,,SUM,0,0,0,0,0,23,9,31.8180229664 +151,,,,,,,,,, +152,,,,,,,,,, +152,BOWL,SUM,0,0,0,0,0,3,0,7.6704599857 +152,CUP,SUM,0,0,0,0,0,1,27,13.5985081196 +152,SPOON,SUM,0,0,0,0,0,1,0,11.7748138905 +152,,SUM,0,0,0,0,0,5,27,33.0437819958 +152,,,,,,,,,, +153,,,,,,,,,, +153,BOWL,SUM,0,0,0,0,8,10,34,23.4281308651 +153,CUP,SUM,0,0,0,0,2,0,9,10.5171349049 +153,SPOON,SUM,0,0,0,0,0,5,6,14.3733201027 +153,,SUM,0,0,0,0,10,15,49,48.3185858727 +153,,,,,,,,,, +154,,,,,,,,,, +154,BOWL,SUM,0,0,0,0,8,6,9,15.7407851219 +154,CUP,SUM,0,0,0,0,0,3,21,12.4679927826 +154,SPOON,SUM,0,0,0,0,8,3,0,15.1039841175 +154,,SUM,0,0,0,0,16,12,30,43.312762022 +154,,,,,,,,,, +155,,,,,,,,,, +155,BOWL,SUM,1,0,1,0,0,8,44,0 +155,CUP,SUM,0,0,0,0,8,4,28,18.9013140202 +155,SPOON,SUM,0,0,0,0,8,1,0,15.8874628544 +155,,SUM,1,0,1,0,16,13,72,34.7887768745 +155,,,,,,,,,, +156,,,,,,,,,, +156,BOWL,SUM,0,0,0,0,0,1,0,9.3529009819 +156,CUP,SUM,0,0,0,0,2,2,8,9.54134202 +156,SPOON,SUM,0,0,0,0,0,4,0,13.2791109085 +156,,SUM,0,0,0,0,2,7,8,32.1733539104 +156,,,,,,,,,, +157,,,,,,,,,, +157,BOWL,SUM,0,0,0,0,16,2,1,14.4753739834 +157,CUP,SUM,1,0,1,0,16,9,51,0 +157,SPOON,SUM,0,0,0,0,0,0,0,10.7643082142 +157,,SUM,1,0,1,0,32,11,52,25.2396821976 +157,,,,,,,,,, +158,,,,,,,,,, +158,BOWL,SUM,0,0,0,0,8,5,1,15.519356966 +158,CUP,SUM,1,0,1,0,0,8,77,0 +158,SPOON,SUM,0,0,0,0,2,8,5,16.472463131 +158,,SUM,1,0,1,0,10,21,83,31.991820097 +158,,,,,,,,,, +159,,,,,,,,,, +159,BOWL,SUM,0,0,0,0,0,1,4,11.1084070206 +159,CUP,SUM,0,0,0,0,2,2,9,9.9092440605 +159,SPOON,SUM,1,0,1,0,8,11,46,0 +159,,SUM,1,0,1,0,10,14,59,21.0176510811 +159,,,,,,,,,, +160,,,,,,,,,, +160,BOWL,SUM,0,0,0,0,8,1,0,11.9087779522 +160,CUP,SUM,0,0,0,0,16,13,21,25.5116438866 +160,SPOON,SUM,0,0,0,0,2,4,4,14.2284789085 +160,,SUM,0,0,0,0,26,18,25,51.6489007473 +160,,,,,,,,,, +161,,,,,,,,,, +161,BOWL,SUM,0,0,0,0,2,2,0,8.7800588608 +161,CUP,SUM,0,0,0,0,0,0,8,8.5091378689 +161,SPOON,SUM,0,0,0,0,0,2,0,11.9040141106 +161,,SUM,0,0,0,0,2,4,8,29.1932108402 +161,,,,,,,,,, +162,,,,,,,,,, +162,BOWL,SUM,0,0,0,0,0,4,12,13.8613197803 +162,CUP,SUM,0,0,0,0,0,1,18,11.4546701908 +162,SPOON,SUM,0,0,0,0,0,3,13,26.8410189152 +162,,SUM,0,0,0,0,0,8,43,52.1570088863 +162,,,,,,,,,, +163,,,,,,,,,, +163,BOWL,SUM,0,0,0,0,8,7,0,19.321598053 +163,CUP,SUM,0,0,0,0,0,4,8,8.8551170826 +163,SPOON,SUM,0,0,0,0,0,0,0,11.8299710751 +163,,SUM,0,0,0,0,8,11,8,40.0066862106 +163,,,,,,,,,, +164,,,,,,,,,, +164,BOWL,SUM,0,0,0,0,16,0,0,16.3501670361 +164,CUP,SUM,1,0,1,0,0,22,135,0 +164,SPOON,SUM,0,0,0,0,0,3,4,11.0021181107 +164,,SUM,1,0,1,0,16,25,139,27.3522851467 +164,,,,,,,,,, +165,,,,,,,,,, +165,BOWL,SUM,0,0,0,0,0,2,1,9.814811945 +165,CUP,SUM,0,0,0,0,0,2,8,8.6740849018 +165,SPOON,SUM,0,0,0,0,0,3,0,11.6359701157 +165,,SUM,0,0,0,0,0,7,9,30.1248669624 +165,,,,,,,,,, +166,,,,,,,,,, +166,BOWL,SUM,0,0,0,0,0,21,0,10.7826371193 +166,CUP,SUM,1,0,1,0,0,17,119,0 +166,SPOON,SUM,0,0,0,0,8,1,0,17.7291870117 +166,,SUM,1,0,1,0,8,39,119,28.511824131 +166,,,,,,,,,, +167,,,,,,,,,, +167,BOWL,SUM,0,0,0,0,2,0,0,9.1797139645 +167,CUP,SUM,0,0,0,0,16,8,23,26.0081038475 +167,SPOON,SUM,0,0,0,0,0,3,0,12.0188400745 +167,,SUM,0,0,0,0,18,11,23,47.2066578865 +167,,,,,,,,,, +168,,,,,,,,,, +168,BOWL,SUM,0,0,0,0,0,2,16,15.1203789711 +168,CUP,SUM,0,0,0,0,8,3,8,12.5509371758 +168,SPOON,SUM,0,0,0,0,8,8,0,16.38575387 +168,,SUM,0,0,0,0,16,13,24,44.0570700169 +168,,,,,,,,,, +169,,,,,,,,,, +169,BOWL,SUM,0,0,0,0,8,17,4,14.2173280716 +169,CUP,SUM,0,0,0,0,0,0,8,8.3387839794 +169,SPOON,SUM,0,0,0,0,0,2,2,12.5175168514 +169,,SUM,0,0,0,0,8,19,14,35.0736289024 +169,,,,,,,,,, +170,,,,,,,,,, +170,BOWL,SUM,0,0,0,0,0,5,0,9.2157459259 +170,CUP,SUM,0,0,0,0,0,1,9,9.2396688461 +170,SPOON,SUM,0,0,0,0,0,1,0,12.4581029415 +170,,SUM,0,0,0,0,0,7,9,30.9135177135 +170,,,,,,,,,, +171,,,,,,,,,, +171,BOWL,SUM,1,0,1,0,0,10,42,0 +171,CUP,SUM,0,0,0,0,0,3,28,20.7623169422 +171,SPOON,SUM,0,0,0,0,0,11,28,31.6724450588 +171,,SUM,1,0,1,0,0,24,98,52.434762001 +171,,,,,,,,,, +172,,,,,,,,,, +172,BOWL,SUM,0,0,0,0,0,2,8,11.5977959633 +172,CUP,SUM,0,0,0,0,0,4,8,8.8810348511 +172,SPOON,SUM,0,0,0,0,0,7,0,12.1853890419 +172,,SUM,0,0,0,0,0,13,16,32.6642198563 +172,,,,,,,,,, +173,,,,,,,,,, +173,BOWL,SUM,0,0,0,0,8,21,11,19.5221409798 +173,CUP,SUM,1,0,1,0,0,8,53,0 +173,SPOON,SUM,0,0,0,0,0,11,4,14.7901911736 +173,,SUM,1,0,1,0,8,40,68,34.3123321533 +173,,,,,,,,,, +174,,,,,,,,,, +174,BOWL,SUM,0,0,0,0,0,1,1,10.287293911 +174,CUP,SUM,0,0,0,0,0,5,20,13.8196630478 +174,SPOON,SUM,0,0,0,0,0,3,0,12.4159939289 +174,,SUM,0,0,0,0,0,9,21,36.5229508877 +174,,,,,,,,,, +175,,,,,,,,,, +175,BOWL,SUM,0,0,0,0,0,2,0,8.4828579426 +175,CUP,SUM,0,0,0,0,0,6,67,30.3520700932 +175,SPOON,SUM,0,0,0,0,2,5,0,13.8513331413 +175,,SUM,0,0,0,0,2,13,67,52.6862611771 +175,,,,,,,,,, +176,,,,,,,,,, +176,BOWL,SUM,0,0,0,0,0,12,15,15.7096729279 +176,CUP,SUM,1,0,1,0,4,7,63,0 +176,SPOON,SUM,0,0,0,0,0,1,0,11.0305950642 +176,,SUM,1,0,1,0,4,20,78,26.740267992 +176,,,,,,,,,, +177,,,,,,,,,, +177,BOWL,SUM,0,0,0,0,8,0,0,11.3227498531 +177,CUP,SUM,0,0,0,0,2,5,14,15.2432849407 +177,SPOON,SUM,0,0,0,0,0,1,0,11.8735527992 +177,,SUM,0,0,0,0,10,6,14,38.4395875931 +177,,,,,,,,,, +178,,,,,,,,,, +178,BOWL,SUM,0,0,0,0,0,1,12,12.0997440815 +178,CUP,SUM,0,0,0,0,2,3,8,9.5297150612 +178,SPOON,SUM,0,0,0,0,0,1,0,11.9877660275 +178,,SUM,0,0,0,0,2,5,20,33.6172251701 +178,,,,,,,,,, +179,,,,,,,,,, +179,BOWL,SUM,0,0,0,0,8,2,0,12.7518279552 +179,CUP,SUM,1,0,1,0,8,9,78,0 +179,SPOON,SUM,0,0,0,0,0,0,0,11.1834151745 +179,,SUM,1,0,1,0,16,11,78,23.9352431297 +179,,,,,,,,,, +180,,,,,,,,,, +180,BOWL,SUM,0,0,0,0,0,5,1,10.4692001343 +180,CUP,SUM,0,0,0,0,56,7,13,36.7226991653 +180,SPOON,SUM,0,0,0,0,0,6,5,14.564136982 +180,,SUM,0,0,0,0,56,18,19,61.7560362816 +180,,,,,,,,,, +181,,,,,,,,,, +181,BOWL,SUM,0,0,0,0,0,6,4,9.8636031151 +181,CUP,SUM,0,0,0,0,0,4,17,13.4458398819 +181,SPOON,SUM,0,0,0,0,0,10,19,21.8631761074 +181,,SUM,0,0,0,0,0,20,40,45.1726191044 +181,,,,,,,,,, +182,,,,,,,,,, +182,BOWL,SUM,0,0,0,0,0,7,1,11.8912990093 +182,CUP,SUM,0,0,0,0,0,0,8,7.8630590439 +182,SPOON,SUM,0,0,0,0,0,3,0,12.5443320274 +182,,SUM,0,0,0,0,0,10,9,32.2986900806 +182,,,,,,,,,, +183,,,,,,,,,, +183,BOWL,SUM,0,0,0,0,0,22,12,17.155739069 +183,CUP,SUM,0,0,0,0,0,16,20,15.4741060734 +183,SPOON,SUM,0,0,0,0,2,9,0,13.8273839951 +183,,SUM,0,0,0,0,2,47,32,46.4572291374 +183,,,,,,,,,, +184,,,,,,,,,, +184,BOWL,SUM,0,0,0,0,0,4,12,13.700551033 +184,CUP,SUM,0,0,0,0,0,7,42,20.8035359383 +184,SPOON,SUM,0,0,0,0,0,1,0,11.4497230053 +184,,SUM,0,0,0,0,0,12,54,45.9538099766 +184,,,,,,,,,, +185,,,,,,,,,, +185,BOWL,SUM,0,0,0,0,18,5,28,25.434607029 +185,CUP,SUM,0,0,0,0,0,9,8,10.1796081066 +185,SPOON,SUM,0,0,0,0,0,7,0,12.0540821552 +185,,SUM,0,0,0,0,18,21,36,47.6682972908 +185,,,,,,,,,, +186,,,,,,,,,, +186,BOWL,SUM,0,0,0,0,0,5,14,15.4566950798 +186,CUP,SUM,0,0,0,0,0,14,8,10.8741090298 +186,SPOON,SUM,1,0,1,0,0,14,11,0 +186,,SUM,1,0,1,0,0,33,33,26.3308041096 +186,,,,,,,,,, +187,,,,,,,,,, +187,BOWL,SUM,0,0,0,0,0,4,5,13.6739640236 +187,CUP,SUM,0,0,0,0,4,1,13,12.2757570744 +187,SPOON,SUM,0,0,0,0,16,13,4,35.8456618786 +187,,SUM,0,0,0,0,20,18,22,61.7953829765 +187,,,,,,,,,, +188,,,,,,,,,, +188,BOWL,SUM,0,0,0,0,0,6,0,10.3277549744 +188,CUP,SUM,0,0,0,0,24,16,34,31.724766016 +188,SPOON,SUM,0,0,0,0,0,3,2,15.5621011257 +188,,SUM,0,0,0,0,24,25,36,57.6146221161 +188,,,,,,,,,, +189,,,,,,,,,, +189,BOWL,SUM,0,0,0,0,0,2,0,9.1651668549 +189,CUP,SUM,0,0,0,0,2,2,23,15.5984320641 +189,SPOON,SUM,0,0,0,0,2,5,10,17.8255610466 +189,,SUM,0,0,0,0,4,9,33,42.5891599655 +189,,,,,,,,,, +190,,,,,,,,,, +190,BOWL,SUM,0,0,0,0,0,15,4,16.3511359692 +190,CUP,SUM,1,0,1,0,0,9,106,0 +190,SPOON,SUM,0,0,0,0,24,7,4,22.7925560474 +190,,SUM,1,0,1,0,24,31,114,39.1436920166 +190,,,,,,,,,, +191,,,,,,,,,, +191,BOWL,SUM,0,0,0,0,22,3,2,21.8862309456 +191,CUP,SUM,0,0,0,0,2,8,8,11.2169578075 +191,SPOON,SUM,0,0,0,0,0,3,0,12.7851951122 +191,,SUM,0,0,0,0,24,14,10,45.8883838654 +191,,,,,,,,,, +192,,,,,,,,,, +192,BOWL,SUM,0,0,0,0,0,0,4,9.2299110889 +192,CUP,SUM,0,0,0,0,0,3,8,9.8890650272 +192,SPOON,SUM,0,0,0,0,8,0,0,16.2710289955 +192,,SUM,0,0,0,0,8,3,12,35.3900051117 +192,,,,,,,,,, +193,,,,,,,,,, +193,BOWL,SUM,0,0,0,0,0,1,0,8.909621954 +193,CUP,SUM,0,0,0,0,16,12,71,41.0975198746 +193,SPOON,SUM,0,0,0,0,0,8,19,21.7113130093 +193,,SUM,0,0,0,0,16,21,90,71.7184548378 +193,,,,,,,,,, +194,,,,,,,,,, +194,BOWL,SUM,0,0,0,0,8,3,9,15.7570240498 +194,CUP,SUM,0,0,0,0,10,8,49,32.808298111 +194,SPOON,SUM,1,0,1,0,0,9,11,0 +194,,SUM,1,0,1,0,18,20,69,48.5653221607 +194,,,,,,,,,, +195,,,,,,,,,, +195,BOWL,SUM,0,0,0,0,8,1,0,15.9714200497 +195,CUP,SUM,1,0,1,0,20,7,126,0 +195,SPOON,SUM,1,0,1,0,32,12,11,0 +195,,SUM,2,0,2,0,60,20,137,15.9714200497 +195,,,,,,,,,, +196,,,,,,,,,, +196,BOWL,SUM,0,0,0,0,8,0,0,17.005491972 +196,CUP,SUM,0,0,0,0,0,7,109,44.545799017 +196,SPOON,SUM,0,0,0,0,0,18,7,17.2711060047 +196,,SUM,0,0,0,0,8,25,116,78.8223969936 +196,,,,,,,,,, +197,,,,,,,,,, +197,BOWL,SUM,0,0,0,0,8,17,12,20.1240460873 +197,CUP,SUM,0,0,0,0,0,1,11,10.5506410599 +197,SPOON,SUM,0,0,0,0,2,3,1,13.9226257801 +197,,SUM,0,0,0,0,10,21,24,44.5973129272 +197,,,,,,,,,, +198,,,,,,,,,, +198,BOWL,SUM,0,0,0,0,0,2,0,8.7968699932 +198,CUP,SUM,0,0,0,0,0,1,29,18.2039649487 +198,SPOON,SUM,0,0,0,0,0,12,7,18.116245985 +198,,SUM,0,0,0,0,0,15,36,45.1170809269 +198,,,,,,,,,, +199,,,,,,,,,, +199,BOWL,SUM,1,0,1,0,6,4,44,0 +199,CUP,SUM,0,0,0,0,0,3,9,8.4732949734 +199,SPOON,SUM,0,0,0,0,2,3,4,13.6519620419 +199,,SUM,1,0,1,0,8,10,57,22.1252570152 +199,,,,,,,,,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/heur_pr2_new.csv b/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/heur_pr2_new.csv new file mode 100644 index 0000000000..34660e544d --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/heur_pr2_new.csv @@ -0,0 +1,1203 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC, +,,,,,,,,,,, +,,,,,,,,,,, +0,,,,,,,,,,, +0,BOWL,SUM,1,0,1,0,0,27,44,0, +0,CUP,SUM,1,0,1,0,8,12,73,0, +0,SPOON,SUM,0,0,0,0,0,4,17,13.5400369167, +0,,SUM,2,0,2,0,8,43,134,13.5400369167, +0,,,,,,,,,,, +1,,,,,,,,,,, +1,BOWL,SUM,1,0,0,1,0,12,19,0, +1,CUP,SUM,1,0,1,0,0,56,70,0, +1,SPOON,SUM,0,0,0,0,0,3,8,10.8458399773, +1,,SUM,2,0,1,1,0,71,97,10.8458399773, +1,,,,,,,,,,, +2,,,,,,,,,,, +2,BOWL,SUM,1,0,1,0,0,81,40,0, +2,CUP,SUM,1,0,1,0,0,15,11,0, +2,SPOON,SUM,0,0,0,0,0,2,1,10.7030098438, +2,,SUM,2,0,2,0,0,98,52,10.7030098438, +2,,,,,,,,,,, +3,,,,,,,,,,, +3,BOWL,SUM,1,0,0,1,16,10,11,0, +3,CUP,SUM,0,0,0,0,0,2,8,6.3630301952, +3,SPOON,SUM,0,0,0,0,0,11,1,9.8828501701, +3,,SUM,1,0,0,1,16,23,20,16.2458803654, +3,,,,,,,,,,, +4,,,,,,,,,,, +4,BOWL,SUM,1,0,1,0,0,39,44,0, +4,CUP,SUM,1,0,1,0,8,29,11,0, +4,SPOON,SUM,0,0,0,0,0,1,5,10.8044281006, +4,,SUM,2,0,2,0,8,69,60,10.8044281006, +4,,,,,,,,,,, +5,,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,0,1,4,7.7007250786, +5,CUP,SUM,0,0,0,0,0,2,7,6.077999115, +5,SPOON,SUM,1,0,1,0,0,343,0,0, +5,,SUM,1,0,1,0,0,346,11,13.7787241936, +5,,,,,,,,,,, +6,,,,,,,,,,, +6,BOWL,SUM,1,0,1,0,0,14,44,0, +6,CUP,SUM,0,0,0,0,0,3,4,4.4828810692, +6,SPOON,SUM,1,0,1,0,0,13,44,0, +6,,SUM,2,0,2,0,0,30,92,4.4828810692, +6,,,,,,,,,,, +7,,,,,,,,,,, +7,BOWL,SUM,1,0,1,0,0,8,44,0, +7,CUP,SUM,0,0,0,0,0,0,9,4.8672280312, +7,SPOON,SUM,1,0,1,0,0,21,44,0, +7,,SUM,2,0,2,0,0,29,97,4.8672280312, +7,,,,,,,,,,, +8,,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,0,4,12,9.7791581154, +8,CUP,SUM,0,0,0,0,0,8,22,8.3392710686, +8,SPOON,SUM,0,0,0,0,0,2,1,10.1766781807, +8,,SUM,0,0,0,0,0,14,35,28.2951073647, +8,,,,,,,,,,, +9,,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,9,20,10.2779750824, +9,CUP,SUM,0,0,0,0,0,4,9,5.6362390518, +9,SPOON,SUM,0,0,0,0,0,6,2,11.054901123, +9,,SUM,0,0,0,0,0,19,31,26.9691152573, +9,,,,,,,,,,, +10,,,,,,,,,,, +10,BOWL,SUM,1,0,1,0,0,5,44,0, +10,CUP,SUM,0,0,0,0,0,0,8,6.7623419762, +10,SPOON,SUM,0,0,0,0,0,14,3,11.8637588024, +10,,SUM,1,0,1,0,0,19,55,18.6261007786, +10,,,,,,,,,,, +11,,,,,,,,,,, +11,BOWL,SUM,1,0,1,0,0,21,44,0, +11,CUP,SUM,1,1,0,0,24,40,0,0, +11,SPOON,SUM,1,0,1,0,0,10,44,0, +11,,SUM,3,1,2,0,24,71,88,0, +11,,,,,,,,,,, +12,,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,0,8,2,7.5895960331, +12,CUP,SUM,0,0,0,0,0,2,6,5.0006430149, +12,SPOON,SUM,0,0,0,0,0,5,1,10.3595590591, +12,,SUM,0,0,0,0,0,15,9,22.9497981071, +12,,,,,,,,,,, +13,,,,,,,,,,, +13,BOWL,SUM,1,0,1,0,0,15,44,0, +13,CUP,SUM,1,0,1,0,8,5,49,0, +13,SPOON,SUM,0,0,0,0,0,7,31,16.5712828636, +13,,SUM,2,0,2,0,8,27,124,16.5712828636, +13,,,,,,,,,,, +14,,,,,,,,,,, +14,BOWL,SUM,1,0,1,0,8,26,44,0, +14,CUP,SUM,0,0,0,0,16,2,5,12.0677399635, +14,SPOON,SUM,1,0,1,0,0,14,44,0, +14,,SUM,2,0,2,0,24,42,93,12.0677399635, +14,,,,,,,,,,, +15,,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,24,10,29,20.9805870056, +15,CUP,SUM,1,0,1,0,0,9,33,0, +15,SPOON,SUM,1,0,1,0,0,10,44,0, +15,,SUM,2,0,2,0,24,29,106,20.9805870056, +15,,,,,,,,,,, +16,,,,,,,,,,, +16,BOWL,SUM,1,0,1,0,0,24,44,0, +16,CUP,SUM,0,0,0,0,0,0,38,10.8845748901, +16,SPOON,SUM,0,0,0,0,0,1,0,10.3752970695, +16,,SUM,1,0,1,0,0,25,82,21.2598719597, +16,,,,,,,,,,, +17,,,,,,,,,,, +17,BOWL,SUM,1,0,1,0,0,42,40,0, +17,CUP,SUM,0,0,0,0,0,5,3,4.9830751419, +17,SPOON,SUM,0,0,0,0,0,5,0,10.2711548805, +17,,SUM,1,0,1,0,0,52,43,15.2542300224, +17,,,,,,,,,,, +18,,,,,,,,,,, +18,BOWL,SUM,1,1,0,0,96,9,0,0, +18,CUP,SUM,1,0,1,0,0,12,33,0, +18,SPOON,SUM,0,0,0,0,0,4,4,11.0577030182, +18,,SUM,2,1,1,0,96,25,37,11.0577030182, +18,,,,,,,,,,, +19,,,,,,,,,,, +19,BOWL,SUM,1,0,1,0,0,15,44,0, +19,CUP,SUM,0,0,0,0,0,14,6,5.2752361298, +19,SPOON,SUM,0,0,0,0,8,3,9,16.3233239651, +19,,SUM,1,0,1,0,8,32,59,21.5985600948, +19,,,,,,,,,,, +20,,,,,,,,,,, +20,BOWL,SUM,1,0,1,0,0,6,44,0, +20,CUP,SUM,0,0,0,0,0,1,8,5.9818398952, +20,SPOON,SUM,1,0,1,0,0,34,44,0, +20,,SUM,2,0,2,0,0,41,96,5.9818398952, +20,,,,,,,,,,, +21,,,,,,,,,,, +21,BOWL,SUM,1,0,0,1,8,25,47,0, +21,CUP,SUM,0,0,0,0,0,7,29,8.9539978504, +21,SPOON,SUM,0,0,0,0,32,7,0,23.5252997875, +21,,SUM,1,0,0,1,40,39,76,32.4792976379, +21,,,,,,,,,,, +22,,,,,,,,,,, +22,BOWL,SUM,1,0,1,0,32,9,44,0, +22,CUP,SUM,1,0,1,0,0,41,30,0, +22,SPOON,SUM,0,0,0,0,0,2,0,10.1448099613, +22,,SUM,2,0,2,0,32,52,74,10.1448099613, +22,,,,,,,,,,, +23,,,,,,,,,,, +23,BOWL,SUM,1,0,1,0,8,36,40,0, +23,CUP,SUM,0,0,0,0,0,0,6,5.0217819214, +23,SPOON,SUM,0,0,0,0,0,1,0,9.9011011124, +23,,SUM,1,0,1,0,8,37,46,14.9228830338, +23,,,,,,,,,,, +24,,,,,,,,,,, +24,BOWL,SUM,1,0,0,1,0,2,19,0, +24,CUP,SUM,1,0,1,0,0,36,11,0, +24,SPOON,SUM,0,0,0,0,0,0,4,10.447026968, +24,,SUM,2,0,1,1,0,38,34,10.447026968, +24,,,,,,,,,,, +25,,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,0,5,37,13.2130250931, +25,CUP,SUM,1,0,1,0,0,20,33,0, +25,SPOON,SUM,0,0,0,0,0,6,28,15.6164619923, +25,,SUM,1,0,1,0,0,31,98,28.8294870853, +25,,,,,,,,,,, +26,,,,,,,,,,, +26,BOWL,SUM,1,0,1,0,0,23,44,0, +26,CUP,SUM,0,0,0,0,0,7,10,8.5528209209, +26,SPOON,SUM,0,0,0,0,0,0,6,12.0918300152, +26,,SUM,1,0,1,0,0,30,60,20.6446509361, +26,,,,,,,,,,, +27,,,,,,,,,,, +27,BOWL,SUM,1,0,1,0,0,14,44,0, +27,CUP,SUM,0,0,0,0,0,1,4,5.0635719299, +27,SPOON,SUM,1,0,1,0,0,10,44,0, +27,,SUM,2,0,2,0,0,25,92,5.0635719299, +27,,,,,,,,,,, +28,,,,,,,,,,, +28,BOWL,SUM,1,0,0,1,0,3,11,0, +28,CUP,SUM,1,0,1,0,0,20,11,0, +28,SPOON,SUM,0,0,0,0,8,1,0,14.4542222023, +28,,SUM,2,0,1,1,8,24,22,14.4542222023, +28,,,,,,,,,,, +29,,,,,,,,,,, +29,BOWL,SUM,1,0,1,0,0,10,44,0, +29,CUP,SUM,1,0,1,0,8,10,81,0, +29,SPOON,SUM,1,0,1,0,0,6,44,0, +29,,SUM,3,0,3,0,8,26,169,0, +29,,,,,,,,,,, +30,,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,0,0,4,8.610599041, +30,CUP,SUM,0,0,0,0,0,10,6,5.627518177, +30,SPOON,SUM,0,0,0,0,0,3,11,12.5609481335, +30,,SUM,0,0,0,0,0,13,21,26.7990653515, +30,,,,,,,,,,, +31,,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,8,5,40,21.3496539593, +31,CUP,SUM,1,0,1,0,0,72,45,0, +31,SPOON,SUM,0,0,0,0,0,2,24,16.9121580124, +31,,SUM,1,0,1,0,8,79,109,38.2618119717, +31,,,,,,,,,,, +32,,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,0,17,26,13.7097661495, +32,CUP,SUM,0,0,0,0,16,7,7,15.8343069553, +32,SPOON,SUM,1,0,1,0,0,10,44,0, +32,,SUM,1,0,1,0,16,34,77,29.5440731049, +32,,,,,,,,,,, +33,,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,3,9,11.7265059948, +33,CUP,SUM,0,0,0,0,0,5,4,6.0797560215, +33,SPOON,SUM,0,0,0,0,8,7,34,22.4832179546, +33,,SUM,0,0,0,0,8,15,47,40.2894799709, +33,,,,,,,,,,, +34,,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,0,11,10,9.5825929642, +34,CUP,SUM,0,0,0,0,0,1,7,7.2674689293, +34,SPOON,SUM,0,0,0,0,16,6,4,22.1296849251, +34,,SUM,0,0,0,0,16,18,21,38.9797468185, +34,,,,,,,,,,, +35,,,,,,,,,,, +35,BOWL,SUM,1,0,0,1,8,2,13,0, +35,CUP,SUM,1,0,1,0,8,16,33,0, +35,SPOON,SUM,0,0,0,0,0,0,1,11.4906909466, +35,,SUM,2,0,1,1,16,18,47,11.4906909466, +35,,,,,,,,,,, +36,,,,,,,,,,, +36,BOWL,SUM,1,0,1,0,0,26,44,0, +36,CUP,SUM,0,0,0,0,0,0,3,6.8225240707, +36,SPOON,SUM,1,0,1,0,0,11,44,0, +36,,SUM,2,0,2,0,0,37,91,6.8225240707, +36,,,,,,,,,,, +37,,,,,,,,,,, +37,BOWL,SUM,1,0,1,0,4,8,44,0, +37,CUP,SUM,0,0,0,0,0,2,6,7.3185169697, +37,SPOON,SUM,1,0,1,0,16,8,44,0, +37,,SUM,2,0,2,0,20,18,94,7.3185169697, +37,,,,,,,,,,, +38,,,,,,,,,,, +38,BOWL,SUM,1,0,1,0,0,10,44,0, +38,CUP,SUM,0,0,0,0,24,4,11,24.1062800884, +38,SPOON,SUM,1,0,1,0,0,15,44,0, +38,,SUM,2,0,2,0,24,29,99,24.1062800884, +38,,,,,,,,,,, +39,,,,,,,,,,, +39,BOWL,SUM,1,0,0,1,0,4,11,0, +39,CUP,SUM,0,0,0,0,8,64,12,38.4845230579, +39,SPOON,SUM,0,0,0,0,0,2,4,11.5273220539, +39,,SUM,1,0,0,1,8,70,27,50.0118451118, +39,,,,,,,,,,, +40,,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,0,3,18,12.0510649681, +40,CUP,SUM,0,0,0,0,16,3,4,15.7503910065, +40,SPOON,SUM,1,1,0,0,8,71,0,0, +40,,SUM,1,1,0,0,24,77,22,27.8014559746, +40,,,,,,,,,,, +41,,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,8,9,13,14.842140913, +41,CUP,SUM,1,0,1,0,12,13,11,0, +41,SPOON,SUM,0,0,0,0,48,6,12,45.0321519375, +41,,SUM,1,0,1,0,68,28,36,59.8742928505, +41,,,,,,,,,,, +42,,,,,,,,,,, +42,BOWL,SUM,1,0,0,1,32,9,11,0, +42,CUP,SUM,0,0,0,0,0,0,4,7.368407011, +42,SPOON,SUM,1,0,1,0,8,15,44,0, +42,,SUM,2,0,1,1,40,24,59,7.368407011, +42,,,,,,,,,,, +43,,,,,,,,,,, +43,BOWL,SUM,1,0,1,0,0,12,44,0, +43,CUP,SUM,0,0,0,0,0,0,6,6.9356291294, +43,SPOON,SUM,0,0,0,0,0,17,16,15.2582910061, +43,,SUM,1,0,1,0,0,29,66,22.1939201355, +43,,,,,,,,,,, +44,,,,,,,,,,, +44,BOWL,SUM,1,0,0,1,16,4,11,0, +44,CUP,SUM,0,0,0,0,0,3,9,8.5127358437, +44,SPOON,SUM,1,0,1,0,0,24,44,0, +44,,SUM,2,0,1,1,16,31,64,8.5127358437, +44,,,,,,,,,,, +45,,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,0,0,8,12.8065440655, +45,CUP,SUM,0,0,0,0,0,3,4,7.3045499325, +45,SPOON,SUM,1,0,1,0,0,157,24,0, +45,,SUM,1,0,1,0,0,160,36,20.111093998, +45,,,,,,,,,,, +46,,,,,,,,,,, +46,BOWL,SUM,1,0,0,1,0,2,11,0, +46,CUP,SUM,1,1,0,0,8,71,0,0, +46,SPOON,SUM,1,0,1,0,56,13,44,0, +46,,SUM,3,1,1,1,64,86,55,0, +46,,,,,,,,,,, +47,,,,,,,,,,, +47,BOWL,SUM,1,0,1,0,0,26,44,0, +47,CUP,SUM,1,0,1,0,8,13,43,0, +47,SPOON,SUM,0,0,0,0,0,1,8,13.2460870743, +47,,SUM,2,0,2,0,8,40,95,13.2460870743, +47,,,,,,,,,,, +48,,,,,,,,,,, +48,BOWL,SUM,1,0,1,0,0,4,44,0, +48,CUP,SUM,1,0,1,0,0,10,33,0, +48,SPOON,SUM,1,1,0,0,8,41,0,0, +48,,SUM,3,1,2,0,8,55,77,0, +48,,,,,,,,,,, +49,,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,0,2,14,12.1834981441, +49,CUP,SUM,0,0,0,0,0,3,28,11.2227091789, +49,SPOON,SUM,1,0,1,0,0,18,44,0, +49,,SUM,1,0,1,0,0,23,86,23.4062073231, +49,,,,,,,,,,, +50,,,,,,,,,,, +50,BOWL,SUM,1,0,1,0,8,9,44,0, +50,CUP,SUM,0,0,0,0,0,0,6,4.5915720463, +50,SPOON,SUM,0,0,0,0,0,7,29,15.854612112, +50,,SUM,1,0,1,0,8,16,79,20.4461841583, +50,,,,,,,,,,, +51,,,,,,,,,,, +51,BOWL,SUM,1,0,1,0,0,11,44,0, +51,CUP,SUM,0,0,0,0,60,11,24,32.5564930439, +51,SPOON,SUM,1,1,0,0,8,71,0,0, +51,,SUM,2,1,1,0,68,93,68,32.5564930439, +51,,,,,,,,,,, +52,,,,,,,,,,, +52,BOWL,SUM,1,0,1,0,0,28,44,0, +52,CUP,SUM,0,0,0,0,0,0,2,4.6323480606, +52,SPOON,SUM,0,0,0,0,0,4,20,13.4446179867, +52,,SUM,1,0,1,0,0,32,66,18.0769660473, +52,,,,,,,,,,, +53,,,,,,,,,,, +53,BOWL,SUM,1,0,1,0,0,8,44,0, +53,CUP,SUM,0,0,0,0,16,5,7,12.6101939678, +53,SPOON,SUM,0,0,0,0,0,2,0,10.2873198986, +53,,SUM,1,0,1,0,16,15,51,22.8975138664, +53,,,,,,,,,,, +54,,,,,,,,,,, +54,BOWL,SUM,1,0,1,0,0,341,0,0, +54,CUP,SUM,0,0,0,0,0,1,3,4.9721260071, +54,SPOON,SUM,0,0,0,0,0,3,16,12.8871209621, +54,,SUM,1,0,1,0,0,345,19,17.8592469692, +54,,,,,,,,,,, +55,,,,,,,,,,, +55,BOWL,SUM,1,0,1,0,0,24,44,0, +55,CUP,SUM,1,0,1,0,16,11,33,0, +55,SPOON,SUM,0,0,0,0,0,3,2,11.1226968765, +55,,SUM,2,0,2,0,16,38,79,11.1226968765, +55,,,,,,,,,,, +56,,,,,,,,,,, +56,BOWL,SUM,1,0,1,0,0,42,40,0, +56,CUP,SUM,0,0,0,0,0,0,9,4.9481818676, +56,SPOON,SUM,0,0,0,0,0,7,0,10.2461819649, +56,,SUM,1,0,1,0,0,49,49,15.1943638325, +56,,,,,,,,,,, +57,,,,,,,,,,, +57,BOWL,SUM,1,0,1,0,0,13,44,0, +57,CUP,SUM,0,0,0,0,8,6,8,9.9500939846, +57,SPOON,SUM,0,0,0,0,0,1,9,11.6489808559, +57,,SUM,1,0,1,0,8,20,61,21.5990748405, +57,,,,,,,,,,, +58,,,,,,,,,,, +58,BOWL,SUM,1,0,1,0,8,16,44,0, +58,CUP,SUM,0,0,0,0,32,5,18,21.36855793, +58,SPOON,SUM,0,0,0,0,0,4,22,15.7651488781, +58,,SUM,1,0,1,0,40,25,84,37.1337068081, +58,,,,,,,,,,, +59,,,,,,,,,,, +59,BOWL,SUM,0,0,0,0,0,15,17,10.7657368183, +59,CUP,SUM,1,0,0,1,0,5,36,0, +59,SPOON,SUM,0,0,0,0,14,9,34,23.7366280556, +59,,SUM,1,0,0,1,14,29,87,34.5023648739, +59,,,,,,,,,,, +60,,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,8,28,3,12.7926268578, +60,CUP,SUM,1,1,0,0,88,7,0,0, +60,SPOON,SUM,1,0,1,0,0,56,40,0, +60,,SUM,2,1,1,0,96,91,43,12.7926268578, +60,,,,,,,,,,, +61,,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,0,5,21,11.2028241158, +61,CUP,SUM,0,0,0,0,0,6,14,7.0317471027, +61,SPOON,SUM,0,0,0,0,0,2,0,10.2939629555, +61,,SUM,0,0,0,0,0,13,35,28.528534174, +61,,,,,,,,,,, +62,,,,,,,,,,, +62,BOWL,SUM,1,0,1,0,16,7,44,0, +62,CUP,SUM,1,0,0,1,0,3,11,0, +62,SPOON,SUM,1,0,1,0,0,13,44,0, +62,,SUM,3,0,2,1,16,23,99,0, +62,,,,,,,,,,, +63,,,,,,,,,,, +63,BOWL,SUM,0,0,0,0,0,6,37,14.1921870708, +63,CUP,SUM,1,0,0,1,0,5,17,0, +63,SPOON,SUM,0,0,0,0,0,1,7,12.4828801155, +63,,SUM,1,0,0,1,0,12,61,26.6750671864, +63,,,,,,,,,,, +64,,,,,,,,,,, +64,BOWL,SUM,0,0,0,0,0,9,50,17.8013710976, +64,CUP,SUM,0,0,0,0,0,7,14,7.0404908657, +64,SPOON,SUM,0,0,0,0,0,1,0,10.6422410011, +64,,SUM,0,0,0,0,0,17,64,35.4841029644, +64,,,,,,,,,,, +65,,,,,,,,,,, +65,BOWL,SUM,0,0,0,0,0,7,42,16.8008699417, +65,CUP,SUM,1,0,1,0,0,25,33,0, +65,SPOON,SUM,0,0,0,0,8,14,24,19.4968969822, +65,,SUM,1,0,1,0,8,46,99,36.2977669239, +65,,,,,,,,,,, +66,,,,,,,,,,, +66,BOWL,SUM,1,0,1,0,16,9,44,0, +66,CUP,SUM,0,0,0,0,0,1,13,8.4715030193, +66,SPOON,SUM,1,0,1,0,0,14,44,0, +66,,SUM,2,0,2,0,16,24,101,8.4715030193, +66,,,,,,,,,,, +67,,,,,,,,,,, +67,BOWL,SUM,0,0,0,0,0,10,14,13.3738029003, +67,CUP,SUM,0,0,0,0,16,6,16,17.3433208466, +67,SPOON,SUM,0,0,0,0,0,16,13,14.493491888, +67,,SUM,0,0,0,0,16,32,43,45.2106156349, +67,,,,,,,,,,, +68,,,,,,,,,,, +68,BOWL,SUM,0,0,0,0,0,0,5,8.5538840294, +68,CUP,SUM,0,0,0,0,0,1,5,6.1293330193, +68,SPOON,SUM,1,0,1,0,0,9,44,0, +68,,SUM,1,0,1,0,0,10,54,14.6832170486, +68,,,,,,,,,,, +69,,,,,,,,,,, +69,BOWL,SUM,1,0,0,1,8,5,11,0, +69,CUP,SUM,0,0,0,0,16,14,32,23.3946518898, +69,SPOON,SUM,0,0,0,0,0,7,19,15.6025791168, +69,,SUM,1,0,0,1,24,26,62,38.9972310066, +69,,,,,,,,,,, +70,,,,,,,,,,, +70,BOWL,SUM,0,0,0,0,0,6,17,13.3027000427, +70,CUP,SUM,1,0,1,0,0,19,11,0, +70,SPOON,SUM,0,0,0,0,0,0,1,12.5880019665, +70,,SUM,1,0,1,0,0,25,29,25.8907020092, +70,,,,,,,,,,, +71,,,,,,,,,,, +71,BOWL,SUM,1,0,1,0,0,14,44,0, +71,CUP,SUM,0,0,0,0,32,6,5,26.9268159866, +71,SPOON,SUM,0,0,0,0,0,6,6,13.432063818, +71,,SUM,1,0,1,0,32,26,55,40.3588798046, +71,,,,,,,,,,, +72,,,,,,,,,,, +72,BOWL,SUM,0,0,0,0,0,5,39,15.6998889446, +72,CUP,SUM,0,0,0,0,0,2,3,6.3949699402, +72,SPOON,SUM,1,0,1,0,0,13,44,0, +72,,SUM,1,0,1,0,0,20,86,22.0948588848, +72,,,,,,,,,,, +73,,,,,,,,,,, +73,BOWL,SUM,1,1,0,0,24,41,0,0, +73,CUP,SUM,1,0,1,0,0,15,77,0, +73,SPOON,SUM,0,0,0,0,0,9,41,19.7721829414, +73,,SUM,2,1,1,0,24,65,118,19.7721829414, +73,,,,,,,,,,, +74,,,,,,,,,,, +74,BOWL,SUM,1,0,1,0,8,20,44,0, +74,CUP,SUM,0,0,0,0,0,6,7,8.0530469418, +74,SPOON,SUM,0,0,0,0,0,6,24,17.7175290585, +74,,SUM,1,0,1,0,8,32,75,25.7705760002, +74,,,,,,,,,,, +75,,,,,,,,,,, +75,BOWL,SUM,1,0,1,0,0,12,44,0, +75,CUP,SUM,0,0,0,0,0,1,8,8.8516659737, +75,SPOON,SUM,0,0,0,0,0,2,2,13.4156200886, +75,,SUM,1,0,1,0,0,15,54,22.2672860622, +75,,,,,,,,,,, +76,,,,,,,,,,, +76,BOWL,SUM,1,0,0,1,8,1,11,0, +76,CUP,SUM,0,0,0,0,0,9,8,6.3222360611, +76,SPOON,SUM,1,0,1,0,0,9,44,0, +76,,SUM,2,0,1,1,8,19,63,6.3222360611, +76,,,,,,,,,,, +77,,,,,,,,,,, +77,BOWL,SUM,1,0,1,0,0,19,44,0, +77,CUP,SUM,0,0,0,0,0,6,5,7.5636029243, +77,SPOON,SUM,0,0,0,0,0,0,2,12.3398170471, +77,,SUM,1,0,1,0,0,25,51,19.9034199715, +77,,,,,,,,,,, +78,,,,,,,,,,, +78,BOWL,SUM,1,0,0,1,0,16,19,0, +78,CUP,SUM,0,0,0,0,0,4,11,6.5302820206, +78,SPOON,SUM,0,0,0,0,0,4,20,15.7602770329, +78,,SUM,1,0,0,1,0,24,50,22.2905590534, +78,,,,,,,,,,, +79,,,,,,,,,,, +79,BOWL,SUM,1,0,1,0,0,15,44,0, +79,CUP,SUM,0,0,0,0,8,1,23,13.3667681217, +79,SPOON,SUM,0,0,0,0,0,5,1,12.1156349182, +79,,SUM,1,0,1,0,8,21,68,25.4824030399, +79,,,,,,,,,,, +80,,,,,,,,,,, +80,BOWL,SUM,1,0,1,0,0,12,44,0, +80,CUP,SUM,1,0,1,0,8,13,77,0, +80,SPOON,SUM,0,0,0,0,0,6,44,20.4522180557, +80,,SUM,2,0,2,0,8,31,165,20.4522180557, +80,,,,,,,,,,, +81,,,,,,,,,,, +81,BOWL,SUM,0,0,0,0,8,5,5,15.7806241512, +81,CUP,SUM,1,0,1,0,8,7,33,0, +81,SPOON,SUM,0,0,0,0,4,3,17,17.670552969, +81,,SUM,1,0,1,0,20,15,55,33.4511771202, +81,,,,,,,,,,, +82,,,,,,,,,,, +82,BOWL,SUM,1,0,1,0,0,37,40,0, +82,CUP,SUM,0,0,0,0,8,2,10,14.8335299492, +82,SPOON,SUM,0,0,0,0,0,2,6,15.0019922256, +82,,SUM,1,0,1,0,8,41,56,29.8355221748, +82,,,,,,,,,,, +83,,,,,,,,,,, +83,BOWL,SUM,0,0,0,0,12,5,21,21.1763129234, +83,CUP,SUM,1,1,0,0,8,27,0,0, +83,SPOON,SUM,0,0,0,0,0,5,2,11.7200109959, +83,,SUM,1,1,0,0,20,37,23,32.8963239193, +83,,,,,,,,,,, +84,,,,,,,,,,, +84,BOWL,SUM,0,0,0,0,0,1,16,12.4908030033, +84,CUP,SUM,0,0,0,0,0,0,6,5.8719360828, +84,SPOON,SUM,0,0,0,0,0,5,0,11.4793810844, +84,,SUM,0,0,0,0,0,6,22,29.8421201706, +84,,,,,,,,,,, +85,,,,,,,,,,, +85,BOWL,SUM,1,0,0,1,8,2,15,0, +85,CUP,SUM,1,0,1,0,0,14,77,0, +85,SPOON,SUM,1,0,1,0,0,341,0,0, +85,,SUM,3,0,2,1,8,357,92,0, +85,,,,,,,,,,, +86,,,,,,,,,,, +86,BOWL,SUM,0,0,0,0,0,2,11,9.8810679913, +86,CUP,SUM,1,0,1,0,24,21,17,0, +86,SPOON,SUM,0,0,0,0,8,16,2,17.6317398548, +86,,SUM,1,0,1,0,32,39,30,27.5128078461, +86,,,,,,,,,,, +87,,,,,,,,,,, +87,BOWL,SUM,1,1,0,0,16,40,0,0, +87,CUP,SUM,0,0,0,0,0,5,17,8.2259118557, +87,SPOON,SUM,0,0,0,0,40,9,7,37.3156759739, +87,,SUM,1,1,0,0,56,54,24,45.5415878296, +87,,,,,,,,,,, +88,,,,,,,,,,, +88,BOWL,SUM,0,0,0,0,0,9,9,12.142663002, +88,CUP,SUM,0,0,0,0,0,1,6,6.2985889912, +88,SPOON,SUM,0,0,0,0,64,7,12,52.8196129799, +88,,SUM,0,0,0,0,64,17,27,71.2608649731, +88,,,,,,,,,,, +89,,,,,,,,,,, +89,BOWL,SUM,0,0,0,0,0,16,37,16.5440459251, +89,CUP,SUM,1,0,0,1,0,1,17,0, +89,SPOON,SUM,0,0,0,0,16,0,1,24.4949471951, +89,,SUM,1,0,0,1,16,17,55,41.0389931202, +89,,,,,,,,,,, +90,,,,,,,,,,, +90,BOWL,SUM,0,0,0,0,0,3,5,11.7328238487, +90,CUP,SUM,0,0,0,0,0,17,12,11.0472819805, +90,SPOON,SUM,1,0,1,0,8,20,44,0, +90,,SUM,1,0,1,0,8,40,61,22.7801058292, +90,,,,,,,,,,, +91,,,,,,,,,,, +91,BOWL,SUM,0,0,0,0,0,13,41,16.8758180141, +91,CUP,SUM,0,0,0,0,16,51,10,33.8195250034, +91,SPOON,SUM,0,0,0,0,0,2,5,13.7576839924, +91,,SUM,0,0,0,0,16,66,56,64.45302701, +91,,,,,,,,,,, +92,,,,,,,,,,, +92,BOWL,SUM,1,0,1,0,0,13,44,0, +92,CUP,SUM,1,0,1,0,16,8,11,0, +92,SPOON,SUM,0,0,0,0,0,10,17,15.3774459362, +92,,SUM,2,0,2,0,16,31,72,15.3774459362, +92,,,,,,,,,,, +93,,,,,,,,,,, +93,BOWL,SUM,0,0,0,0,0,3,8,12.3671450615, +93,CUP,SUM,0,0,0,0,0,13,6,8.6578369141, +93,SPOON,SUM,0,0,0,0,8,3,18,20.6980750561, +93,,SUM,0,0,0,0,8,19,32,41.7230570316, +93,,,,,,,,,,, +94,,,,,,,,,,, +94,BOWL,SUM,0,0,0,0,0,2,3,9.5711569786, +94,CUP,SUM,1,0,1,0,8,9,33,0, +94,SPOON,SUM,0,0,0,0,16,1,1,24.3515269756, +94,,SUM,1,0,1,0,24,12,37,33.9226839542, +94,,,,,,,,,,, +95,,,,,,,,,,, +95,BOWL,SUM,0,0,0,0,0,4,31,16.805629015, +95,CUP,SUM,1,0,1,0,0,27,33,0, +95,SPOON,SUM,0,0,0,0,0,7,24,16.2626509666, +95,,SUM,1,0,1,0,0,38,88,33.0682799816, +95,,,,,,,,,,, +96,,,,,,,,,,, +96,BOWL,SUM,1,0,1,0,0,12,44,0, +96,CUP,SUM,0,0,0,0,16,1,7,17.8180291653, +96,SPOON,SUM,0,0,0,0,0,1,0,11.880510807, +96,,SUM,1,0,1,0,16,14,51,29.6985399723, +96,,,,,,,,,,, +97,,,,,,,,,,, +97,BOWL,SUM,0,0,0,0,0,1,1,8.7802970409, +97,CUP,SUM,0,0,0,0,0,6,25,12.5315921307, +97,SPOON,SUM,1,1,0,0,0,42,0,0, +97,,SUM,1,1,0,0,0,49,26,21.3118891716, +97,,,,,,,,,,, +98,,,,,,,,,,, +98,BOWL,SUM,0,0,0,0,0,4,13,9.7245550156, +98,CUP,SUM,0,0,0,0,0,2,2,6.2576959133, +98,SPOON,SUM,1,0,1,0,0,27,44,0, +98,,SUM,1,0,1,0,0,33,59,15.9822509289, +98,,,,,,,,,,, +99,,,,,,,,,,, +99,BOWL,SUM,1,0,1,0,0,27,44,0, +99,CUP,SUM,1,0,1,0,8,12,73,0, +99,SPOON,SUM,0,0,0,0,0,4,17,13.7426280975, +99,,SUM,2,0,2,0,8,43,134,13.7426280975, +99,,,,,,,,,,, +100,,,,,,,,,,, +100,BOWL,SUM,0,0,0,0,0,3,20,11.8010160923, +100,CUP,SUM,1,0,1,0,0,7,11,0, +100,SPOON,SUM,0,0,0,0,16,6,1,24.7989139557, +100,,SUM,1,0,1,0,16,16,32,36.599930048, +100,,,,,,,,,,, +101,,,,,,,,,,, +101,BOWL,SUM,1,0,0,1,0,12,19,0, +101,CUP,SUM,1,0,1,0,0,56,70,0, +101,SPOON,SUM,0,0,0,0,0,3,8,11.4359250069, +101,,SUM,2,0,1,1,0,71,97,11.4359250069, +101,,,,,,,,,,, +102,,,,,,,,,,, +102,BOWL,SUM,1,0,1,0,0,81,40,0, +102,CUP,SUM,1,0,1,0,0,15,11,0, +102,SPOON,SUM,0,0,0,0,0,2,1,10.3460469246, +102,,SUM,2,0,2,0,0,98,52,10.3460469246, +102,,,,,,,,,,, +103,,,,,,,,,,, +103,BOWL,SUM,1,0,0,1,16,10,11,0, +103,CUP,SUM,0,0,0,0,0,2,8,6.3846328259, +103,SPOON,SUM,0,0,0,0,0,11,1,9.9385490417, +103,,SUM,1,0,0,1,16,23,20,16.3231818676, +103,,,,,,,,,,, +104,,,,,,,,,,, +104,BOWL,SUM,1,0,1,0,0,39,44,0, +104,CUP,SUM,1,0,1,0,8,29,11,0, +104,SPOON,SUM,0,0,0,0,0,1,5,10.4719629288, +104,,SUM,2,0,2,0,8,69,60,10.4719629288, +104,,,,,,,,,,, +105,,,,,,,,,,, +105,BOWL,SUM,0,0,0,0,0,1,4,7.6709680557, +105,CUP,SUM,0,0,0,0,0,2,7,6.2186059952, +105,SPOON,SUM,1,0,1,0,0,343,0,0, +105,,SUM,1,0,1,0,0,346,11,13.8895740509, +105,,,,,,,,,,, +106,,,,,,,,,,, +106,BOWL,SUM,1,0,1,0,0,14,44,0, +106,CUP,SUM,0,0,0,0,0,3,4,4.4082040787, +106,SPOON,SUM,1,0,1,0,0,13,44,0, +106,,SUM,2,0,2,0,0,30,92,4.4082040787, +106,,,,,,,,,,, +107,,,,,,,,,,, +107,BOWL,SUM,1,0,1,0,0,8,44,0, +107,CUP,SUM,0,0,0,0,0,0,9,4.7959961891, +107,SPOON,SUM,1,0,1,0,0,21,44,0, +107,,SUM,2,0,2,0,0,29,97,4.7959961891, +107,,,,,,,,,,, +108,,,,,,,,,,, +108,BOWL,SUM,0,0,0,0,0,4,12,9.5334329605, +108,CUP,SUM,0,0,0,0,0,8,22,8.4405250549, +108,SPOON,SUM,0,0,0,0,0,2,1,9.9288349152, +108,,SUM,0,0,0,0,0,14,35,27.9027929306, +108,,,,,,,,,,, +109,,,,,,,,,,, +109,BOWL,SUM,0,0,0,0,0,9,20,10.1935310364, +109,CUP,SUM,0,0,0,0,0,4,9,5.6742899418, +109,SPOON,SUM,0,0,0,0,0,6,2,10.6187880039, +109,,SUM,0,0,0,0,0,19,31,26.4866089821, +109,,,,,,,,,,, +110,,,,,,,,,,, +110,BOWL,SUM,1,0,1,0,0,5,44,0, +110,CUP,SUM,0,0,0,0,0,0,8,6.6443140507, +110,SPOON,SUM,0,0,0,0,0,14,3,11.3886129856, +110,,SUM,1,0,1,0,0,19,55,18.0329270363, +110,,,,,,,,,,, +111,,,,,,,,,,, +111,BOWL,SUM,1,0,1,0,0,21,44,0, +111,CUP,SUM,1,1,0,0,24,40,0,0, +111,SPOON,SUM,1,0,1,0,0,10,44,0, +111,,SUM,3,1,2,0,24,71,88,0, +111,,,,,,,,,,, +112,,,,,,,,,,, +112,BOWL,SUM,0,0,0,0,0,8,2,7.2476820946, +112,CUP,SUM,0,0,0,0,0,2,6,5.13134408, +112,SPOON,SUM,0,0,0,0,0,5,1,9.9607899189, +112,,SUM,0,0,0,0,0,15,9,22.3398160934, +112,,,,,,,,,,, +113,,,,,,,,,,, +113,BOWL,SUM,1,0,1,0,0,15,44,0, +113,CUP,SUM,1,0,1,0,8,5,49,0, +113,SPOON,SUM,0,0,0,0,0,7,31,16.161452055, +113,,SUM,2,0,2,0,8,27,124,16.161452055, +113,,,,,,,,,,, +114,,,,,,,,,,, +114,BOWL,SUM,1,0,1,0,8,26,44,0, +114,CUP,SUM,0,0,0,0,16,2,5,12.0059139729, +114,SPOON,SUM,1,0,1,0,0,14,44,0, +114,,SUM,2,0,2,0,24,42,93,12.0059139729, +114,,,,,,,,,,, +115,,,,,,,,,,, +115,BOWL,SUM,0,0,0,0,24,10,29,21.0402109623, +115,CUP,SUM,1,0,1,0,0,9,33,0, +115,SPOON,SUM,1,0,1,0,0,10,44,0, +115,,SUM,2,0,2,0,24,29,106,21.0402109623, +115,,,,,,,,,,, +116,,,,,,,,,,, +116,BOWL,SUM,1,0,1,0,0,24,44,0, +116,CUP,SUM,0,0,0,0,0,0,38,10.7499389648, +116,SPOON,SUM,0,0,0,0,0,1,0,9.9788239002, +116,,SUM,1,0,1,0,0,25,82,20.7287628651, +116,,,,,,,,,,, +117,,,,,,,,,,, +117,BOWL,SUM,1,0,1,0,0,42,40,0, +117,CUP,SUM,0,0,0,0,0,5,3,4.9641079903, +117,SPOON,SUM,0,0,0,0,0,5,0,9.9034800529, +117,,SUM,1,0,1,0,0,52,43,14.8675880432, +117,,,,,,,,,,, +118,,,,,,,,,,, +118,BOWL,SUM,1,1,0,0,96,9,0,0, +118,CUP,SUM,1,0,1,0,0,12,33,0, +118,SPOON,SUM,0,0,0,0,0,4,4,10.6765151024, +118,,SUM,2,1,1,0,96,25,37,10.6765151024, +118,,,,,,,,,,, +119,,,,,,,,,,, +119,BOWL,SUM,1,0,1,0,0,15,44,0, +119,CUP,SUM,0,0,0,0,0,14,6,5.4586949348, +119,SPOON,SUM,0,0,0,0,8,3,9,16.0127439499, +119,,SUM,1,0,1,0,8,32,59,21.4714388847, +119,,,,,,,,,,, +120,,,,,,,,,,, +120,BOWL,SUM,1,0,1,0,0,6,44,0, +120,CUP,SUM,0,0,0,0,0,1,8,6.1562922001, +120,SPOON,SUM,1,0,1,0,0,34,44,0, +120,,SUM,2,0,2,0,0,41,96,6.1562922001, +120,,,,,,,,,,, +121,,,,,,,,,,, +121,BOWL,SUM,1,0,0,1,8,25,47,0, +121,CUP,SUM,0,0,0,0,0,7,29,8.6942539215, +121,SPOON,SUM,0,0,0,0,32,7,0,22.842648983, +121,,SUM,1,0,0,1,40,39,76,31.5369029045, +121,,,,,,,,,,, +122,,,,,,,,,,, +122,BOWL,SUM,1,0,1,0,32,9,44,0, +122,CUP,SUM,1,0,1,0,0,41,30,0, +122,SPOON,SUM,0,0,0,0,0,2,0,10.0144908428, +122,,SUM,2,0,2,0,32,52,74,10.0144908428, +122,,,,,,,,,,, +123,,,,,,,,,,, +123,BOWL,SUM,1,0,1,0,8,36,40,0, +123,CUP,SUM,0,0,0,0,0,0,6,4.5151400566, +123,SPOON,SUM,0,0,0,0,0,1,0,9.7148361206, +123,,SUM,1,0,1,0,8,37,46,14.2299761772, +123,,,,,,,,,,, +124,,,,,,,,,,, +124,BOWL,SUM,1,0,0,1,0,2,19,0, +124,CUP,SUM,1,0,1,0,0,36,11,0, +124,SPOON,SUM,0,0,0,0,0,0,4,10.4653279781, +124,,SUM,2,0,1,1,0,38,34,10.4653279781, +124,,,,,,,,,,, +125,,,,,,,,,,, +125,BOWL,SUM,0,0,0,0,0,5,37,13.6137499809, +125,CUP,SUM,1,0,1,0,0,20,33,0, +125,SPOON,SUM,0,0,0,0,0,6,28,15.4622981548, +125,,SUM,1,0,1,0,0,31,98,29.0760481358, +125,,,,,,,,,,, +126,,,,,,,,,,, +126,BOWL,SUM,1,0,1,0,0,23,44,0, +126,CUP,SUM,0,0,0,0,0,7,10,8.4861087799, +126,SPOON,SUM,0,0,0,0,0,0,6,11.4946870804, +126,,SUM,1,0,1,0,0,30,60,19.9807958603, +126,,,,,,,,,,, +127,,,,,,,,,,, +127,BOWL,SUM,1,0,1,0,0,14,44,0, +127,CUP,SUM,0,0,0,0,0,1,4,5.0686948299, +127,SPOON,SUM,1,0,1,0,0,10,44,0, +127,,SUM,2,0,2,0,0,25,92,5.0686948299, +127,,,,,,,,,,, +128,,,,,,,,,,, +128,BOWL,SUM,1,0,0,1,0,3,11,0, +128,CUP,SUM,1,0,1,0,0,20,11,0, +128,SPOON,SUM,0,0,0,0,8,1,0,14.1841220856, +128,,SUM,2,0,1,1,8,24,22,14.1841220856, +128,,,,,,,,,,, +129,,,,,,,,,,, +129,BOWL,SUM,1,0,1,0,0,10,44,0, +129,CUP,SUM,1,0,1,0,8,10,81,0, +129,SPOON,SUM,1,0,1,0,0,6,44,0, +129,,SUM,3,0,3,0,8,26,169,0, +129,,,,,,,,,,, +130,,,,,,,,,,, +130,BOWL,SUM,0,0,0,0,0,0,4,8.6438801289, +130,CUP,SUM,0,0,0,0,0,10,6,5.2915380001, +130,SPOON,SUM,0,0,0,0,0,3,11,13.3512639999, +130,,SUM,0,0,0,0,0,13,21,27.2866821289, +130,,,,,,,,,,, +131,,,,,,,,,,, +131,BOWL,SUM,0,0,0,0,8,5,40,20.4245080948, +131,CUP,SUM,1,0,1,0,0,72,45,0, +131,SPOON,SUM,0,0,0,0,0,2,24,15.6421468258, +131,,SUM,1,0,1,0,8,79,109,36.0666549206, +131,,,,,,,,,,, +132,,,,,,,,,,, +132,BOWL,SUM,0,0,0,0,0,17,26,13.43572402, +132,CUP,SUM,0,0,0,0,16,7,7,14.698168993, +132,SPOON,SUM,1,0,1,0,0,10,44,0, +132,,SUM,1,0,1,0,16,34,77,28.133893013, +132,,,,,,,,,,, +133,,,,,,,,,,, +133,BOWL,,,,,,,,,, +133,CUP,BOWL,SUM,0,0,0,0,0,3,20,11.8010160923 +133,SPOON,CUP,SUM,1,0,1,0,0,7,11,0 +133,,SPOON,SUM,0,0,0,0,16,6,1,24.7989139557 +133,,,SUM,1,0,1,0,16,16,32,36.599930048 +134,,,,,,,,,,, +134,BOWL,SUM,0,0,0,0,0,11,10,9.5188651085, +134,CUP,SUM,0,0,0,0,0,1,7,7.6647639275, +134,SPOON,SUM,0,0,0,0,16,6,4,19.6616859436, +134,,SUM,0,0,0,0,16,18,21,36.8453149796, +134,,,,,,,,,,, +135,,,,,,,,,,, +135,BOWL,SUM,1,0,0,1,8,2,13,0, +135,CUP,SUM,1,0,1,0,8,16,33,0, +135,SPOON,SUM,0,0,0,0,0,0,1,11.9704418182, +135,,SUM,2,0,1,1,16,18,47,11.9704418182, +135,,,,,,,,,,, +136,,,,,,,,,,, +136,BOWL,SUM,1,0,1,0,0,26,44,0, +136,CUP,SUM,0,0,0,0,0,0,3,7.1904070377, +136,SPOON,SUM,1,0,1,0,0,11,44,0, +136,,SUM,2,0,2,0,0,37,91,7.1904070377, +136,,,,,,,,,,, +137,,,,,,,,,,, +137,BOWL,SUM,1,0,1,0,4,8,44,0, +137,CUP,SUM,0,0,0,0,0,2,6,5.923648119, +137,SPOON,SUM,1,0,1,0,16,8,44,0, +137,,SUM,2,0,2,0,20,18,94,5.923648119, +137,,,,,,,,,,, +138,,,,,,,,,,, +138,BOWL,SUM,1,0,1,0,0,10,44,0, +138,CUP,SUM,0,0,0,0,24,4,11,23.4751749039, +138,SPOON,SUM,1,0,1,0,0,15,44,0, +138,,SUM,2,0,2,0,24,29,99,23.4751749039, +138,,,,,,,,,,, +139,,,,,,,,,,, +139,BOWL,SUM,1,0,0,1,0,4,11,0, +139,CUP,SUM,0,0,0,0,8,64,12,36.9832060337, +139,SPOON,SUM,0,0,0,0,0,2,4,12.1681649685, +139,,SUM,1,0,0,1,8,70,27,49.1513710022, +139,,,,,,,,,,, +140,,,,,,,,,,, +140,BOWL,SUM,0,0,0,0,0,3,18,11.8182878494, +140,CUP,SUM,0,0,0,0,16,3,4,16.7213029861, +140,SPOON,SUM,1,1,0,0,8,71,0,0, +140,,SUM,1,1,0,0,24,77,22,28.5395908356, +140,,,,,,,,,,, +141,,,,,,,,,,, +141,BOWL,SUM,0,0,0,0,8,9,13,15.1042940617, +141,CUP,SUM,1,0,1,0,12,13,11,0, +141,SPOON,SUM,0,0,0,0,48,6,12,43.8079309464, +141,,SUM,1,0,1,0,68,28,36,58.912225008, +141,,,,,,,,,,, +142,,,,,,,,,,, +142,BOWL,SUM,1,0,0,1,32,9,11,0, +142,CUP,SUM,0,0,0,0,0,0,4,6.2575290203, +142,SPOON,SUM,1,0,1,0,8,14,44,0, +142,,SUM,2,0,1,1,40,23,59,6.2575290203, +142,,,,,,,,,,, +143,,,,,,,,,,, +143,BOWL,SUM,1,0,1,0,0,12,44,0, +143,CUP,SUM,0,0,0,0,0,0,6,5.9623861313, +143,SPOON,SUM,0,0,0,0,0,17,16,15.0095448494, +143,,SUM,1,0,1,0,0,29,66,20.9719309807, +143,,,,,,,,,,, +144,,,,,,,,,,, +144,BOWL,SUM,1,0,0,1,16,4,11,0, +144,CUP,SUM,0,0,0,0,0,3,9,8.5464868546, +144,SPOON,SUM,1,0,1,0,0,24,44,0, +144,,SUM,2,0,1,1,16,31,64,8.5464868546, +144,,,,,,,,,,, +145,,,,,,,,,,, +145,BOWL,SUM,0,0,0,0,0,0,8,11.432997942, +145,CUP,SUM,0,0,0,0,0,3,4,6.0902090073, +145,SPOON,SUM,1,0,1,0,0,157,24,0, +145,,SUM,1,0,1,0,0,160,36,17.5232069492, +145,,,,,,,,,,, +146,,,,,,,,,,, +146,BOWL,SUM,1,0,0,1,0,2,11,0, +146,CUP,SUM,1,1,0,0,8,71,0,0, +146,SPOON,SUM,1,0,1,0,56,13,44,0, +146,,SUM,3,1,1,1,64,86,55,0, +146,,,,,,,,,,, +147,,,,,,,,,,, +147,BOWL,SUM,1,0,1,0,0,26,44,0, +147,CUP,SUM,1,0,1,0,8,13,43,0, +147,SPOON,SUM,0,0,0,0,0,1,8,13.0368509293, +147,,SUM,2,0,2,0,8,40,95,13.0368509293, +147,,,,,,,,,,, +148,,,,,,,,,,, +148,BOWL,SUM,1,0,1,0,0,4,44,0, +148,CUP,SUM,1,0,1,0,0,10,33,0, +148,SPOON,SUM,1,1,0,0,8,41,0,0, +148,,SUM,3,1,2,0,8,55,77,0, +148,,,,,,,,,,, +149,,,,,,,,,,, +149,BOWL,SUM,0,0,0,0,0,2,14,11.6629359722, +149,CUP,SUM,0,0,0,0,0,3,28,11.6526257992, +149,SPOON,SUM,1,0,1,0,0,18,44,0, +149,,SUM,1,0,1,0,0,23,86,23.3155617714, +149,,,,,,,,,,, +150,,,,,,,,,,, +150,BOWL,SUM,1,0,1,0,8,9,44,0, +150,CUP,SUM,0,0,0,0,0,0,6,6.8687500954, +150,SPOON,SUM,0,0,0,0,0,7,29,17.9745469093, +150,,SUM,1,0,1,0,8,16,79,24.8432970047, +150,,,,,,,,,,, +151,,,,,,,,,,, +151,BOWL,SUM,1,0,1,0,0,11,44,0, +151,CUP,SUM,0,0,0,0,60,11,24,44.5633671284, +151,SPOON,SUM,1,1,0,0,8,71,0,0, +151,,SUM,2,1,1,0,68,93,68,44.5633671284, +151,,,,,,,,,,, +152,,,,,,,,,,, +152,BOWL,SUM,1,0,1,0,0,28,44,0, +152,CUP,SUM,0,0,0,0,0,0,2,5.480312109, +152,SPOON,SUM,0,0,0,0,0,4,20,15.8566520214, +152,,SUM,1,0,1,0,0,32,66,21.3369641304, +152,,,,,,,,,,, +153,,,,,,,,,,, +153,BOWL,SUM,1,0,1,0,0,8,44,0, +153,CUP,SUM,0,0,0,0,16,5,7,17.0104131699, +153,SPOON,SUM,0,0,0,0,0,2,0,10.861438036, +153,,SUM,1,0,1,0,16,15,51,27.8718512058, +153,,,,,,,,,,, +154,,,,,,,,,,, +154,BOWL,SUM,1,0,1,0,0,341,0,0, +154,CUP,SUM,0,0,0,0,0,1,3,6.3119931221, +154,SPOON,SUM,0,0,0,0,0,3,16,15.1821382046, +154,,SUM,1,0,1,0,0,345,19,21.4941313267, +154,,,,,,,,,,, +155,,,,,,,,,,, +155,BOWL,SUM,1,0,1,0,0,24,44,0, +155,CUP,SUM,1,0,1,0,16,11,33,0, +155,SPOON,SUM,0,0,0,0,0,3,2,12.6849770546, +155,,SUM,2,0,2,0,16,38,79,12.6849770546, +155,,,,,,,,,,, +156,,,,,,,,,,, +156,BOWL,SUM,1,0,1,0,0,42,40,0, +156,CUP,SUM,0,0,0,0,0,0,9,6.7622821331, +156,SPOON,SUM,0,0,0,0,0,7,0,11.763199091, +156,,SUM,1,0,1,0,0,49,49,18.5254812241, +156,,,,,,,,,,, +157,,,,,,,,,,, +157,BOWL,SUM,1,0,1,0,0,13,44,0, +157,CUP,SUM,0,0,0,0,8,6,8,13.2593421936, +157,SPOON,SUM,0,0,0,0,0,1,9,14.0687110424, +157,,SUM,1,0,1,0,8,20,61,27.328053236, +157,,,,,,,,,,, +158,,,,,,,,,,, +158,BOWL,SUM,1,0,1,0,8,16,44,0, +158,CUP,SUM,0,0,0,0,32,5,18,31.896447897, +158,SPOON,SUM,0,0,0,0,0,4,22,17.0525698662, +158,,SUM,1,0,1,0,40,25,84,48.9490177631, +158,,,,,,,,,,, +159,,,,,,,,,,, +159,BOWL,SUM,0,0,0,0,0,15,17,11.7529029846, +159,CUP,SUM,1,0,0,1,0,5,36,0, +159,SPOON,SUM,0,0,0,0,14,9,34,27.2936820984, +159,,SUM,1,0,0,1,14,29,87,39.046585083, +159,,,,,,,,,,, +160,,,,,,,,,,, +160,BOWL,SUM,0,0,0,0,8,28,3,16.12439394, +160,CUP,SUM,1,1,0,0,88,7,0,0, +160,SPOON,SUM,1,0,1,0,0,56,40,0, +160,,SUM,2,1,1,0,96,91,43,16.12439394, +160,,,,,,,,,,, +161,,,,,,,,,,, +161,BOWL,SUM,0,0,0,0,0,5,21,12.1083211899, +161,CUP,SUM,0,0,0,0,0,6,14,7.321873188, +161,SPOON,SUM,0,0,0,0,0,2,0,10.8815219402, +161,,SUM,0,0,0,0,0,13,35,30.3117163181, +161,,,,,,,,,,, +162,,,,,,,,,,, +162,BOWL,SUM,1,0,1,0,16,7,44,0, +162,CUP,SUM,1,0,0,1,0,3,11,0, +162,SPOON,SUM,1,0,1,0,0,13,44,0, +162,,SUM,3,0,2,1,16,23,99,0, +162,,,,,,,,,,, +163,,,,,,,,,,, +163,BOWL,SUM,0,0,0,0,0,6,37,15.5653710365, +163,CUP,SUM,1,0,0,1,0,5,17,0, +163,SPOON,SUM,0,0,0,0,0,1,7,13.0041890144, +163,,SUM,1,0,0,1,0,12,61,28.569560051, +163,,,,,,,,,,, +164,,,,,,,,,,, +164,BOWL,SUM,0,0,0,0,0,9,50,18.9871940613, +164,CUP,SUM,0,0,0,0,0,7,14,8.2136371136, +164,SPOON,SUM,0,0,0,0,0,1,0,11.0881400108, +164,,SUM,0,0,0,0,0,17,64,38.2889711857, +164,,,,,,,,,,, +165,,,,,,,,,,, +165,BOWL,SUM,0,0,0,0,0,7,42,18.5211920738, +165,CUP,SUM,1,0,1,0,0,25,33,0, +165,SPOON,SUM,0,0,0,0,8,14,24,21.5657382011, +165,,SUM,1,0,1,0,8,46,99,40.086930275, +165,,,,,,,,,,, +166,,,,,,,,,,, +166,BOWL,SUM,1,0,1,0,16,9,44,0, +166,CUP,SUM,0,0,0,0,0,1,13,8.9795269966, +166,SPOON,SUM,1,0,1,0,0,14,44,0, +166,,SUM,2,0,2,0,16,24,101,8.9795269966, +166,,,,,,,,,,, +167,,,,,,,,,,, +167,BOWL,SUM,0,0,0,0,0,10,14,15.3389379978, +167,CUP,SUM,0,0,0,0,16,6,16,22.1768651009, +167,SPOON,SUM,0,0,0,0,0,11,4,12.492866993, +167,,SUM,0,0,0,0,16,27,34,50.0086700916, +167,,,,,,,,,,, +168,,,,,,,,,,, +168,BOWL,SUM,0,0,0,0,0,0,1,8.3621249199, +168,CUP,SUM,1,0,1,0,0,4,33,0, +168,SPOON,SUM,1,0,1,0,0,13,44,0, +168,,SUM,2,0,2,0,0,17,78,8.3621249199, +168,,,,,,,,,,, +169,,,,,,,,,,, +169,BOWL,SUM,1,0,0,1,8,12,23,0, +169,CUP,SUM,1,0,1,0,24,27,77,0, +169,SPOON,SUM,0,0,0,0,0,2,0,10.2206320763, +169,,SUM,2,0,1,1,32,41,100,10.2206320763, +169,,,,,,,,,,, +170,,,,,,,,,,, +170,BOWL,SUM,0,0,0,0,20,0,6,22.3981318474, +170,CUP,SUM,0,0,0,0,0,7,2,5.4617760181, +170,SPOON,SUM,0,0,0,0,0,0,10,14.7321579456, +170,,SUM,0,0,0,0,20,7,18,42.5920658112, +170,,,,,,,,,,, +171,,,,,,,,,,, +171,BOWL,SUM,1,0,1,0,0,14,44,0, +171,CUP,SUM,0,0,0,0,16,3,12,18.2048490047, +171,SPOON,SUM,0,0,0,0,0,0,0,11.387693882, +171,,SUM,1,0,1,0,16,17,56,29.5925428867, +171,,,,,,,,,,, +172,,,,,,,,,,, +172,BOWL,SUM,0,0,0,0,16,6,1,18.9545619488, +172,CUP,SUM,0,0,0,0,16,2,5,16.498800993, +172,SPOON,SUM,1,0,1,0,0,21,44,0, +172,,SUM,1,0,1,0,32,29,50,35.4533629417, +172,,,,,,,,,,, +173,,,,,,,,,,, +173,BOWL,SUM,0,0,0,0,8,2,6,15.099834919, +173,CUP,SUM,1,0,1,0,0,13,77,0, +173,SPOON,SUM,0,0,0,0,0,3,0,11.2342867851, +173,,SUM,1,0,1,0,8,18,83,26.3341217041, +173,,,,,,,,,,, +174,,,,,,,,,,, +174,BOWL,SUM,1,0,1,0,0,16,44,0, +174,CUP,SUM,0,0,0,0,0,5,10,8.7305181026, +174,SPOON,SUM,0,0,0,0,0,3,10,14.4291517735, +174,,SUM,1,0,1,0,0,24,64,23.1596698761, +174,,,,,,,,,,, +175,,,,,,,,,,, +175,BOWL,SUM,0,0,0,0,8,10,13,18.8611459732, +175,CUP,SUM,1,0,1,0,0,15,39,0, +175,SPOON,SUM,0,0,0,0,8,6,17,19.5398159027, +175,,SUM,1,0,1,0,16,31,69,38.4009618759, +175,,,,,,,,,,, +176,,,,,,,,,,, +176,BOWL,SUM,0,0,0,0,0,0,4,10.1839029789, +176,CUP,SUM,0,0,0,0,0,0,3,7.5769870281, +176,SPOON,SUM,1,0,1,0,8,12,44,0, +176,,SUM,1,0,1,0,8,12,51,17.760890007, +176,,,,,,,,,,, +177,,,,,,,,,,, +177,BOWL,SUM,1,0,1,0,8,10,44,0, +177,CUP,SUM,0,0,0,0,0,3,12,7.454474926, +177,SPOON,SUM,0,0,0,0,0,0,1,10.6336429119, +177,,SUM,1,0,1,0,8,13,57,18.0881178379, +177,,,,,,,,,,, +178,,,,,,,,,,, +178,BOWL,SUM,0,0,0,0,0,0,2,9.6163320541, +178,CUP,SUM,1,0,1,0,8,15,11,0, +178,SPOON,SUM,0,0,0,0,0,13,14,15.2853200436, +178,,SUM,1,0,1,0,8,28,27,24.9016520977, +178,,,,,,,,,,, +179,,,,,,,,,,, +179,BOWL,SUM,1,0,1,0,0,19,44,0, +179,CUP,SUM,0,0,0,0,0,1,7,7.8703119755, +179,SPOON,SUM,0,0,0,0,12,3,10,21.2854120731, +179,,SUM,1,0,1,0,12,23,61,29.1557240486, +179,,,,,,,,,,, +180,,,,,,,,,,, +180,BOWL,SUM,1,0,0,1,40,8,11,0, +180,CUP,SUM,0,0,0,0,0,6,11,10.2074959278, +180,SPOON,SUM,0,0,0,0,16,2,4,21.9615950584, +180,,SUM,1,0,0,1,56,16,26,32.1690909863, +180,,,,,,,,,,, +181,,,,,,,,,,, +181,BOWL,SUM,1,0,1,0,0,19,44,0, +181,CUP,SUM,0,0,0,0,0,6,13,7.9505028725, +181,SPOON,SUM,0,0,0,0,16,1,0,22.5744860172, +181,,SUM,1,0,1,0,16,26,57,30.5249888897, +181,,,,,,,,,,, +182,,,,,,,,,,, +182,BOWL,SUM,0,0,0,0,8,3,21,19.5262699127, +182,CUP,SUM,1,0,1,0,0,10,33,0, +182,SPOON,SUM,1,0,1,0,0,25,44,0, +182,,SUM,2,0,2,0,8,38,98,19.5262699127, +182,,,,,,,,,,, +183,,,,,,,,,,, +183,BOWL,SUM,1,0,0,1,8,0,13,0, +183,CUP,SUM,0,0,0,0,0,1,2,8.4699010849, +183,SPOON,SUM,1,0,1,0,0,28,44,0, +183,,SUM,2,0,1,1,8,29,59,8.4699010849, +183,,,,,,,,,,, +184,,,,,,,,,,, +184,BOWL,SUM,1,0,1,0,0,174,24,0, +184,CUP,SUM,0,0,0,0,0,0,15,8.2353930473, +184,SPOON,SUM,0,0,0,0,0,4,5,14.0056550503, +184,,SUM,1,0,1,0,0,178,44,22.2410480976, +184,,,,,,,,,,, +185,,,,,,,,,,, +185,BOWL,SUM,1,1,0,0,96,6,0,0, +185,CUP,SUM,0,0,0,0,16,13,6,50.9591639042, +185,SPOON,SUM,1,0,1,0,0,15,44,0, +185,,SUM,2,1,1,0,112,34,50,50.9591639042, +185,,,,,,,,,,, +186,,,,,,,,,,, +186,BOWL,SUM,0,0,0,0,0,0,4,9.7632758617, +186,CUP,SUM,1,0,0,1,20,6,13,0, +186,SPOON,SUM,1,0,1,0,0,28,44,0, +186,,SUM,2,0,1,1,20,34,61,9.7632758617, +186,,,,,,,,,,, +187,,,,,,,,,,, +187,BOWL,SUM,1,0,1,0,12,10,44,0, +187,CUP,SUM,0,0,0,0,0,2,2,6.8748562336, +187,SPOON,SUM,0,0,0,0,0,1,0,11.1090378761, +187,,SUM,1,0,1,0,12,13,46,17.9838941097, +187,,,,,,,,,,, +188,,,,,,,,,,, +188,BOWL,SUM,1,0,1,0,16,15,44,0, +188,CUP,SUM,0,0,0,0,0,1,6,6.037142992, +188,SPOON,SUM,0,0,0,0,16,3,1,22.871876955, +188,,SUM,1,0,1,0,32,19,51,28.9090199471, +188,,,,,,,,,,, +189,,,,,,,,,,, +189,BOWL,SUM,0,0,0,0,0,3,0,8.9889361858, +189,CUP,SUM,0,0,0,0,0,2,12,7.1721839905, +189,SPOON,SUM,0,0,0,0,16,9,40,29.7200610638, +189,,SUM,0,0,0,0,16,14,52,45.8811812401, +189,,,,,,,,,,, +190,,,,,,,,,,, +190,BOWL,SUM,0,0,0,0,0,5,15,11.6802399158, +190,CUP,SUM,1,0,1,0,0,55,10,0, +190,SPOON,SUM,0,0,0,0,0,4,5,12.5475389957, +190,,SUM,1,0,1,0,0,64,30,24.2277789116, +190,,,,,,,,,,, +191,,,,,,,,,,, +191,BOWL,SUM,0,0,0,0,8,32,20,19.5476880074, +191,CUP,SUM,0,0,0,0,0,22,8,7.9055600166, +191,SPOON,SUM,0,0,0,0,26,3,4,28.8938138485, +191,,SUM,0,0,0,0,34,57,32,56.3470618725, +191,,,,,,,,,,, +192,,,,,,,,,,, +192,BOWL,SUM,1,0,1,0,0,12,44,0, +192,CUP,SUM,0,0,0,0,0,4,4,7.2315981388, +192,SPOON,SUM,0,0,0,0,0,1,0,11.6747610569, +192,,SUM,1,0,1,0,0,17,48,18.9063591957, +192,,,,,,,,,,, +193,,,,,,,,,,, +193,BOWL,SUM,0,0,0,0,24,4,6,25.858355999, +193,CUP,SUM,1,0,1,0,0,26,33,0, +193,SPOON,SUM,0,0,0,0,0,5,28,17.0169429779, +193,,SUM,1,0,1,0,24,35,67,42.8752989769, +193,,,,,,,,,,, +194,,,,,,,,,,, +194,BOWL,SUM,1,0,1,0,0,7,44,0, +194,CUP,SUM,0,0,0,0,0,0,2,4.9429750443, +194,SPOON,SUM,1,0,1,0,0,341,0,0, +194,,SUM,2,0,2,0,0,348,46,4.9429750443, +194,,,,,,,,,,, +195,,,,,,,,,,, +195,BOWL,SUM,0,0,0,0,0,1,8,10.3405179977, +195,CUP,SUM,1,0,1,0,0,21,33,0, +195,SPOON,SUM,1,0,1,0,0,8,44,0, +195,,SUM,2,0,2,0,0,30,85,10.3405179977, +195,,,,,,,,,,, +196,,,,,,,,,,, +196,BOWL,SUM,1,0,1,0,0,37,40,0, +196,CUP,SUM,0,0,0,0,0,5,13,11.7845001221, +196,SPOON,SUM,0,0,0,0,0,5,17,14.992718935, +196,,SUM,1,0,1,0,0,47,70,26.7772190571, +196,,,,,,,,,,, +197,,,,,,,,,,, +197,BOWL,SUM,1,0,0,1,0,6,13,0, +197,CUP,SUM,1,0,1,0,4,10,11,0, +197,SPOON,SUM,0,0,0,0,8,6,37,25.0864229202, +197,,SUM,2,0,1,1,12,22,61,25.0864229202, +197,,,,,,,,,,, +198,,,,,,,,,,, +198,BOWL,SUM,0,0,0,0,8,8,5,17.2684919834, +198,CUP,SUM,1,1,0,0,8,80,0,0, +198,SPOON,SUM,0,0,0,0,0,2,25,16.5347821712, +198,,SUM,1,1,0,0,16,90,30,33.8032741547, +198,,,,,,,,,,, +199,,,,,,,,,,, +199,BOWL,SUM,1,0,1,0,0,28,44,0, +199,CUP,SUM,0,0,0,0,0,2,5,7.9615008831, +199,SPOON,SUM,0,0,0,0,0,5,36,18.3941440582, +199,,SUM,1,0,1,0,0,35,85,26.3556449413, +199,,,,,,,,,,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/heur_pr2_orig.csv b/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/heur_pr2_orig.csv new file mode 100644 index 0000000000..ac76a60080 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/heur_pr2_orig.csv @@ -0,0 +1,1203 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,16,0,0,16.0908989906 +0,CUP,SUM,1,0,0,1,0,0,11,0 +0,SPOON,SUM,1,0,1,0,0,5,44,0 +0,,SUM,2,0,1,1,16,5,55,16.0908989906 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,8,1,13,13.5569479465 +1,CUP,SUM,0,0,0,0,16,2,14,15.1056079865 +1,SPOON,SUM,0,0,0,0,0,0,0,9.9465920925 +1,,SUM,0,0,0,0,24,3,27,38.6091480255 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,1,0,1,0,0,1,44,0 +2,CUP,SUM,1,0,0,1,0,5,32,0 +2,SPOON,SUM,0,0,0,0,0,0,9,11.9806311131 +2,,SUM,2,0,1,1,0,6,85,11.9806311131 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,0,0,4,7.8048260212 +3,CUP,SUM,0,0,0,0,0,1,11,6.6010439396 +3,SPOON,SUM,0,0,0,0,0,0,0,10.4570579529 +3,,SUM,0,0,0,0,0,1,15,24.8629279137 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,1,4,7.902613163 +4,CUP,SUM,1,0,0,1,16,0,12,0 +4,SPOON,SUM,0,0,0,0,0,2,20,13.772217989 +4,,SUM,1,0,0,1,16,3,36,21.674831152 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,24,4,36,24.1229500771 +5,CUP,SUM,0,0,0,0,0,0,2,4.5270810127 +5,SPOON,SUM,0,0,0,0,0,0,7,12.2756679058 +5,,SUM,0,0,0,0,24,4,45,40.9256989956 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,8,2,13,12.9568269253 +6,CUP,SUM,1,0,0,1,0,0,11,0 +6,SPOON,SUM,0,0,0,0,0,0,5,11.7542731762 +6,,SUM,1,0,0,1,8,2,29,24.7111001015 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,44,2,9,27.55534482 +7,CUP,SUM,0,0,0,0,24,3,10,16.7267870903 +7,SPOON,SUM,1,0,1,0,8,3,44,0 +7,,SUM,1,0,1,0,76,8,63,44.2821319103 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,1,0,1,0,24,4,44,0 +8,CUP,SUM,1,0,0,1,0,1,18,0 +8,SPOON,SUM,0,0,0,0,0,1,8,11.8552091122 +8,,SUM,2,0,1,1,24,6,70,11.8552091122 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,0,5,8.5220751762 +9,CUP,SUM,1,0,0,1,0,2,11,0 +9,SPOON,SUM,0,0,0,0,8,1,1,13.6455879211 +9,,SUM,1,0,0,1,8,3,17,22.1676630974 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,3,32,13.3466501236 +10,CUP,SUM,1,0,0,1,0,0,11,0 +10,SPOON,SUM,0,0,0,0,16,0,5,18.4817039967 +10,,SUM,1,0,0,1,16,3,48,31.8283541203 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,8,7,32,16.2029840946 +11,CUP,SUM,0,0,0,0,0,3,16,10.1003251076 +11,SPOON,SUM,0,0,0,0,0,2,16,13.2082059383 +11,,SUM,0,0,0,0,8,12,64,39.5115151405 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,0,0,8,8.357074976 +12,CUP,SUM,1,0,0,1,0,0,17,0 +12,SPOON,SUM,0,0,0,0,8,5,24,17.9342930317 +12,,SUM,1,0,0,1,8,5,49,26.2913680077 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,0,1,12,9.102337122 +13,CUP,SUM,0,0,0,0,8,0,2,8.3139820099 +13,SPOON,SUM,0,0,0,0,0,5,32,16.4842641354 +13,,SUM,0,0,0,0,8,6,46,33.9005832672 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,16,4,0,14.2003099918 +14,CUP,SUM,1,0,0,1,0,0,17,0 +14,SPOON,SUM,0,0,0,0,8,1,1,14.8334131241 +14,,SUM,1,0,0,1,24,5,18,29.0337231159 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,1,0,1,0,0,5,44,0 +15,CUP,SUM,1,0,0,1,32,0,17,0 +15,SPOON,SUM,0,0,0,0,12,0,12,17.5370099545 +15,,SUM,2,0,1,1,44,5,73,17.5370099545 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,0,1,7.8193941116 +16,CUP,SUM,1,0,0,1,8,4,35,0 +16,SPOON,SUM,0,0,0,0,0,0,9,12.7784059048 +16,,SUM,1,0,0,1,8,4,45,20.5978000164 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,0,0,1,7.7409598827 +17,CUP,SUM,1,0,1,0,0,4,25,0 +17,SPOON,SUM,0,0,0,0,8,3,28,19.6595950127 +17,,SUM,1,0,1,0,8,7,54,27.4005548954 +17,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,0,0,5,7.9468929768 +18,CUP,SUM,0,0,0,0,0,1,6,4.7033939362 +18,SPOON,SUM,0,0,0,0,0,1,13,12.8126540184 +18,,SUM,0,0,0,0,0,2,24,25.4629409313 +18,,,,,,,,,, +18,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,0,21,10.5336260796 +19,CUP,SUM,0,0,0,0,32,1,6,19.4816849232 +19,SPOON,SUM,0,0,0,0,8,2,15,16.6754469872 +19,,SUM,0,0,0,0,40,3,42,46.6907579899 +19,,,,,,,,,, +19,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,8,0,0,10.5921700001 +20,CUP,SUM,1,0,0,1,8,1,17,0 +20,SPOON,SUM,1,0,1,0,0,6,44,0 +20,,SUM,2,0,1,1,16,7,61,10.5921700001 +20,,,,,,,,,, +20,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,0,4,8.0128669739 +21,CUP,SUM,1,0,0,1,0,0,11,0 +21,SPOON,SUM,0,0,0,0,8,1,0,14.2866690159 +21,,SUM,1,0,0,1,8,1,15,22.2995359898 +21,,,,,,,,,, +21,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,0,1,8,9.1596682072 +22,CUP,SUM,1,0,0,1,0,0,11,0 +22,SPOON,SUM,1,0,1,0,0,7,44,0 +22,,SUM,2,0,1,1,0,8,63,9.1596682072 +22,,,,,,,,,, +22,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,0,0,7.5834739208 +23,CUP,SUM,1,0,0,1,8,0,11,0 +23,SPOON,SUM,0,0,0,0,0,1,11,13.3500390053 +23,,SUM,1,0,0,1,8,1,22,20.9335129261 +23,,,,,,,,,, +23,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,0,2,12,9.1711261272 +24,CUP,SUM,1,0,0,1,0,1,11,0 +24,SPOON,SUM,0,0,0,0,0,2,13,12.9868779182 +24,,SUM,1,0,0,1,0,5,36,22.1580040455 +24,,,,,,,,,, +24,,,,,,,,,, +25,BOWL,SUM,1,0,1,0,0,2,44,0 +25,CUP,SUM,1,0,0,1,8,1,12,0 +25,SPOON,SUM,0,0,0,0,0,0,1,10.6138269901 +25,,SUM,2,0,1,1,8,3,57,10.6138269901 +25,,,,,,,,,, +25,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,8,5,14,14.2087850571 +26,CUP,SUM,1,0,0,1,6,1,17,0 +26,SPOON,SUM,0,0,0,0,0,0,20,14.3131599426 +26,,SUM,1,0,0,1,14,6,51,28.5219449997 +26,,,,,,,,,, +26,,,,,,,,,, +27,BOWL,SUM,1,0,1,0,0,4,44,0 +27,CUP,SUM,0,0,0,0,44,5,67,31.4812760353 +27,SPOON,SUM,0,0,0,0,0,1,16,13.5532569885 +27,,SUM,1,0,1,0,44,10,127,45.0345330238 +27,,,,,,,,,, +27,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,16,0,0,14.9937460423 +28,CUP,SUM,1,0,0,1,0,0,15,0 +28,SPOON,SUM,1,0,1,0,0,3,44,0 +28,,SUM,2,0,1,1,16,3,59,14.9937460423 +28,,,,,,,,,, +28,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,0,0,1,8.0499680042 +29,CUP,SUM,1,0,0,1,0,0,11,0 +29,SPOON,SUM,0,0,0,0,0,1,12,12.8911111355 +29,,SUM,1,0,0,1,0,1,24,20.9410791397 +29,,,,,,,,,, +29,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,0,2,0,7.3274409771 +30,CUP,SUM,1,0,0,1,0,0,11,0 +30,SPOON,SUM,0,0,0,0,0,2,20,14.8593699932 +30,,SUM,1,0,0,1,0,4,31,22.1868109703 +30,,,,,,,,,, +30,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,8,5,36,17.2517809868 +31,CUP,SUM,1,0,0,1,0,0,18,0 +31,SPOON,SUM,0,0,0,0,8,0,1,14.5215251446 +31,,SUM,1,0,0,1,16,5,55,31.7733061314 +31,,,,,,,,,, +31,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,8,1,20,14.5430059433 +32,CUP,SUM,0,0,0,0,0,6,16,10.5946850777 +32,SPOON,SUM,0,0,0,0,0,0,4,11.1537828445 +32,,SUM,0,0,0,0,8,7,40,36.2914738655 +32,,,,,,,,,, +32,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,1,8,8.7054278851 +33,CUP,SUM,1,0,0,1,12,0,19,0 +33,SPOON,SUM,0,0,0,0,0,0,4,11.2080450058 +33,,SUM,1,0,0,1,12,1,31,19.9134728909 +33,,,,,,,,,, +33,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,0,1,18,10.2658150196 +34,CUP,SUM,1,0,0,1,0,3,11,0 +34,SPOON,SUM,0,0,0,0,0,3,16,13.5303990841 +34,,SUM,1,0,0,1,0,7,45,23.7962141037 +34,,,,,,,,,, +34,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,12,2,34,18.2723309994 +35,CUP,SUM,0,0,0,0,0,3,8,5.1405959129 +35,SPOON,SUM,0,0,0,0,0,5,4,11.7703728676 +35,,SUM,0,0,0,0,12,10,46,35.1832997799 +35,,,,,,,,,, +35,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,0,0,5,9.213654995 +36,CUP,SUM,0,0,0,0,8,0,15,12.4043228626 +36,SPOON,SUM,0,0,0,0,0,4,17,14.6642260551 +36,,SUM,0,0,0,0,8,4,37,36.2822039127 +36,,,,,,,,,, +36,,,,,,,,,, +37,BOWL,SUM,0,0,0,0,8,1,20,14.9099128246 +37,CUP,SUM,0,0,0,0,8,0,13,11.3325939178 +37,SPOON,SUM,0,0,0,0,0,1,4,11.6810569763 +37,,SUM,0,0,0,0,16,2,37,37.9235637188 +37,,,,,,,,,, +37,,,,,,,,,, +38,BOWL,SUM,0,0,0,0,0,0,1,7.8724060059 +38,CUP,SUM,0,0,0,0,24,0,14,20.1030390263 +38,SPOON,SUM,0,0,0,0,0,0,4,11.067081213 +38,,SUM,0,0,0,0,24,0,19,39.0425262451 +38,,,,,,,,,, +38,,,,,,,,,, +39,BOWL,SUM,0,0,0,0,0,1,0,7.417301178 +39,CUP,SUM,1,0,0,1,0,2,11,0 +39,SPOON,SUM,0,0,0,0,0,1,9,12.2423779964 +39,,SUM,1,0,0,1,0,4,20,19.6596791744 +39,,,,,,,,,, +39,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,16,1,0,14.2166690826 +40,CUP,SUM,1,0,0,1,16,0,11,0 +40,SPOON,SUM,0,0,0,0,8,0,1,13.9622790813 +40,,SUM,1,0,0,1,40,1,12,28.178948164 +40,,,,,,,,,, +40,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,0,0,6,8.3873791695 +41,CUP,SUM,0,0,0,0,0,0,6,4.7343769073 +41,SPOON,SUM,0,0,0,0,24,3,21,25.7377250195 +41,,SUM,0,0,0,0,24,3,33,38.8594810963 +41,,,,,,,,,, +41,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,0,1,16,10.0478510857 +42,CUP,SUM,1,0,0,1,0,1,11,0 +42,SPOON,SUM,0,0,0,0,16,0,4,18.7537460327 +42,,SUM,1,0,0,1,16,2,31,28.8015971184 +42,,,,,,,,,, +42,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,0,1,12,9.0865368843 +43,CUP,SUM,0,0,0,0,12,4,19,15.5288248062 +43,SPOON,SUM,0,0,0,0,0,0,3,11.1328909397 +43,,SUM,0,0,0,0,12,5,34,35.7482526302 +43,,,,,,,,,, +43,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,8,0,2,11.315237999 +44,CUP,SUM,0,0,0,0,0,1,4,4.651941061 +44,SPOON,SUM,0,0,0,0,0,1,13,12.8725280762 +44,,SUM,0,0,0,0,8,2,19,28.8397071362 +44,,,,,,,,,, +44,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,0,1,13,9.5758650303 +45,CUP,SUM,0,0,0,0,0,0,4,5.0230879784 +45,SPOON,SUM,0,0,0,0,0,2,18,14.3156619072 +45,,SUM,0,0,0,0,0,3,35,28.9146149158 +45,,,,,,,,,, +45,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,0,0,0,7.5921308994 +46,CUP,SUM,1,0,0,1,0,0,12,0 +46,SPOON,SUM,0,0,0,0,0,3,32,16.3581438065 +46,,SUM,1,0,0,1,0,3,44,23.9502747059 +46,,,,,,,,,, +46,,,,,,,,,, +47,BOWL,SUM,0,0,0,0,48,0,4,29.631978035 +47,CUP,SUM,1,0,0,1,0,0,19,0 +47,SPOON,SUM,0,0,0,0,0,3,9,12.4314539433 +47,,SUM,1,0,0,1,48,3,32,42.0634319782 +47,,,,,,,,,, +47,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,0,0,0,7.4364180565 +48,CUP,SUM,1,0,0,1,0,1,11,0 +48,SPOON,SUM,0,0,0,0,16,1,5,18.74137187 +48,,SUM,1,0,0,1,16,2,16,26.1777899265 +48,,,,,,,,,, +48,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,0,0,1,7.7798500061 +49,CUP,SUM,0,0,0,0,8,0,8,8.7965669632 +49,SPOON,SUM,0,0,0,0,0,0,0,10.2725379467 +49,,SUM,0,0,0,0,8,0,9,26.848954916 +49,,,,,,,,,, +49,,,,,,,,,, +50,BOWL,SUM,0,0,0,0,16,0,0,14.5628221035 +50,CUP,SUM,1,0,0,1,0,6,47,0 +50,SPOON,SUM,0,0,0,0,0,2,24,14.5269141197 +50,,SUM,1,0,0,1,16,8,71,29.0897362232 +50,,,,,,,,,, +50,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,0,2,12,9.6157450676 +51,CUP,SUM,1,0,0,1,0,1,11,0 +51,SPOON,SUM,0,0,0,0,0,2,33,16.8213160038 +51,,SUM,1,0,0,1,0,5,56,26.4370610714 +51,,,,,,,,,, +51,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,8,0,0,11.4475929737 +52,CUP,SUM,1,0,0,1,0,0,11,0 +52,SPOON,SUM,0,0,0,0,8,0,1,14.8031470776 +52,,SUM,1,0,0,1,16,0,12,26.2507400513 +52,,,,,,,,,, +52,,,,,,,,,, +53,BOWL,SUM,0,0,0,0,0,0,1,7.6924679279 +53,CUP,SUM,0,0,0,0,0,0,14,9.8666980267 +53,SPOON,SUM,0,0,0,0,8,0,8,16.4037489891 +53,,SUM,0,0,0,0,8,0,23,33.9629149437 +53,,,,,,,,,, +53,,,,,,,,,, +54,BOWL,SUM,1,0,1,0,0,1,44,0 +54,CUP,SUM,0,0,0,0,0,1,8,6.5134541988 +54,SPOON,SUM,0,0,0,0,8,0,7,18.5083880425 +54,,SUM,1,0,1,0,8,2,59,25.0218422413 +54,,,,,,,,,, +54,,,,,,,,,, +55,BOWL,SUM,0,0,0,0,0,1,3,8.4696469307 +55,CUP,SUM,0,0,0,0,0,0,2,4.7757558823 +55,SPOON,SUM,0,0,0,0,8,2,22,19.5132780075 +55,,SUM,0,0,0,0,8,3,27,32.7586808205 +55,,,,,,,,,, +55,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,0,3,20,10.9438450336 +56,CUP,SUM,0,0,0,0,0,1,10,7.2538809776 +56,SPOON,SUM,0,0,0,0,0,0,8,12.7890999317 +56,,SUM,0,0,0,0,0,4,38,30.986825943 +56,,,,,,,,,, +56,,,,,,,,,, +57,BOWL,SUM,1,0,1,0,0,7,44,0 +57,CUP,SUM,1,0,0,1,0,1,26,0 +57,SPOON,SUM,0,0,0,0,8,3,28,18.829777956 +57,,SUM,2,0,1,1,8,11,98,18.829777956 +57,,,,,,,,,, +57,,,,,,,,,, +58,BOWL,SUM,0,0,0,0,0,1,12,8.9016320705 +58,CUP,SUM,0,0,0,0,0,0,14,8.6314549446 +58,SPOON,SUM,0,0,0,0,0,0,2,10.6147549152 +58,,SUM,0,0,0,0,0,1,28,28.1478419304 +58,,,,,,,,,, +58,,,,,,,,,, +59,BOWL,SUM,0,0,0,0,0,0,5,7.9928691387 +59,CUP,SUM,0,0,0,0,0,1,6,4.5234599113 +59,SPOON,SUM,0,0,0,0,0,1,13,13.0547270775 +59,,SUM,0,0,0,0,0,2,24,25.5710561275 +59,,,,,,,,,, +59,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,0,0,21,10.8251240253 +60,CUP,SUM,0,0,0,0,32,1,6,20.2537519932 +60,SPOON,SUM,0,0,0,0,8,2,15,17.7351200581 +60,,SUM,0,0,0,0,40,3,42,48.8139960766 +60,,,,,,,,,, +60,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,8,0,0,11.1574389935 +61,CUP,SUM,1,0,0,1,8,1,17,0 +61,SPOON,SUM,1,0,1,0,0,6,44,0 +61,,SUM,2,0,1,1,16,7,61,11.1574389935 +61,,,,,,,,,, +61,,,,,,,,,, +62,BOWL,SUM,0,0,0,0,0,0,4,7.7585761547 +62,CUP,SUM,1,0,0,1,0,0,11,0 +62,SPOON,SUM,0,0,0,0,8,1,0,14.4823701382 +62,,SUM,1,0,0,1,8,1,15,22.2409462929 +62,,,,,,,,,, +62,,,,,,,,,, +63,BOWL,SUM,0,0,0,0,0,1,8,8.6061930656 +63,CUP,SUM,1,0,0,1,0,0,11,0 +63,SPOON,SUM,1,0,1,0,0,7,44,0 +63,,SUM,2,0,1,1,0,8,63,8.6061930656 +63,,,,,,,,,, +63,,,,,,,,,, +64,BOWL,SUM,0,0,0,0,0,0,0,7.1587569714 +64,CUP,SUM,1,0,0,1,8,0,11,0 +64,SPOON,SUM,0,0,0,0,0,1,11,13.0544710159 +64,,SUM,1,0,0,1,8,1,22,20.2132279873 +64,,,,,,,,,, +64,,,,,,,,,, +65,BOWL,SUM,0,0,0,0,0,2,12,9.0194160938 +65,CUP,SUM,1,0,0,1,0,1,11,0 +65,SPOON,SUM,0,0,0,0,0,2,13,12.6173911095 +65,,SUM,1,0,0,1,0,5,36,21.6368072033 +65,,,,,,,,,, +65,,,,,,,,,, +66,BOWL,SUM,1,0,1,0,0,2,44,0 +66,CUP,SUM,1,0,0,1,8,1,12,0 +66,SPOON,SUM,0,0,0,0,0,0,1,10.6649329662 +66,,SUM,2,0,1,1,8,3,57,10.6649329662 +66,,,,,,,,,, +66,,,,,,,,,, +67,BOWL,SUM,0,0,0,0,8,5,14,14.4327719212 +67,CUP,SUM,1,0,0,1,6,1,17,0 +67,SPOON,SUM,0,0,0,0,0,0,20,14.5419318676 +67,,SUM,1,0,0,1,14,6,51,28.9747037888 +67,,,,,,,,,, +67,,,,,,,,,, +68,BOWL,SUM,1,0,1,0,0,4,44,0 +68,CUP,SUM,0,0,0,0,44,5,67,31.5919189453 +68,SPOON,SUM,0,0,0,0,0,1,16,13.8390939236 +68,,SUM,1,0,1,0,44,10,127,45.4310128689 +68,,,,,,,,,, +68,,,,,,,,,, +69,BOWL,SUM,0,0,0,0,16,0,0,14.7661738396 +69,CUP,SUM,1,0,0,1,0,0,15,0 +69,SPOON,SUM,1,0,1,0,0,3,44,0 +69,,SUM,2,0,1,1,16,3,59,14.7661738396 +69,,,,,,,,,, +69,,,,,,,,,, +70,BOWL,SUM,0,0,0,0,0,0,1,7.9913580418 +70,CUP,SUM,1,0,0,1,0,0,11,0 +70,SPOON,SUM,0,0,0,0,0,1,12,12.9608240128 +70,,SUM,1,0,0,1,0,1,24,20.9521820545 +70,,,,,,,,,, +70,,,,,,,,,, +71,BOWL,SUM,0,0,0,0,0,2,0,7.4578588009 +71,CUP,SUM,1,0,0,1,0,0,11,0 +71,SPOON,SUM,0,0,0,0,0,2,20,15.147400856 +71,,SUM,1,0,0,1,0,4,31,22.6052596569 +71,,,,,,,,,, +71,,,,,,,,,, +72,BOWL,SUM,0,0,0,0,8,5,36,17.5651929379 +72,CUP,SUM,1,0,0,1,0,0,18,0 +72,SPOON,SUM,0,0,0,0,8,0,1,15.0042300224 +72,,SUM,1,0,0,1,16,5,55,32.5694229603 +72,,,,,,,,,, +72,,,,,,,,,, +73,BOWL,SUM,0,0,0,0,8,1,20,14.6955227852 +73,CUP,SUM,0,0,0,0,0,6,16,11.0188179016 +73,SPOON,SUM,0,0,0,0,0,0,4,10.9840619564 +73,,SUM,0,0,0,0,8,7,40,36.6984026432 +73,,,,,,,,,, +73,,,,,,,,,, +74,BOWL,SUM,0,0,0,0,0,1,8,8.9963769913 +74,CUP,SUM,1,0,0,1,12,0,19,0 +74,SPOON,SUM,0,0,0,0,0,0,4,11.5707349777 +74,,SUM,1,0,0,1,12,1,31,20.567111969 +74,,,,,,,,,, +74,,,,,,,,,, +75,BOWL,SUM,0,0,0,0,0,1,18,10.482558012 +75,CUP,SUM,1,0,0,1,0,3,11,0 +75,SPOON,SUM,0,0,0,0,0,3,16,13.9246089458 +75,,SUM,1,0,0,1,0,7,45,24.4071669579 +75,,,,,,,,,, +75,,,,,,,,,, +76,BOWL,SUM,0,0,0,0,12,2,34,18.7302060127 +76,CUP,SUM,0,0,0,0,0,3,8,6.0940549374 +76,SPOON,SUM,0,0,0,0,0,5,4,12.4039719105 +76,,SUM,0,0,0,0,12,10,46,37.2282328606 +76,,,,,,,,,, +76,,,,,,,,,, +77,BOWL,SUM,0,0,0,0,0,0,5,9.1319749355 +77,CUP,SUM,0,0,0,0,8,0,15,13.1134939194 +77,SPOON,SUM,0,0,0,0,0,4,17,14.9392821789 +77,,SUM,0,0,0,0,8,4,37,37.1847510338 +77,,,,,,,,,, +77,,,,,,,,,, +78,BOWL,SUM,0,0,0,0,8,1,20,14.8515188694 +78,CUP,SUM,0,0,0,0,8,0,13,12.3796949387 +78,SPOON,SUM,0,0,0,0,0,1,4,11.7136240005 +78,,SUM,0,0,0,0,16,2,37,38.9448378086 +78,,,,,,,,,, +78,,,,,,,,,, +79,BOWL,SUM,0,0,0,0,0,0,1,8.2394759655 +79,CUP,SUM,0,0,0,0,24,0,14,21.2455749512 +79,SPOON,SUM,0,0,0,0,0,0,4,12.1253681183 +79,,SUM,0,0,0,0,24,0,19,41.610419035 +79,,,,,,,,,, +79,,,,,,,,,, +80,BOWL,SUM,1,0,1,0,0,7,44,0 +80,CUP,SUM,1,0,0,1,0,1,26,0 +80,SPOON,SUM,0,0,0,0,8,3,28,18.4933261871 +80,,SUM,2,0,1,1,8,11,98,18.4933261871 +80,,,,,,,,,, +80,,,,,,,,,, +81,BOWL,SUM,0,0,0,0,0,1,12,8.8889400959 +81,CUP,SUM,0,0,0,0,0,0,14,8.5484919548 +81,SPOON,SUM,0,0,0,0,0,0,2,10.6539101601 +81,,SUM,0,0,0,0,0,1,28,28.0913422108 +81,,,,,,,,,, +81,,,,,,,,,, +82,BOWL,SUM,0,0,0,0,0,0,5,8.0698261261 +82,CUP,SUM,0,0,0,0,0,1,6,4.6353368759 +82,SPOON,SUM,0,0,0,0,0,1,13,12.4650518894 +82,,SUM,0,0,0,0,0,2,24,25.1702148914 +82,,,,,,,,,, +82,,,,,,,,,, +83,BOWL,SUM,0,0,0,0,0,0,21,10.7793281078 +83,CUP,SUM,0,0,0,0,32,1,6,19.9651010036 +83,SPOON,SUM,0,0,0,0,8,2,15,17.3216769695 +83,,SUM,0,0,0,0,40,3,42,48.066106081 +83,,,,,,,,,, +83,,,,,,,,,, +84,BOWL,SUM,0,0,0,0,8,0,0,10.5563240051 +84,CUP,SUM,1,0,0,1,8,1,17,0 +84,SPOON,SUM,1,0,1,0,0,6,44,0 +84,,SUM,2,0,1,1,16,7,61,10.5563240051 +84,,,,,,,,,, +84,,,,,,,,,, +85,BOWL,SUM,0,0,0,0,0,0,4,8.1229388714 +85,CUP,SUM,1,0,0,1,0,0,11,0 +85,SPOON,SUM,0,0,0,0,8,1,0,14.2496099472 +85,,SUM,1,0,0,1,8,1,15,22.3725488186 +85,,,,,,,,,, +85,,,,,,,,,, +86,BOWL,SUM,0,0,0,0,0,1,8,8.5583598614 +86,CUP,SUM,1,0,0,1,0,0,11,0 +86,SPOON,SUM,1,0,1,0,0,7,44,0 +86,,SUM,2,0,1,1,0,8,63,8.5583598614 +86,,,,,,,,,, +86,,,,,,,,,, +87,BOWL,SUM,0,0,0,0,0,0,0,6.9523279667 +87,CUP,SUM,1,0,0,1,8,0,11,0 +87,SPOON,SUM,0,0,0,0,0,1,11,12.9354829788 +87,,SUM,1,0,0,1,8,1,22,19.8878109455 +87,,,,,,,,,, +87,,,,,,,,,, +88,BOWL,SUM,0,0,0,0,0,2,12,9.1349301338 +88,CUP,SUM,1,0,0,1,0,1,11,0 +88,SPOON,SUM,0,0,0,0,0,2,13,12.8090589046 +88,,SUM,1,0,0,1,0,5,36,21.9439890385 +88,,,,,,,,,, +88,,,,,,,,,, +89,BOWL,SUM,1,0,1,0,0,2,44,0 +89,CUP,SUM,1,0,0,1,8,1,12,0 +89,SPOON,SUM,0,0,0,0,0,0,1,10.7945160866 +89,,SUM,2,0,1,1,8,3,57,10.7945160866 +89,,,,,,,,,, +89,,,,,,,,,, +90,BOWL,SUM,0,0,0,0,8,5,14,14.5862650871 +90,CUP,SUM,1,0,0,1,6,1,17,0 +90,SPOON,SUM,0,0,0,0,0,0,20,13.5365991592 +90,,SUM,1,0,0,1,14,6,51,28.1228642464 +90,,,,,,,,,, +90,,,,,,,,,, +91,BOWL,SUM,1,0,1,0,0,4,44,0 +91,CUP,SUM,0,0,0,0,44,5,67,32.2395730019 +91,SPOON,SUM,0,0,0,0,0,1,16,13.6120769978 +91,,SUM,1,0,1,0,44,10,127,45.8516499996 +91,,,,,,,,,, +91,,,,,,,,,, +92,BOWL,SUM,0,0,0,0,16,0,0,14.298358202 +92,CUP,SUM,1,0,0,1,0,0,15,0 +92,SPOON,SUM,1,0,1,0,0,3,44,0 +92,,SUM,2,0,1,1,16,3,59,14.298358202 +92,,,,,,,,,, +92,,,,,,,,,, +93,BOWL,SUM,0,0,0,0,0,0,1,7.8226950169 +93,CUP,SUM,1,0,0,1,0,0,11,0 +93,SPOON,SUM,0,0,0,0,0,1,12,13.0035178661 +93,,SUM,1,0,0,1,0,1,24,20.826212883 +93,,,,,,,,,, +93,,,,,,,,,, +94,BOWL,SUM,0,0,0,0,0,2,0,7.5843029022 +94,CUP,SUM,1,0,0,1,0,0,11,0 +94,SPOON,SUM,0,0,0,0,0,2,20,14.9923319817 +94,,SUM,1,0,0,1,0,4,31,22.5766348839 +94,,,,,,,,,, +94,,,,,,,,,, +95,BOWL,SUM,0,0,0,0,8,5,36,16.9351811409 +95,CUP,SUM,1,0,0,1,0,0,18,0 +95,SPOON,SUM,0,0,0,0,8,0,1,14.2875897884 +95,,SUM,1,0,0,1,16,5,55,31.2227709293 +95,,,,,,,,,, +95,,,,,,,,,, +96,BOWL,SUM,0,0,0,0,8,1,20,14.1860098839 +96,CUP,SUM,0,0,0,0,0,6,16,10.7020220757 +96,SPOON,SUM,0,0,0,0,0,0,4,11.0964319706 +96,,SUM,0,0,0,0,8,7,40,35.9844639301 +96,,,,,,,,,, +96,,,,,,,,,, +97,BOWL,SUM,0,0,0,0,0,1,8,8.6147010326 +97,CUP,SUM,1,0,0,1,12,0,19,0 +97,SPOON,SUM,0,0,0,0,0,0,4,10.9142560959 +97,,SUM,1,0,0,1,12,1,31,19.5289571285 +97,,,,,,,,,, +97,,,,,,,,,, +98,BOWL,SUM,0,0,0,0,0,1,18,10.3255479336 +98,CUP,SUM,1,0,0,1,0,3,11,0 +98,SPOON,SUM,0,0,0,0,0,3,16,13.8381330967 +98,,SUM,1,0,0,1,0,7,45,24.1636810303 +98,,,,,,,,,, +98,,,,,,,,,, +99,BOWL,SUM,0,0,0,0,12,2,34,18.161044836 +99,CUP,SUM,0,0,0,0,0,3,8,5.0742509365 +99,SPOON,SUM,0,0,0,0,0,5,4,11.8395738602 +99,,SUM,0,0,0,0,12,10,46,35.0748696327 +99,,,,,,,,,, +99,,,,,,,,,, +100,BOWL,SUM,0,0,0,0,0,0,5,8.7887191772 +100,CUP,SUM,0,0,0,0,8,0,15,12.7108709812 +100,SPOON,SUM,0,0,0,0,0,4,17,14.5642330647 +100,,SUM,0,0,0,0,8,4,37,36.0638232231 +100,,,,,,,,,, +100,,,,,,,,,, +101,BOWL,SUM,0,0,0,0,8,1,20,15.477241993 +101,CUP,SUM,0,0,0,0,8,0,13,11.5720140934 +101,SPOON,SUM,0,0,0,0,0,1,4,11.5963890553 +101,,SUM,0,0,0,0,16,2,37,38.6456451416 +101,,,,,,,,,, +101,,,,,,,,,, +102,BOWL,SUM,0,0,0,0,0,0,1,7.4590368271 +102,CUP,SUM,0,0,0,0,24,0,14,19.8688409328 +102,SPOON,SUM,0,0,0,0,0,0,4,11.0847461224 +102,,SUM,0,0,0,0,24,0,19,38.4126238823 +102,,,,,,,,,, +102,,,,,,,,,, +103,BOWL,SUM,1,0,1,0,0,7,44,0 +103,CUP,SUM,1,0,0,1,0,1,26,0 +103,SPOON,SUM,0,0,0,0,8,3,28,18.3595449924 +103,,SUM,2,0,1,1,8,11,98,18.3595449924 +103,,,,,,,,,, +103,,,,,,,,,, +104,BOWL,SUM,0,0,0,0,0,1,12,8.926763773 +104,CUP,SUM,0,0,0,0,0,0,14,8.9727039337 +104,SPOON,SUM,0,0,0,0,0,0,2,10.5587990284 +104,,SUM,0,0,0,0,0,1,28,28.4582667351 +104,,,,,,,,,, +104,,,,,,,,,, +105,BOWL,SUM,0,0,0,0,0,0,5,8.1286921501 +105,CUP,SUM,0,0,0,0,0,1,6,4.9638950825 +105,SPOON,SUM,0,0,0,0,0,1,13,12.9461500645 +105,,SUM,0,0,0,0,0,2,24,26.0387372971 +105,,,,,,,,,, +105,,,,,,,,,, +106,BOWL,SUM,0,0,0,0,0,0,21,10.974132061 +106,CUP,SUM,0,0,0,0,32,1,6,19.7350780964 +106,SPOON,SUM,0,0,0,0,8,2,15,17.5787100792 +106,,SUM,0,0,0,0,40,3,42,48.2879202366 +106,,,,,,,,,, +106,,,,,,,,,, +107,BOWL,SUM,0,0,0,0,8,0,0,10.2387311459 +107,CUP,SUM,1,0,0,1,8,1,17,0 +107,SPOON,SUM,1,0,1,0,0,6,44,0 +107,,SUM,2,0,1,1,16,7,61,10.2387311459 +107,,,,,,,,,, +107,,,,,,,,,, +108,BOWL,SUM,0,0,0,0,0,0,4,7.4951879978 +108,CUP,SUM,1,0,0,1,0,0,11,0 +108,SPOON,SUM,0,0,0,0,8,1,0,14.4823901653 +108,,SUM,1,0,0,1,8,1,15,21.9775781631 +108,,,,,,,,,, +108,,,,,,,,,, +109,BOWL,SUM,0,0,0,0,0,1,8,8.4347259998 +109,CUP,SUM,1,0,0,1,0,0,11,0 +109,SPOON,SUM,1,0,1,0,0,7,44,0 +109,,SUM,2,0,1,1,0,8,63,8.4347259998 +109,,,,,,,,,, +109,,,,,,,,,, +110,BOWL,SUM,0,0,0,0,0,0,0,7.2712070942 +110,CUP,SUM,1,0,0,1,8,0,11,0 +110,SPOON,SUM,0,0,0,0,0,1,11,13.2354009151 +110,,SUM,1,0,0,1,8,1,22,20.5066080093 +110,,,,,,,,,, +110,,,,,,,,,, +111,BOWL,SUM,0,0,0,0,0,2,12,9.0649001598 +111,CUP,SUM,1,0,0,1,0,1,11,0 +111,SPOON,SUM,0,0,0,0,0,2,13,12.5656249523 +111,,SUM,1,0,0,1,0,5,36,21.6305251122 +111,,,,,,,,,, +111,,,,,,,,,, +112,BOWL,SUM,1,0,1,0,0,2,44,0 +112,CUP,SUM,1,0,0,1,8,1,12,0 +112,SPOON,SUM,0,0,0,0,0,0,1,10.7807719707 +112,,SUM,2,0,1,1,8,3,57,10.7807719707 +112,,,,,,,,,, +112,,,,,,,,,, +113,BOWL,SUM,0,0,0,0,8,5,14,14.4060008526 +113,CUP,SUM,1,0,0,1,6,1,17,0 +113,SPOON,SUM,0,0,0,0,0,0,20,14.0462949276 +113,,SUM,1,0,0,1,14,6,51,28.4522957802 +113,,,,,,,,,, +113,,,,,,,,,, +114,BOWL,SUM,1,0,1,0,0,4,44,0 +114,CUP,SUM,0,0,0,0,44,5,67,31.2239041328 +114,SPOON,SUM,0,0,0,0,0,1,16,14.1713171005 +114,,SUM,1,0,1,0,44,10,127,45.3952212334 +114,,,,,,,,,, +114,,,,,,,,,, +115,BOWL,SUM,0,0,0,0,16,0,0,14.7992508411 +115,CUP,SUM,1,0,0,1,0,0,15,0 +115,SPOON,SUM,1,0,1,0,0,3,44,0 +115,,SUM,2,0,1,1,16,3,59,14.7992508411 +115,,,,,,,,,, +115,,,,,,,,,, +116,BOWL,SUM,0,0,0,0,0,0,1,7.1466989517 +116,CUP,SUM,1,0,0,1,0,0,11,0 +116,SPOON,SUM,0,0,0,0,0,1,12,12.6712698936 +116,,SUM,1,0,0,1,0,1,24,19.8179688454 +116,,,,,,,,,, +116,,,,,,,,,, +117,BOWL,SUM,0,0,0,0,0,2,0,7.7306358814 +117,CUP,SUM,1,0,0,1,0,0,11,0 +117,SPOON,SUM,0,0,0,0,0,2,20,14.7489509583 +117,,SUM,1,0,0,1,0,4,31,22.4795868397 +117,,,,,,,,,, +117,,,,,,,,,, +118,BOWL,SUM,0,0,0,0,8,5,36,16.975028038 +118,CUP,SUM,1,0,0,1,0,0,18,0 +118,SPOON,SUM,0,0,0,0,8,0,1,14.734418869 +118,,SUM,1,0,0,1,16,5,55,31.709446907 +118,,,,,,,,,, +118,,,,,,,,,, +119,BOWL,SUM,0,0,0,0,8,1,20,14.1540560722 +119,CUP,SUM,0,0,0,0,0,6,16,10.4268729687 +119,SPOON,SUM,0,0,0,0,0,0,4,11.0964810848 +119,,SUM,0,0,0,0,8,7,40,35.6774101257 +119,,,,,,,,,, +119,,,,,,,,,, +120,BOWL,SUM,0,0,0,0,0,1,8,8.6448290348 +120,CUP,SUM,1,0,0,1,12,0,19,0 +120,SPOON,SUM,0,0,0,0,0,0,4,11.055560112 +120,,SUM,1,0,0,1,12,1,31,19.7003891468 +120,,,,,,,,,, +120,,,,,,,,,, +121,BOWL,SUM,0,0,0,0,0,1,18,10.1801950932 +121,CUP,SUM,1,0,0,1,0,3,11,0 +121,SPOON,SUM,0,0,0,0,0,3,16,13.3143351078 +121,,SUM,1,0,0,1,0,7,45,23.494530201 +121,,,,,,,,,, +121,,,,,,,,,, +122,BOWL,SUM,0,0,0,0,12,2,34,17.7745249271 +122,CUP,SUM,0,0,0,0,0,3,8,5.4758520126 +122,SPOON,SUM,0,0,0,0,0,5,4,12.2872438431 +122,,SUM,0,0,0,0,12,10,46,35.5376207829 +122,,,,,,,,,, +122,,,,,,,,,, +123,BOWL,SUM,0,0,0,0,0,0,5,8.6141700745 +123,CUP,SUM,0,0,0,0,8,0,15,12.3336091042 +123,SPOON,SUM,0,0,0,0,0,4,17,14.4455640316 +123,,SUM,0,0,0,0,8,4,37,35.3933432102 +123,,,,,,,,,, +123,,,,,,,,,, +124,BOWL,SUM,0,0,0,0,8,1,20,14.8594589233 +124,CUP,SUM,0,0,0,0,8,0,13,11.2695820332 +124,SPOON,SUM,0,0,0,0,0,1,4,11.7643070221 +124,,SUM,0,0,0,0,16,2,37,37.8933479786 +124,,,,,,,,,, +124,,,,,,,,,, +125,BOWL,SUM,0,0,0,0,0,0,1,8.0197639465 +125,CUP,SUM,0,0,0,0,24,0,14,19.7506270409 +125,SPOON,SUM,0,0,0,0,0,0,4,11.5545239449 +125,,SUM,0,0,0,0,24,0,19,39.3249149323 +125,,,,,,,,,, +125,,,,,,,,,, +126,BOWL,SUM,1,0,1,0,0,2,44,0 +126,CUP,SUM,0,0,0,0,0,1,4,5.1721148491 +126,SPOON,SUM,0,0,0,0,8,0,0,13.0090479851 +126,,SUM,1,0,1,0,8,3,48,18.1811628342 +126,,,,,,,,,, +126,,,,,,,,,, +127,BOWL,SUM,0,0,0,0,16,0,8,15.2236778736 +127,CUP,SUM,0,0,0,0,0,0,2,4.36302495 +127,SPOON,SUM,1,0,1,0,0,5,44,0 +127,,SUM,1,0,1,0,16,5,54,19.5867028236 +127,,,,,,,,,, +127,,,,,,,,,, +128,BOWL,SUM,0,0,0,0,12,0,4,12.8249340057 +128,CUP,SUM,1,0,0,1,0,1,11,0 +128,SPOON,SUM,0,0,0,0,8,2,0,13.8053541183 +128,,SUM,1,0,0,1,20,3,15,26.6302881241 +128,,,,,,,,,, +128,,,,,,,,,, +129,BOWL,SUM,0,0,0,0,0,4,20,10.4737799168 +129,CUP,SUM,0,0,0,0,0,0,7,5.3390471935 +129,SPOON,SUM,0,0,0,0,0,0,4,11.3812401295 +129,,SUM,0,0,0,0,0,4,31,27.1940672398 +129,,,,,,,,,, +129,,,,,,,,,, +130,BOWL,SUM,0,0,0,0,0,0,0,6.9132730961 +130,CUP,SUM,0,0,0,0,0,0,5,5.2021479607 +130,SPOON,SUM,0,0,0,0,24,2,16,24.9408280849 +130,,SUM,0,0,0,0,24,2,21,37.0562491417 +130,,,,,,,,,, +130,,,,,,,,,, +131,BOWL,SUM,0,0,0,0,0,0,0,7.442841053 +131,CUP,SUM,1,0,0,1,0,0,20,0 +131,SPOON,SUM,0,0,0,0,0,1,7,12.2038750648 +131,,SUM,1,0,0,1,0,1,27,19.6467161179 +131,,,,,,,,,, +131,,,,,,,,,, +132,BOWL,SUM,0,0,0,0,8,0,0,10.5709779263 +132,CUP,SUM,1,0,0,1,0,0,11,0 +132,SPOON,SUM,0,0,0,0,0,0,0,9.6507899761 +132,,SUM,1,0,0,1,8,0,11,20.2217679024 +132,,,,,,,,,, +132,,,,,,,,,, +133,BOWL,SUM,0,0,0,0,0,0,4,7.9626989365 +133,CUP,SUM,0,0,0,0,0,2,12,8.0945000648 +133,SPOON,SUM,0,0,0,0,0,1,9,12.1706328392 +133,,SUM,0,0,0,0,0,3,25,28.2278318405 +133,,,,,,,,,, +133,,,,,,,,,, +134,BOWL,SUM,0,0,0,0,0,3,41,14.8263459206 +134,CUP,SUM,0,0,0,0,0,6,124,16.8453440666 +134,SPOON,SUM,0,0,0,0,0,0,3,11.400769949 +134,,SUM,0,0,0,0,0,9,168,43.0724599361 +134,,,,,,,,,, +134,,,,,,,,,, +135,BOWL,SUM,0,0,0,0,0,0,16,9.7629320621 +135,CUP,SUM,1,0,0,1,0,1,11,0 +135,SPOON,SUM,0,0,0,0,0,2,13,13.1192479134 +135,,SUM,1,0,0,1,0,3,40,22.8821799755 +135,,,,,,,,,, +135,,,,,,,,,, +136,BOWL,SUM,1,0,1,0,0,2,44,0 +136,CUP,SUM,1,0,0,1,8,1,11,0 +136,SPOON,SUM,0,0,0,0,0,0,6,11.6380388737 +136,,SUM,2,0,1,1,8,3,61,11.6380388737 +136,,,,,,,,,, +136,,,,,,,,,, +137,BOWL,SUM,1,0,1,0,0,5,44,0 +137,CUP,SUM,1,0,0,1,0,2,26,0 +137,SPOON,SUM,0,0,0,0,0,1,29,15.474766016 +137,,SUM,2,0,1,1,0,8,99,15.474766016 +137,,,,,,,,,, +137,,,,,,,,,, +138,BOWL,SUM,0,0,0,0,0,1,24,11.4029591084 +138,CUP,SUM,0,0,0,0,0,0,9,6.1637639999 +138,SPOON,SUM,0,0,0,0,0,0,5,11.5713129044 +138,,SUM,0,0,0,0,0,1,38,29.1380360126 +138,,,,,,,,,, +138,,,,,,,,,, +139,BOWL,SUM,0,0,0,0,0,1,8,8.4199180603 +139,CUP,SUM,1,0,0,1,0,0,11,0 +139,SPOON,SUM,0,0,0,0,0,1,12,12.3391251564 +139,,SUM,1,0,0,1,0,2,31,20.7590432167 +139,,,,,,,,,, +139,,,,,,,,,, +140,BOWL,SUM,0,0,0,0,0,0,0,7.1711521149 +140,CUP,SUM,1,0,0,1,8,0,21,0 +140,SPOON,SUM,0,0,0,0,0,0,4,10.7804808617 +140,,SUM,1,0,0,1,8,0,25,17.9516329765 +140,,,,,,,,,, +140,,,,,,,,,, +141,BOWL,SUM,0,0,0,0,8,0,8,11.9394841194 +141,CUP,SUM,0,0,0,0,0,0,8,6.0983099937 +141,SPOON,SUM,1,0,1,0,0,8,44,0 +141,,SUM,1,0,1,0,8,8,60,18.0377941132 +141,,,,,,,,,, +141,,,,,,,,,, +142,BOWL,SUM,0,0,0,0,0,0,0,7.3077399731 +142,CUP,SUM,0,0,0,0,0,0,28,9.5341868401 +142,SPOON,SUM,0,0,0,0,0,2,12,13.3187139034 +142,,SUM,0,0,0,0,0,2,40,30.1606407166 +142,,,,,,,,,, +142,,,,,,,,,, +143,BOWL,SUM,0,0,0,0,8,4,41,18.2916350365 +143,CUP,SUM,1,0,0,1,0,0,11,0 +143,SPOON,SUM,0,0,0,0,16,3,33,24.3468780518 +143,,SUM,1,0,0,1,24,7,85,42.6385130882 +143,,,,,,,,,, +143,,,,,,,,,, +144,BOWL,SUM,0,0,0,0,16,2,28,19.8660678864 +144,CUP,SUM,1,0,0,1,0,0,11,0 +144,SPOON,SUM,0,0,0,0,0,3,36,16.9746391773 +144,,SUM,1,0,0,1,16,5,75,36.8407070637 +144,,,,,,,,,, +144,,,,,,,,,, +145,BOWL,SUM,1,0,1,0,8,4,44,0 +145,CUP,SUM,0,0,0,0,0,0,4,5.1251649857 +145,SPOON,SUM,0,0,0,0,8,0,11,16.9526100159 +145,,SUM,1,0,1,0,16,4,59,22.0777750015 +145,,,,,,,,,, +145,,,,,,,,,, +146,BOWL,SUM,0,0,0,0,0,1,7,8.3415880203 +146,CUP,SUM,0,0,0,0,0,4,2,4.9271879196 +146,SPOON,SUM,0,0,0,0,8,5,40,20.7019460201 +146,,SUM,0,0,0,0,8,10,49,33.9707219601 +146,,,,,,,,,, +146,,,,,,,,,, +147,BOWL,SUM,0,0,0,0,8,0,0,10.2560710907 +147,CUP,SUM,1,0,0,1,0,1,11,0 +147,SPOON,SUM,0,0,0,0,0,1,8,11.237719059 +147,,SUM,1,0,0,1,8,2,19,21.4937901497 +147,,,,,,,,,, +147,,,,,,,,,, +148,BOWL,SUM,1,0,1,0,16,3,44,0 +148,CUP,SUM,0,0,0,0,0,0,2,4.7666490078 +148,SPOON,SUM,1,0,1,0,16,6,44,0 +148,,SUM,2,0,2,0,32,9,90,4.7666490078 +148,,,,,,,,,, +148,,,,,,,,,, +149,BOWL,SUM,0,0,0,0,0,0,20,10.5354180336 +149,CUP,SUM,1,0,0,1,16,1,11,0 +149,SPOON,SUM,0,0,0,0,0,0,0,9.8192908764 +149,,SUM,1,0,0,1,16,1,31,20.35470891 +149,,,,,,,,,, +149,,,,,,,,,, +150,BOWL,SUM,1,0,1,0,8,5,44,0 +150,CUP,SUM,0,0,0,0,0,0,2,5.0044779778 +150,SPOON,SUM,0,0,0,0,0,0,8,11.6593260765 +150,,SUM,1,0,1,0,8,5,54,16.6638040543 +150,,,,,,,,,, +150,,,,,,,,,, +151,BOWL,SUM,1,0,1,0,8,3,44,0 +151,CUP,SUM,1,0,0,1,0,1,11,0 +151,SPOON,SUM,0,0,0,0,0,1,8,11.6332850456 +151,,SUM,2,0,1,1,8,5,63,11.6332850456 +151,,,,,,,,,, +151,,,,,,,,,, +152,BOWL,SUM,1,0,1,0,12,3,44,0 +152,CUP,SUM,0,0,0,0,0,0,14,7.9376020432 +152,SPOON,SUM,0,0,0,0,0,0,14,12.8907330036 +152,,SUM,1,0,1,0,12,3,72,20.8283350468 +152,,,,,,,,,, +152,,,,,,,,,, +153,BOWL,SUM,0,0,0,0,0,0,4,7.6115350723 +153,CUP,SUM,1,0,0,1,0,1,21,0 +153,SPOON,SUM,0,0,0,0,12,1,13,17.1059019566 +153,,SUM,1,0,0,1,12,2,38,24.7174370289 +153,,,,,,,,,, +153,,,,,,,,,, +154,BOWL,SUM,0,0,0,0,0,2,8,8.3896691799 +154,CUP,SUM,1,0,0,1,0,0,12,0 +154,SPOON,SUM,0,0,0,0,0,0,9,12.2362229824 +154,,SUM,1,0,0,1,0,2,29,20.6258921623 +154,,,,,,,,,, +154,,,,,,,,,, +155,BOWL,SUM,0,0,0,0,12,1,4,12.4635798931 +155,CUP,SUM,0,0,0,0,0,1,3,5.3243360519 +155,SPOON,SUM,0,0,0,0,0,1,7,12.2293059826 +155,,SUM,0,0,0,0,12,3,14,30.0172219276 +155,,,,,,,,,, +155,,,,,,,,,, +156,BOWL,SUM,1,0,1,0,0,5,44,0 +156,CUP,SUM,0,0,0,0,0,4,3,5.9744930267 +156,SPOON,SUM,0,0,0,0,0,0,6,11.7150859833 +156,,SUM,1,0,1,0,0,9,53,17.68957901 +156,,,,,,,,,, +156,,,,,,,,,, +157,BOWL,SUM,0,0,0,0,0,0,0,6.9688739777 +157,CUP,SUM,1,0,0,1,6,1,11,0 +157,SPOON,SUM,0,0,0,0,0,1,3,11.3017289639 +157,,SUM,1,0,0,1,6,2,14,18.2706029415 +157,,,,,,,,,, +157,,,,,,,,,, +158,BOWL,SUM,0,0,0,0,0,0,0,7.3001179695 +158,CUP,SUM,1,0,0,1,56,0,11,0 +158,SPOON,SUM,0,0,0,0,0,2,24,14.1748700142 +158,,SUM,1,0,0,1,56,2,35,21.4749879837 +158,,,,,,,,,, +158,,,,,,,,,, +159,BOWL,SUM,1,0,1,0,0,3,44,0 +159,CUP,SUM,1,0,0,1,0,4,32,0 +159,SPOON,SUM,0,0,0,0,0,0,0,10.8226408958 +159,,SUM,2,0,1,1,0,7,76,10.8226408958 +159,,,,,,,,,, +159,,,,,,,,,, +160,BOWL,SUM,0,0,0,0,8,1,2,11.5318090916 +160,CUP,SUM,1,0,0,1,8,1,11,0 +160,SPOON,SUM,0,0,0,0,8,0,2,14.8526570797 +160,,SUM,1,0,0,1,24,2,15,26.3844661713 +160,,,,,,,,,, +160,,,,,,,,,, +81,BOWL,SUM,0,0,0,0,0,0,4,8.0874228477 +161,CUP,SUM,1,0,1,0,0,1,37,0 +161,SPOON,SUM,0,0,0,0,12,0,2,16.7071819305 +161,,SUM,1,0,1,0,12,1,43,24.7946047783 +161,,,,,,,,,, +161,,,,,,,,,, +162,BOWL,SUM,0,0,0,0,0,1,12,10.2416059971 +162,CUP,SUM,0,0,0,0,0,1,2,5.6675229073 +162,SPOON,SUM,0,0,0,0,0,0,4,11.6093459129 +162,,SUM,0,0,0,0,0,2,18,27.5184748173 +162,,,,,,,,,, +162,,,,,,,,,, +163,BOWL,SUM,0,0,0,0,0,1,8,9.4575190544 +163,CUP,SUM,0,0,0,0,0,0,2,4.9495830536 +163,SPOON,SUM,0,0,0,0,0,0,0,11.0135099888 +163,,SUM,0,0,0,0,0,1,10,25.4206120968 +163,,,,,,,,,, +163,,,,,,,,,, +164,BOWL,SUM,1,0,1,0,0,3,44,0 +164,CUP,SUM,0,0,0,0,0,0,2,5.3534588814 +164,SPOON,SUM,0,0,0,0,12,1,13,19.4031159878 +164,,SUM,1,0,1,0,12,4,59,24.7565748692 +164,,,,,,,,,, +164,,,,,,,,,, +165,BOWL,SUM,0,0,0,0,0,0,18,10.1564729214 +165,CUP,SUM,1,0,0,1,16,0,28,0 +165,SPOON,SUM,0,0,0,0,0,3,22,14.9861021042 +165,,SUM,1,0,0,1,16,3,68,25.1425750256 +165,,,,,,,,,, +165,,,,,,,,,, +166,BOWL,SUM,1,0,1,0,0,7,44,0 +166,CUP,SUM,1,0,0,1,0,1,26,0 +166,SPOON,SUM,0,0,0,0,8,3,28,17.9515199661 +166,,SUM,2,0,1,1,8,11,98,17.9515199661 +166,,,,,,,,,, +166,,,,,,,,,, +167,BOWL,SUM,0,0,0,0,0,1,12,8.9237859249 +167,CUP,SUM,0,0,0,0,0,2,14,8.6281139851 +167,SPOON,SUM,0,0,0,0,0,0,2,10.656594038 +167,,SUM,0,0,0,0,0,3,28,28.208493948 +167,,,,,,,,,, +167,,,,,,,,,, +168,BOWL,SUM,0,0,0,0,0,1,5,7.8352839947 +168,CUP,SUM,0,0,0,0,0,1,6,4.5605678558 +168,SPOON,SUM,0,0,0,0,0,1,13,12.0963790417 +168,,SUM,0,0,0,0,0,3,24,24.4922308922 +168,,,,,,,,,, +168,,,,,,,,,, +169,BOWL,SUM,0,0,0,0,0,2,21,10.4310359955 +169,CUP,SUM,0,0,0,0,24,0,2,14.3583450317 +169,SPOON,SUM,0,0,0,0,0,2,27,16.2586390972 +169,,SUM,0,0,0,0,24,4,50,41.0480201244 +169,,,,,,,,,, +169,,,,,,,,,, +170,BOWL,SUM,0,0,0,0,0,0,0,6.6946909428 +170,CUP,SUM,0,0,0,0,0,0,5,5.1819331646 +170,SPOON,SUM,0,0,0,0,8,3,16,16.5373730659 +170,,SUM,0,0,0,0,8,3,21,28.4139971733 +170,,,,,,,,,, +170,,,,,,,,,, +171,BOWL,SUM,0,0,0,0,8,0,3,10.5527451038 +171,CUP,SUM,0,0,0,0,0,1,11,6.3168690205 +171,SPOON,SUM,0,0,0,0,0,1,13,13.1939871311 +171,,SUM,0,0,0,0,8,2,27,30.0636012554 +171,,,,,,,,,, +171,,,,,,,,,, +172,BOWL,SUM,0,0,0,0,8,1,0,10.0606548786 +172,CUP,SUM,0,0,0,0,20,3,21,17.4721519947 +172,SPOON,SUM,1,0,1,0,0,11,44,0 +172,,SUM,1,0,1,0,28,15,65,27.5328068733 +172,,,,,,,,,, +172,,,,,,,,,, +173,BOWL,SUM,0,0,0,0,0,6,32,12.4122409821 +173,CUP,SUM,1,0,0,1,16,1,11,0 +173,SPOON,SUM,0,0,0,0,0,1,10,11.7601418495 +173,,SUM,1,0,0,1,16,8,53,24.1723828316 +173,,,,,,,,,, +173,,,,,,,,,, +174,BOWL,SUM,1,0,1,0,8,4,44,0 +174,CUP,SUM,1,0,0,1,0,0,11,0 +174,SPOON,SUM,0,0,0,0,0,0,0,10.3760700226 +174,,SUM,2,0,1,1,8,4,55,10.3760700226 +174,,,,,,,,,, +174,,,,,,,,,, +175,BOWL,SUM,1,0,1,0,0,7,44,0 +175,CUP,SUM,0,0,0,0,0,1,2,4.8846178055 +175,SPOON,SUM,0,0,0,0,0,2,13,14.1282269955 +175,,SUM,1,0,1,0,0,10,59,19.0128448009 +175,,,,,,,,,, +175,,,,,,,,,, +176,BOWL,SUM,0,0,0,0,24,0,4,18.3240609169 +176,CUP,SUM,0,0,0,0,0,2,2,5.001157999 +176,SPOON,SUM,0,0,0,0,0,2,0,10.2332849503 +176,,SUM,0,0,0,0,24,4,6,33.5585038662 +176,,,,,,,,,, +176,,,,,,,,,, +177,BOWL,SUM,0,0,0,0,0,2,12,9.2105891705 +177,CUP,SUM,0,0,0,0,0,2,2,5.1137299538 +177,SPOON,SUM,0,0,0,0,24,4,0,21.7804300785 +177,,SUM,0,0,0,0,24,8,14,36.1047492027 +177,,,,,,,,,, +177,,,,,,,,,, +178,BOWL,SUM,1,0,1,0,8,6,44,0 +178,CUP,SUM,1,0,1,0,12,2,11,0 +178,SPOON,SUM,0,0,0,0,0,4,0,10.5202789307 +178,,SUM,2,0,2,0,20,12,55,10.5202789307 +178,,,,,,,,,, +178,,,,,,,,,, +179,BOWL,SUM,0,0,0,0,0,0,0,6.770236969 +179,CUP,SUM,1,0,0,1,8,0,17,0 +179,SPOON,SUM,0,0,0,0,0,1,4,10.974011898 +179,,SUM,1,0,0,1,8,1,21,17.744248867 +179,,,,,,,,,, +179,,,,,,,,,, +180,BOWL,SUM,1,0,1,0,8,4,44,0 +180,CUP,SUM,0,0,0,0,0,5,37,11.6026470661 +180,SPOON,SUM,1,0,1,0,8,10,44,0 +180,,SUM,2,0,2,0,16,19,125,11.6026470661 +180,,,,,,,,,, +180,,,,,,,,,, +181,BOWL,SUM,0,0,0,0,0,0,0,7.0572290421 +181,CUP,SUM,0,0,0,0,24,3,2,15.5493228436 +181,SPOON,SUM,0,0,0,0,0,0,0,10.1831591129 +181,,SUM,0,0,0,0,24,3,2,32.7897109985 +181,,,,,,,,,, +181,,,,,,,,,, +182,BOWL,SUM,1,0,1,0,0,3,44,0 +182,CUP,SUM,0,0,0,0,8,1,2,8.7766821384 +182,SPOON,SUM,0,0,0,0,0,2,0,10.6251888275 +182,,SUM,1,0,1,0,8,6,46,19.401870966 +182,,,,,,,,,, +182,,,,,,,,,, +183,BOWL,SUM,0,0,0,0,0,0,4,8.3425798416 +183,CUP,SUM,1,0,0,1,8,2,11,0 +183,SPOON,SUM,0,0,0,0,16,0,0,17.0707039833 +183,,SUM,1,0,0,1,24,2,15,25.4132838249 +183,,,,,,,,,, +183,,,,,,,,,, +184,BOWL,SUM,0,0,0,0,0,0,1,8.2794508934 +184,CUP,SUM,1,0,0,1,0,1,11,0 +184,SPOON,SUM,0,0,0,0,40,3,12,31.8623631001 +184,,SUM,1,0,0,1,40,4,24,40.1418139935 +184,,,,,,,,,, +184,,,,,,,,,, +185,BOWL,SUM,0,0,0,0,8,3,1,12.1664590836 +185,CUP,SUM,1,0,0,1,0,2,11,0 +185,SPOON,SUM,0,0,0,0,0,0,1,10.4260070324 +185,,SUM,1,0,0,1,8,5,13,22.592466116 +185,,,,,,,,,, +185,,,,,,,,,, +186,BOWL,SUM,1,0,1,0,0,4,44,0 +186,CUP,SUM,1,0,0,1,0,1,11,0 +186,SPOON,SUM,0,0,0,0,0,2,36,16.7238230705 +186,,SUM,2,0,1,1,0,7,91,16.7238230705 +186,,,,,,,,,, +186,,,,,,,,,, +187,BOWL,SUM,0,0,0,0,0,3,16,10.2425920963 +187,CUP,SUM,1,0,0,1,0,0,17,0 +187,SPOON,SUM,0,0,0,0,0,3,34,16.6521868706 +187,,SUM,1,0,0,1,0,6,67,26.8947789669 +187,,,,,,,,,, +187,,,,,,,,,, +188,BOWL,SUM,1,0,1,0,0,4,44,0 +188,CUP,SUM,1,0,0,1,8,3,11,0 +188,SPOON,SUM,0,0,0,0,0,3,24,14.6588668823 +188,,SUM,2,0,1,1,8,10,79,14.6588668823 +188,,,,,,,,,, +188,,,,,,,,,, +189,BOWL,SUM,0,0,0,0,0,0,0,7.3959648609 +189,CUP,SUM,1,0,0,1,0,0,11,0 +189,SPOON,SUM,0,0,0,0,0,2,9,13.0320661068 +189,,SUM,1,0,0,1,0,2,20,20.4280309677 +189,,,,,,,,,, +189,,,,,,,,,, +190,BOWL,SUM,0,0,0,0,0,1,0,7.3283028603 +190,CUP,SUM,0,0,0,0,0,0,2,4.8656790257 +190,SPOON,SUM,0,0,0,0,0,5,36,16.3442611694 +190,,SUM,0,0,0,0,0,6,38,28.5382430553 +190,,,,,,,,,, +190,,,,,,,,,, +191,BOWL,SUM,0,0,0,0,0,0,0,7.2763221264 +191,CUP,SUM,1,0,0,1,0,0,11,0 +191,SPOON,SUM,1,0,1,0,0,5,44,0 +191,,SUM,2,0,1,1,0,5,55,7.2763221264 +191,,,,,,,,,, +191,,,,,,,,,, +192,BOWL,SUM,0,0,0,0,0,4,1,7.3278541565 +192,CUP,SUM,0,0,0,0,0,1,17,9.0630099773 +192,SPOON,SUM,0,0,0,0,8,6,21,17.8689110279 +192,,SUM,0,0,0,0,8,11,39,34.2597751617 +192,,,,,,,,,, +192,,,,,,,,,, +193,BOWL,SUM,1,0,1,0,24,7,44,0 +193,CUP,SUM,0,0,0,0,0,1,2,4.870541811 +193,SPOON,SUM,0,0,0,0,0,0,0,10.3970658779 +193,,SUM,1,0,1,0,24,8,46,15.2676076889 +193,,,,,,,,,, +193,,,,,,,,,, +194,BOWL,SUM,1,0,1,0,0,4,44,0 +194,CUP,SUM,0,0,0,0,0,3,11,7.6614909172 +194,SPOON,SUM,0,0,0,0,0,0,1,10.7214860916 +194,,SUM,1,0,1,0,0,7,56,18.3829770088 +194,,,,,,,,,, +194,,,,,,,,,, +195,BOWL,SUM,0,0,0,0,0,0,0,7.0351099968 +195,CUP,SUM,1,0,0,1,40,6,46,0 +195,SPOON,SUM,0,0,0,0,0,1,4,11.2242088318 +195,,SUM,1,0,0,1,40,7,50,18.2593188286 +195,,,,,,,,,, +195,,,,,,,,,, +196,BOWL,SUM,0,0,0,0,0,1,8,8.4781200886 +196,CUP,SUM,0,0,0,0,8,1,2,8.3474159241 +196,SPOON,SUM,0,0,0,0,0,1,3,11.5721290112 +196,,SUM,0,0,0,0,8,3,13,28.3976650238 +196,,,,,,,,,, +196,,,,,,,,,, +197,BOWL,SUM,0,0,0,0,0,1,4,7.9306440353 +197,CUP,SUM,1,0,0,1,8,0,11,0 +197,SPOON,SUM,0,0,0,0,0,3,40,17.6018869877 +197,,SUM,1,0,0,1,8,4,55,25.532531023 +197,,,,,,,,,, +197,,,,,,,,,, +198,BOWL,SUM,0,0,0,0,8,5,19,15.9665050507 +198,CUP,SUM,0,0,0,0,0,1,11,7.9614930153 +198,SPOON,SUM,0,0,0,0,0,1,0,10.6570780277 +198,,SUM,0,0,0,0,8,7,30,34.5850760937 +198,,,,,,,,,, +198,,,,,,,,,, +199,BOWL,SUM,1,0,1,0,0,3,44,0 +199,CUP,SUM,0,0,0,0,8,0,2,8.7669808865 +199,SPOON,SUM,0,0,0,0,0,6,27,16.0432140827 +199,,SUM,1,0,1,0,8,9,73,24.8101949692 +199,,,,,,,,,, +199,,,,,,,,,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/kvr_boxy_3var_best.csv b/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/kvr_boxy_3var_best.csv new file mode 100644 index 0000000000..855226b495 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/kvr_boxy_3var_best.csv @@ -0,0 +1,303 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,2,45,14,35.26452302932739 +0,CUP,SUM,1,0,0,1,0,469,58,0.0 +0,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +0,,SUM,2,0,1,1,2,2095,72,35.26452302932739 +0,, +1,, +1,BOWL,SUM,0,0,0,0,6,28,6,25.85601305961609 +1,CUP,SUM,0,0,0,0,0,13,2,12.409448146820068 +1,SPOON,SUM,0,0,0,0,0,1,14,29.9533531665802 +1,,SUM,0,0,0,0,6,42,22,68.21881437301636 +1,, +2,, +2,BOWL,SUM,1,0,1,0,0,1404,18,0.0 +2,CUP,SUM,0,0,0,0,0,14,10,18.43154788017273 +2,SPOON,SUM,1,0,1,0,0,1564,8,0.0 +2,,SUM,2,0,2,0,0,2982,36,18.43154788017273 +2,, +3,, +3,BOWL,SUM,0,0,0,0,0,35,0,15.790754079818726 +3,CUP,SUM,0,0,0,0,0,10,0,11.57533597946167 +3,SPOON,SUM,0,0,0,0,0,36,2,18.805893898010254 +3,,SUM,0,0,0,0,0,81,2,46.17198395729065 +3,, +4,, +4,BOWL,SUM,0,0,0,0,6,45,16,38.230873107910156 +4,CUP,SUM,0,0,0,0,0,92,0,16.134905099868774 +4,SPOON,SUM,0,0,0,0,0,216,0,29.674817085266113 +4,,SUM,0,0,0,0,6,353,16,84.04059529304504 +4,, +5,, +5,BOWL,SUM,0,0,0,0,0,387,2,41.53441596031189 +5,CUP,SUM,0,0,0,0,0,31,2,13.482014179229736 +5,SPOON,SUM,0,0,0,0,0,26,4,17.79829502105713 +5,,SUM,0,0,0,0,0,444,8,72.81472516059875 +5,, +6,, +6,BOWL,SUM,0,0,0,0,0,38,13,25.44232702255249 +6,CUP,SUM,0,0,0,0,2,53,7,18.7336528301239 +6,SPOON,SUM,1,0,1,0,2,1581,5,0.0 +6,,SUM,1,0,1,0,4,1672,25,44.17597985267639 +6,, +7,, +7,BOWL,SUM,0,0,0,0,0,23,8,20.340171813964844 +7,CUP,SUM,1,0,1,0,2,524,107,0.0 +7,SPOON,SUM,0,0,0,0,0,46,9,36.318702936172485 +7,,SUM,1,0,1,0,2,593,124,56.65887475013733 +7,, +8,, +8,BOWL,SUM,0,0,0,0,0,15,5,16.030744791030884 +8,CUP,SUM,0,0,0,0,6,73,0,16.65789484977722 +8,SPOON,SUM,0,0,0,0,0,161,1,29.691219091415405 +8,,SUM,0,0,0,0,6,249,6,62.37985873222351 +8,, +9,, +9,BOWL,SUM,0,0,0,0,0,167,8,33.539669036865234 +9,CUP,SUM,0,0,0,0,0,9,4,12.90775179862976 +9,SPOON,SUM,0,0,0,0,4,567,4,52.225929975509644 +9,,SUM,0,0,0,0,4,743,16,98.67335081100464 +9,, +10,, +10,BOWL,SUM,0,0,0,0,6,29,5,23.604433059692383 +10,CUP,SUM,0,0,0,0,8,12,8,18.779245138168335 +10,SPOON,SUM,0,0,0,0,0,35,0,17.461730003356934 +10,,SUM,0,0,0,0,14,76,13,59.84540820121765 +10,, +11,, +11,BOWL,SUM,0,0,0,0,0,64,7,21.09502100944519 +11,CUP,SUM,0,0,0,0,2,6,6,14.86521601676941 +11,SPOON,SUM,0,0,0,0,0,130,0,25.152591943740845 +11,,SUM,0,0,0,0,2,200,13,61.112828969955444 +11,, +12,, +12,BOWL,SUM,0,0,0,0,0,100,3,24.63730812072754 +12,CUP,SUM,1,0,1,0,0,438,115,0.0 +12,SPOON,SUM,0,0,0,0,0,14,0,16.512137174606323 +12,,SUM,1,0,1,0,0,552,118,41.14944529533386 +12,, +13,, +13,BOWL,SUM,0,0,0,0,0,28,6,17.39031481742859 +13,CUP,SUM,0,0,0,0,2,44,9,20.80741310119629 +13,SPOON,SUM,0,0,0,0,2,12,4,18.434448957443237 +13,,SUM,0,0,0,0,4,84,19,56.632176876068115 +13,, +14,, +14,BOWL,SUM,0,0,0,0,6,11,5,25.677917957305908 +14,CUP,SUM,1,0,1,0,6,382,108,0.0 +14,SPOON,SUM,0,0,0,0,0,17,9,33.09389805793762 +14,,SUM,1,0,1,0,12,410,122,58.77181601524353 +14,, +15,, +15,BOWL,SUM,0,0,0,0,0,182,0,24.333861827850342 +15,CUP,SUM,0,0,0,0,0,26,7,14.393471002578735 +15,SPOON,SUM,0,0,0,0,0,15,2,18.83298110961914 +15,,SUM,0,0,0,0,0,223,9,57.56031394004822 +15,, +16,, +16,BOWL,SUM,0,0,0,0,0,45,1,16.495805025100708 +16,CUP,SUM,0,0,0,0,16,24,6,24.350743055343628 +16,SPOON,SUM,0,0,0,0,0,907,4,78.50611186027527 +16,,SUM,0,0,0,0,16,976,11,119.3526599407196 +16,, +17,, +17,BOWL,SUM,0,0,0,0,0,53,6,27.511013984680176 +17,CUP,SUM,1,0,1,0,2,855,90,0.0 +17,SPOON,SUM,0,0,0,0,0,87,7,30.62739896774292 +17,,SUM,1,0,1,0,2,995,103,58.138412952423096 +17,, +18,, +18,BOWL,SUM,0,0,0,0,0,24,0,13.885917901992798 +18,CUP,SUM,0,0,0,0,6,56,4,18.6828670501709 +18,SPOON,SUM,0,0,0,0,4,6,1,18.861089944839478 +18,,SUM,0,0,0,0,10,86,5,51.429874897003174 +18,, +19,, +19,BOWL,SUM,0,0,0,0,0,55,4,17.536975145339966 +19,CUP,SUM,0,0,0,0,0,22,2,12.047250986099243 +19,SPOON,SUM,0,0,0,0,8,3,0,21.359088897705078 +19,,SUM,0,0,0,0,8,80,6,50.94331502914429 +19,, +20,, +20,BOWL,SUM,0,0,0,0,0,82,7,25.10892605781555 +20,CUP,SUM,1,0,1,0,0,465,110,0.0 +20,SPOON,SUM,0,0,0,0,0,7,10,32.079673051834106 +20,,SUM,1,0,1,0,0,554,127,57.18859910964966 +20,, +21,, +21,BOWL,SUM,1,0,1,0,2,1587,13,0.0 +21,CUP,SUM,1,0,1,0,0,610,104,0.0 +21,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +21,,SUM,3,0,3,0,2,3778,117,0.0 +21,, +22,, +22,BOWL,SUM,0,0,0,0,0,75,6,26.107800006866455 +22,CUP,SUM,0,0,0,0,0,12,10,16.855175971984863 +22,SPOON,SUM,0,0,0,0,8,101,0,27.97274684906006 +22,,SUM,0,0,0,0,8,188,16,70.93572282791138 +22,, +23,, +23,BOWL,SUM,0,0,0,0,0,14,7,21.378226041793823 +23,CUP,SUM,1,0,0,1,8,574,114,0.0 +23,SPOON,SUM,0,0,0,0,0,241,7,47.047467947006226 +23,,SUM,1,0,0,1,8,829,128,68.42569398880005 +23,, +24,, +24,BOWL,SUM,0,0,0,0,6,44,0,18.01453399658203 +24,CUP,SUM,0,0,0,0,0,44,2,12.958813905715942 +24,SPOON,SUM,1,0,1,0,6,1568,5,0.0 +24,,SUM,1,0,1,0,12,1656,7,30.973347902297974 +24,, +25,, +25,BOWL,SUM,0,0,0,0,0,119,4,21.42752504348755 +25,CUP,SUM,0,0,0,0,6,23,5,16.091768980026245 +25,SPOON,SUM,0,0,0,0,0,1,3,22.663936853408813 +25,,SUM,0,0,0,0,6,143,12,60.18323087692261 +25,, +26,, +26,BOWL,SUM,0,0,0,0,0,151,3,24.114493131637573 +26,CUP,SUM,0,0,0,0,0,54,9,16.781694173812866 +26,SPOON,SUM,0,0,0,0,0,5,1,17.97213387489319 +26,,SUM,0,0,0,0,0,210,13,58.86832118034363 +26,, +27,, +27,BOWL,SUM,0,0,0,0,0,30,4,21.774598121643066 +27,CUP,SUM,0,0,0,0,0,17,2,13.456995010375977 +27,SPOON,SUM,0,0,0,0,0,13,0,16.910961151123047 +27,,SUM,0,0,0,0,0,60,6,52.14255428314209 +27,, +28,, +28,BOWL,SUM,0,0,0,0,4,214,12,35.60226106643677 +28,CUP,SUM,0,0,0,0,0,21,4,13.346338033676147 +28,SPOON,SUM,0,0,0,0,0,175,0,27.523408889770508 +28,,SUM,0,0,0,0,4,410,16,76.47200798988342 +28,, +29,, +29,BOWL,SUM,0,0,0,0,6,37,4,17.56292486190796 +29,CUP,SUM,0,0,0,0,0,75,11,24.25345206260681 +29,SPOON,SUM,0,0,0,0,0,11,0,16.537650108337402 +29,,SUM,0,0,0,0,6,123,15,58.35402703285217 +29,, +30,, +30,BOWL,SUM,1,0,1,0,0,1500,22,0.0 +30,CUP,SUM,0,0,0,0,0,13,6,12.961507797241211 +30,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +30,,SUM,2,0,2,0,0,3094,28,12.961507797241211 +30,, +31,, +31,BOWL,SUM,0,0,0,0,0,42,18,26.60525608062744 +31,CUP,SUM,1,0,1,0,8,1123,63,0.0 +31,SPOON,SUM,0,0,0,0,0,25,1,19.352105140686035 +31,,SUM,1,0,1,0,8,1190,82,45.95736122131348 +31,, +32,, +32,BOWL,SUM,0,0,0,0,0,208,24,54.39823794364929 +32,CUP,SUM,0,0,0,0,0,26,4,12.791224002838135 +32,SPOON,SUM,0,0,0,0,0,391,1,41.84676504135132 +32,,SUM,0,0,0,0,0,625,29,109.03622698783875 +32,, +33,, +33,BOWL,SUM,0,0,0,0,0,77,7,25.586490869522095 +33,CUP,SUM,1,0,1,0,26,129,109,0.0 +33,SPOON,SUM,0,0,0,0,8,0,0,22.6729838848114 +33,,SUM,1,0,1,0,34,206,116,48.259474754333496 +33,, +34,, +34,BOWL,SUM,1,0,1,0,10,1247,53,0.0 +34,CUP,SUM,1,0,1,0,2,221,112,0.0 +34,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +34,,SUM,3,0,3,0,12,3049,165,0.0 +34,, +35,, +35,BOWL,SUM,1,0,1,0,0,1241,28,0.0 +35,CUP,SUM,0,0,0,0,0,5,4,12.96828579902649 +35,SPOON,SUM,0,0,0,0,4,78,0,23.940156936645508 +35,,SUM,1,0,1,0,4,1324,32,36.908442735672 +35,, +36,, +36,BOWL,SUM,0,0,0,0,0,6,2,14.210785865783691 +36,CUP,SUM,0,0,0,0,18,40,2,28.262330055236816 +36,SPOON,SUM,0,0,0,0,0,58,5,29.730287075042725 +36,,SUM,0,0,0,0,18,104,9,72.20340299606323 +36,, +37,, +37,BOWL,SUM,0,0,0,0,0,323,2,40.30579400062561 +37,CUP,SUM,0,0,0,0,0,38,4,12.771619081497192 +37,SPOON,SUM,0,0,0,0,0,33,11,41.81716799736023 +37,,SUM,0,0,0,0,0,394,17,94.89458107948303 +37,, +38,, +38,BOWL,SUM,0,0,0,0,0,114,2,23.842216968536377 +38,CUP,SUM,0,0,0,0,0,77,28,39.54249405860901 +38,SPOON,SUM,1,0,1,0,2,1567,5,0.0 +38,,SUM,1,0,1,0,2,1758,35,63.384711027145386 +38,, +39,, +39,BOWL,SUM,1,0,1,0,8,1517,13,0.0 +39,CUP,SUM,0,0,0,0,0,26,0,12.114723920822144 +39,SPOON,SUM,0,0,0,0,8,243,4,37.027223110198975 +39,,SUM,1,0,1,0,16,1786,17,49.14194703102112 +39,, +40,, +40,BOWL,SUM,1,0,1,0,0,933,70,0.0 +40,CUP,SUM,0,0,0,0,0,13,4,13.071056127548218 +40,SPOON,SUM,0,0,0,0,30,173,0,39.960164070129395 +40,,SUM,1,0,1,0,30,1119,74,53.03122019767761 +40,, +41,, +41,BOWL,SUM,1,0,1,0,0,1549,6,0.0 +41,CUP,SUM,0,0,0,0,10,13,6,23.908283948898315 +41,SPOON,SUM,0,0,0,0,0,76,4,21.21236801147461 +41,,SUM,1,0,1,0,10,1638,16,45.120651960372925 +41,, +42,, +42,BOWL,SUM,0,0,0,0,14,177,16,43.287765979766846 +42,CUP,SUM,1,0,1,0,0,374,106,0.0 +42,SPOON,SUM,0,0,0,0,34,131,2,46.55565309524536 +42,,SUM,1,0,1,0,48,682,124,89.8434190750122 +42,, +43,, +43,BOWL,SUM,0,0,0,0,0,39,4,19.90210795402527 +43,CUP,SUM,0,0,0,0,2,41,4,14.28514289855957 +43,SPOON,SUM,0,0,0,0,0,120,1,25.053864002227783 +43,,SUM,0,0,0,0,2,200,9,59.24111485481262 +43,, +44,, +44,BOWL,SUM,0,0,0,0,0,192,6,30.820032835006714 +44,CUP,SUM,1,0,1,0,0,775,53,0.0 +44,SPOON,SUM,0,0,0,0,0,22,0,16.17891001701355 +44,,SUM,1,0,1,0,0,989,59,46.998942852020264 +44,, +45,, +45,BOWL,SUM,0,0,0,0,0,46,6,25.13912296295166 +45,CUP,SUM,1,0,1,0,6,225,112,0.0 +45,SPOON,SUM,0,0,0,0,0,114,9,44.78759503364563 +45,,SUM,1,0,1,0,6,385,127,69.92671799659729 +45,, +46,, +46,BOWL,SUM,0,0,0,0,0,49,5,20.763957023620605 +46,CUP,SUM,1,0,1,0,2,206,111,0.0 +46,SPOON,SUM,0,0,0,0,0,118,0,23.122469186782837 +46,,SUM,1,0,1,0,2,373,116,43.88642621040344 +46,, +47,, +47,BOWL,SUM,0,0,0,0,0,26,0,14.366594076156616 +47,CUP,SUM,1,0,1,0,4,521,99,0.0 +47,SPOON,SUM,0,0,0,0,0,13,2,17.05501699447632 +47,,SUM,1,0,1,0,4,560,101,31.421611070632935 +47,, +48,, +48,BOWL,SUM,0,0,0,0,2,415,8,46.314335107803345 +48,CUP,SUM,0,0,0,0,0,17,11,17.968498945236206 +48,SPOON,SUM,0,0,0,0,0,37,0,18.874425172805786 +48,,SUM,0,0,0,0,2,469,19,83.15725922584534 +48,, +49,, +49,BOWL,SUM,0,0,0,0,14,662,11,75.74930500984192 +49,CUP,SUM,1,0,1,0,0,223,81,0.0 +49,SPOON,SUM,0,0,0,0,0,98,7,38.095966815948486 +49,,SUM,1,0,1,0,14,983,99,113.8452718257904 +49,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/kvr_last_run.csv b/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/kvr_last_run.csv new file mode 100644 index 0000000000..872d531eff --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/kvr_last_run.csv @@ -0,0 +1,144 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,0,90,5,26.146669149398804 +0,CUP,SUM,0,0,0,0,0,3,2,9.97815203666687 +0,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +0,,SUM,1,1,0,0,0,1612,7,36.124821186065674 +0,, +1,, +1,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +1,CUP,SUM,0,0,0,0,2,106,12,20.07645893096924 +1,SPOON,SUM,0,0,0,0,0,95,4,26.837361812591553 +1,,SUM,1,1,0,0,2,1720,16,46.91382074356079 +1,, +2,, +2,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +2,CUP,SUM,1,1,0,0,0,1519,0,0.0 +2,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +2,,SUM,3,3,0,0,0,4557,0,0.0 +2,, +3,, +3,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +3,CUP,SUM,0,0,0,0,0,48,6,15.514100790023804 +3,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +3,,SUM,2,2,0,0,0,3086,6,15.514100790023804 +3,, +4,, +4,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +4,CUP,SUM,1,1,0,0,0,1519,0,0.0 +4,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +4,,SUM,3,3,0,0,0,4557,0,0.0 +4,, +5,, +5,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +5,CUP,SUM,1,1,0,0,0,1519,0,0.0 +5,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +5,,SUM,3,3,0,0,0,4557,0,0.0 +5,, +6,, +6,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +6,CUP,SUM,1,1,0,0,0,1519,0,0.0 +6,SPOON,SUM,0,0,0,0,0,431,0,40.24056816101074 +6,,SUM,2,2,0,0,0,3469,0,40.24056816101074 +6,, +7,, +7,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +7,CUP,SUM,1,1,0,0,0,1519,0,0.0 +7,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +7,,SUM,3,3,0,0,0,4557,0,0.0 +7,, +8,, +8,BOWL,SUM,1,0,1,0,0,1589,0,0.0 +8,CUP,SUM,1,1,0,0,0,1519,0,0.0 +8,SPOON,SUM,0,0,0,0,0,0,0,15.104079961776733 +8,,SUM,2,1,1,0,0,3108,0,15.104079961776733 +8,, +9,, +9,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +9,CUP,SUM,1,1,0,0,0,1519,0,0.0 +9,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +9,,SUM,3,3,0,0,0,4557,0,0.0 +9,, +10,, +10,BOWL,SUM,0,0,0,0,32,23,0,28.552817821502686 +10,CUP,SUM,1,1,0,0,0,1519,0,0.0 +10,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +10,,SUM,2,2,0,0,32,3061,0,28.552817821502686 +10,, +11,, +11,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +11,CUP,SUM,1,1,0,0,0,1519,0,0.0 +11,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +11,,SUM,3,3,0,0,0,4557,0,0.0 +11,, +12,, +12,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +12,CUP,SUM,1,1,0,0,0,1519,0,0.0 +12,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +12,,SUM,3,3,0,0,0,4557,0,0.0 +12,, +13,, +13,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +13,CUP,SUM,0,0,0,0,0,4,1,11.309921979904175 +13,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +13,,SUM,2,2,0,0,0,3042,1,11.309921979904175 +13,, +14,, +14,BOWL,SUM,0,0,0,0,0,56,4,19.901787042617798 +14,CUP,SUM,1,1,0,0,0,1519,0,0.0 +14,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +14,,SUM,2,2,0,0,0,3094,4,19.901787042617798 +14,, +15,, +15,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +15,CUP,SUM,0,0,0,0,0,80,19,35.60285711288452 +15,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +15,,SUM,2,2,0,0,0,3118,19,35.60285711288452 +15,, +16,, +16,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +16,CUP,SUM,1,1,0,0,0,1519,0,0.0 +16,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +16,,SUM,3,3,0,0,0,4557,0,0.0 +16,, +17,, +17,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +17,CUP,SUM,1,1,0,0,0,1519,0,0.0 +17,SPOON,SUM,0,0,0,0,0,14,0,15.217566013336182 +17,,SUM,2,2,0,0,0,3052,0,15.217566013336182 +17,, +18,, +18,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +18,CUP,SUM,1,0,1,0,0,1658,0,0.0 +18,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +18,,SUM,3,2,1,0,0,4696,0,0.0 +18,, +19,, +19,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +19,CUP,SUM,1,0,1,0,0,1638,0,0.0 +19,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +19,,SUM,3,2,1,0,0,4676,0,0.0 +19,, +20,, +20,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +20,CUP,SUM,1,1,0,0,0,1519,0,0.0 +20,SPOON,SUM,1,0,1,0,8,1582,0,0.0 +20,,SUM,3,2,1,0,8,4620,0,0.0 +20,, +21,, +21,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +21,CUP,SUM,1,1,0,0,0,1519,0,0.0 +21,SPOON,SUM,0,0,0,0,6,103,10,27.39035391807556 +21,,SUM,2,2,0,0,6,3141,10,27.39035391807556 +21,, +22,, +22,BOWL,SUM,0,0,0,0,0,62,8,19.67384910583496 +22,CUP,SUM,0,0,0,0,0,12,10,15.023195028305054 +22,SPOON,SUM,1,0,1,0,0,1405,28,0.0 +22,,SUM,1,0,1,0,0,1479,46,34.697044134140015 +22,, +23,, +23,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +23,CUP,SUM,0,0,0,0,0,10,10,12.614169836044312 diff --git a/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/kvr_pr2_new_best.csv b/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/kvr_pr2_new_best.csv new file mode 100644 index 0000000000..872d531eff --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/kvr_pr2_new_best.csv @@ -0,0 +1,144 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,0,90,5,26.146669149398804 +0,CUP,SUM,0,0,0,0,0,3,2,9.97815203666687 +0,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +0,,SUM,1,1,0,0,0,1612,7,36.124821186065674 +0,, +1,, +1,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +1,CUP,SUM,0,0,0,0,2,106,12,20.07645893096924 +1,SPOON,SUM,0,0,0,0,0,95,4,26.837361812591553 +1,,SUM,1,1,0,0,2,1720,16,46.91382074356079 +1,, +2,, +2,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +2,CUP,SUM,1,1,0,0,0,1519,0,0.0 +2,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +2,,SUM,3,3,0,0,0,4557,0,0.0 +2,, +3,, +3,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +3,CUP,SUM,0,0,0,0,0,48,6,15.514100790023804 +3,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +3,,SUM,2,2,0,0,0,3086,6,15.514100790023804 +3,, +4,, +4,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +4,CUP,SUM,1,1,0,0,0,1519,0,0.0 +4,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +4,,SUM,3,3,0,0,0,4557,0,0.0 +4,, +5,, +5,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +5,CUP,SUM,1,1,0,0,0,1519,0,0.0 +5,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +5,,SUM,3,3,0,0,0,4557,0,0.0 +5,, +6,, +6,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +6,CUP,SUM,1,1,0,0,0,1519,0,0.0 +6,SPOON,SUM,0,0,0,0,0,431,0,40.24056816101074 +6,,SUM,2,2,0,0,0,3469,0,40.24056816101074 +6,, +7,, +7,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +7,CUP,SUM,1,1,0,0,0,1519,0,0.0 +7,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +7,,SUM,3,3,0,0,0,4557,0,0.0 +7,, +8,, +8,BOWL,SUM,1,0,1,0,0,1589,0,0.0 +8,CUP,SUM,1,1,0,0,0,1519,0,0.0 +8,SPOON,SUM,0,0,0,0,0,0,0,15.104079961776733 +8,,SUM,2,1,1,0,0,3108,0,15.104079961776733 +8,, +9,, +9,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +9,CUP,SUM,1,1,0,0,0,1519,0,0.0 +9,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +9,,SUM,3,3,0,0,0,4557,0,0.0 +9,, +10,, +10,BOWL,SUM,0,0,0,0,32,23,0,28.552817821502686 +10,CUP,SUM,1,1,0,0,0,1519,0,0.0 +10,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +10,,SUM,2,2,0,0,32,3061,0,28.552817821502686 +10,, +11,, +11,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +11,CUP,SUM,1,1,0,0,0,1519,0,0.0 +11,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +11,,SUM,3,3,0,0,0,4557,0,0.0 +11,, +12,, +12,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +12,CUP,SUM,1,1,0,0,0,1519,0,0.0 +12,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +12,,SUM,3,3,0,0,0,4557,0,0.0 +12,, +13,, +13,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +13,CUP,SUM,0,0,0,0,0,4,1,11.309921979904175 +13,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +13,,SUM,2,2,0,0,0,3042,1,11.309921979904175 +13,, +14,, +14,BOWL,SUM,0,0,0,0,0,56,4,19.901787042617798 +14,CUP,SUM,1,1,0,0,0,1519,0,0.0 +14,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +14,,SUM,2,2,0,0,0,3094,4,19.901787042617798 +14,, +15,, +15,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +15,CUP,SUM,0,0,0,0,0,80,19,35.60285711288452 +15,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +15,,SUM,2,2,0,0,0,3118,19,35.60285711288452 +15,, +16,, +16,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +16,CUP,SUM,1,1,0,0,0,1519,0,0.0 +16,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +16,,SUM,3,3,0,0,0,4557,0,0.0 +16,, +17,, +17,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +17,CUP,SUM,1,1,0,0,0,1519,0,0.0 +17,SPOON,SUM,0,0,0,0,0,14,0,15.217566013336182 +17,,SUM,2,2,0,0,0,3052,0,15.217566013336182 +17,, +18,, +18,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +18,CUP,SUM,1,0,1,0,0,1658,0,0.0 +18,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +18,,SUM,3,2,1,0,0,4696,0,0.0 +18,, +19,, +19,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +19,CUP,SUM,1,0,1,0,0,1638,0,0.0 +19,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +19,,SUM,3,2,1,0,0,4676,0,0.0 +19,, +20,, +20,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +20,CUP,SUM,1,1,0,0,0,1519,0,0.0 +20,SPOON,SUM,1,0,1,0,8,1582,0,0.0 +20,,SUM,3,2,1,0,8,4620,0,0.0 +20,, +21,, +21,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +21,CUP,SUM,1,1,0,0,0,1519,0,0.0 +21,SPOON,SUM,0,0,0,0,6,103,10,27.39035391807556 +21,,SUM,2,2,0,0,6,3141,10,27.39035391807556 +21,, +22,, +22,BOWL,SUM,0,0,0,0,0,62,8,19.67384910583496 +22,CUP,SUM,0,0,0,0,0,12,10,15.023195028305054 +22,SPOON,SUM,1,0,1,0,0,1405,28,0.0 +22,,SUM,1,0,1,0,0,1479,46,34.697044134140015 +22,, +23,, +23,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +23,CUP,SUM,0,0,0,0,0,10,10,12.614169836044312 diff --git a/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/kvr_pr2_orig_orig_best.csv b/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/kvr_pr2_orig_orig_best.csv new file mode 100644 index 0000000000..99afcf48a8 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/kvr_pr2_orig_orig_best.csv @@ -0,0 +1,63 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +20,, +20,BOWL,SUM,0,0,0,0,2,47,0,13.78581714630127 +20,CUP,SUM,1,0,0,1,2,188,58,0.0 +20,SPOON,SUM,0,0,0,0,0,125,0,20.95003318786621 +20,,SUM,1,0,0,1,4,360,58,34.73585033416748 +20,, +21,, +21,BOWL,SUM,0,0,0,0,0,53,0,13.247747898101807 +21,CUP,SUM,0,0,0,0,0,27,14,24.23551607131958 +21,SPOON,SUM,0,0,0,0,0,80,2,18.07046103477478 +21,,SUM,0,0,0,0,0,160,16,55.55372500419617 +21,, +22,, +22,BOWL,SUM,0,0,0,0,0,15,0,11.859118938446045 +22,CUP,SUM,0,0,0,0,0,33,13,19.584190845489502 +22,SPOON,SUM,0,0,0,0,16,63,2,24.22484803199768 +22,,SUM,0,0,0,0,16,111,15,55.66815781593323 +22,, +23,, +23,BOWL,SUM,0,0,0,0,0,13,0,10.66537094116211 +23,CUP,SUM,1,0,1,0,0,280,81,0.0 +23,SPOON,SUM,0,0,0,0,0,0,0,13.794100999832153 +23,,SUM,1,0,1,0,0,293,81,24.459471940994263 +23,, +24,, +24,BOWL,SUM,0,0,0,0,2,5,0,10.852939128875732 +24,CUP,SUM,1,0,0,1,0,185,51,0.0 +24,SPOON,SUM,0,0,0,0,0,35,0,15.279842853546143 +24,,SUM,1,0,0,1,2,225,51,26.132781982421875 +24,, +25,, +25,BOWL,SUM,0,0,0,0,0,17,0,10.735448837280273 +25,CUP,SUM,0,0,0,0,0,10,5,11.906934022903442 +25,SPOON,SUM,0,0,0,0,2,17,3,16.28773283958435 +25,,SUM,0,0,0,0,2,44,8,38.930115699768066 +25,, +26,, +26,BOWL,SUM,0,0,0,0,0,9,0,10.646228075027466 +26,CUP,SUM,1,0,0,1,0,228,54,0.0 +26,SPOON,SUM,0,0,0,0,0,29,0,14.428622961044312 +26,,SUM,1,0,0,1,0,266,54,25.074851036071777 +26,, +27,, +27,BOWL,SUM,0,0,0,0,0,0,0,10.294739961624146 +27,CUP,SUM,0,0,0,0,0,37,9,15.870995044708252 +27,SPOON,SUM,0,0,0,0,0,1,2,13.735243082046509 +27,,SUM,0,0,0,0,0,38,11,39.900978088378906 +27,, +28,, +28,BOWL,SUM,0,0,0,0,0,11,0,10.87513017654419 +28,CUP,SUM,0,0,0,0,0,22,1,10.793434143066406 +28,SPOON,SUM,0,0,0,0,0,49,0,15.872761011123657 +28,,SUM,0,0,0,0,0,82,1,37.54132533073425 +28,, +29,, +29,BOWL,SUM,0,0,0,0,2,11,0,11.241461992263794 +29,CUP,SUM,0,0,0,0,2,16,10,18.71555995941162 +29,SPOON,SUM,0,0,0,0,0,2,3,15.333929061889648 +29,,SUM,0,0,0,0,4,29,13,45.29095101356506 +29,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/kvr_pr2_orig_var_best.csv b/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/kvr_pr2_orig_var_best.csv new file mode 100644 index 0000000000..bb3024d8ba --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/kvr_pr2_orig_var_best.csv @@ -0,0 +1,123 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +30,, +30,BOWL,SUM,0,0,0,0,2,25,3,15.176192998886108 +30,CUP,SUM,1,0,0,1,0,311,72,0.0 +30,SPOON,SUM,0,0,0,0,0,82,3,21.904402017593384 +30,,SUM,1,0,0,1,2,418,78,37.08059501647949 +30,, +31,, +31,BOWL,SUM,0,0,0,0,2,17,1,14.191196918487549 +31,CUP,SUM,0,0,0,0,0,33,5,11.319457054138184 +31,SPOON,SUM,0,0,0,0,0,108,6,30.83554196357727 +31,,SUM,0,0,0,0,2,158,12,56.346195936203 +31,, +32,, +32,BOWL,SUM,0,0,0,0,0,29,2,12.624501943588257 +32,CUP,SUM,1,0,0,1,0,322,74,0.0 +32,SPOON,SUM,0,0,0,0,0,1,1,15.137447118759155 +32,,SUM,1,0,0,1,0,352,77,27.761949062347412 +32,, +33,, +33,BOWL,SUM,0,0,0,0,8,72,5,21.26604413986206 +33,CUP,SUM,0,0,0,0,2,37,2,15.092926025390625 +33,SPOON,SUM,0,0,0,0,0,52,0,17.986762046813965 +33,,SUM,0,0,0,0,10,161,7,54.34573221206665 +33,, +34,, +34,BOWL,SUM,0,0,0,0,0,58,0,14.654443979263306 +34,CUP,SUM,0,0,0,0,0,33,0,11.376353025436401 +34,SPOON,SUM,0,0,0,0,6,90,0,22.241242170333862 +34,,SUM,0,0,0,0,6,181,0,48.27203917503357 +34,, +35,, +35,BOWL,SUM,0,0,0,0,0,33,3,14.326218128204346 +35,CUP,SUM,0,0,0,0,0,9,6,10.497527122497559 +35,SPOON,SUM,0,0,0,0,4,114,0,22.181149005889893 +35,,SUM,0,0,0,0,4,156,9,47.0048942565918 +35,, +36,, +36,BOWL,SUM,1,0,1,0,56,709,92,0.0 +36,CUP,SUM,0,0,0,0,6,24,0,13.171665906906128 +36,SPOON,SUM,0,0,0,0,0,5,0,14.967988014221191 +36,,SUM,1,0,1,0,62,738,92,28.13965392112732 +36,, +37,, +37,BOWL,SUM,0,0,0,0,0,21,4,14.213629007339478 +37,CUP,SUM,0,0,0,0,0,10,2,10.409108877182007 +37,SPOON,SUM,0,0,0,0,4,9,11,27.090785026550293 +37,,SUM,0,0,0,0,4,40,17,51.71352291107178 +37,, +38,, +38,BOWL,SUM,0,0,0,0,0,23,4,14.445498943328857 +38,CUP,SUM,0,0,0,0,0,79,14,21.001418113708496 +38,SPOON,SUM,0,0,0,0,0,16,8,23.722058057785034 +38,,SUM,0,0,0,0,0,118,26,59.16897511482239 +38,, +39,, +39,BOWL,SUM,0,0,0,0,0,40,4,16.103780031204224 +39,CUP,SUM,0,0,0,0,2,11,0,11.215667009353638 +39,SPOON,SUM,0,0,0,0,0,1,1,16.523443937301636 +39,,SUM,0,0,0,0,2,52,5,43.8428909778595 +39,, +40,, +40,BOWL,SUM,0,0,0,0,0,12,0,12.185853958129883 +40,CUP,SUM,0,0,0,0,2,32,4,11.859659910202026 +40,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +40,,SUM,1,0,1,0,2,1625,4,24.04551386833191 +40,, +41,, +41,BOWL,SUM,0,0,0,0,0,55,0,14.7917799949646 +41,CUP,SUM,1,0,0,1,0,312,50,0.0 +41,SPOON,SUM,0,0,0,0,2,355,2,39.10470986366272 +41,,SUM,1,0,0,1,2,722,52,53.89648985862732 +41,, +42,, +42,BOWL,SUM,0,0,0,0,26,159,16,43.63910412788391 +42,CUP,SUM,0,0,0,0,0,37,5,19.566689014434814 +42,SPOON,SUM,0,0,0,0,0,78,5,25.31734800338745 +42,,SUM,0,0,0,0,26,274,26,88.52314114570618 +42,, +43,, +43,BOWL,SUM,0,0,0,0,0,41,3,16.09066605567932 +43,CUP,SUM,0,0,0,0,0,8,10,12.512807130813599 +43,SPOON,SUM,0,0,0,0,0,114,0,22.12491202354431 +43,,SUM,0,0,0,0,0,163,13,50.72838521003723 +43,, +44,, +44,BOWL,SUM,0,0,0,0,0,9,0,11.853585958480835 +44,CUP,SUM,0,0,0,0,0,4,6,10.589781999588013 +44,SPOON,SUM,0,0,0,0,0,25,1,17.042464017868042 +44,,SUM,0,0,0,0,0,38,7,39.48583197593689 +44,, +45,, +45,BOWL,SUM,0,0,0,0,2,10,2,13.216369867324829 +45,CUP,SUM,0,0,0,0,0,11,5,10.870016098022461 +45,SPOON,SUM,0,0,0,0,0,475,2,48.28839898109436 +45,,SUM,0,0,0,0,2,496,9,72.37478494644165 +45,, +46,, +46,BOWL,SUM,0,0,0,0,0,64,8,19.686548948287964 +46,CUP,SUM,0,0,0,0,0,9,0,10.32280707359314 +46,SPOON,SUM,0,0,0,0,0,1,1,16.505611896514893 +46,,SUM,0,0,0,0,0,74,9,46.514967918395996 +46,, +47,, +47,BOWL,SUM,0,0,0,0,0,55,3,15.032520771026611 +47,CUP,SUM,0,0,0,0,0,20,2,10.923398971557617 +47,SPOON,SUM,0,0,0,0,0,80,2,19.789910078048706 +47,,SUM,0,0,0,0,0,155,7,45.745829820632935 +47,, +48,, +48,BOWL,SUM,0,0,0,0,0,9,0,12.139205932617188 +48,CUP,SUM,0,0,0,0,0,58,15,30.707082986831665 +48,SPOON,SUM,0,0,0,0,0,23,6,19.366377115249634 +48,,SUM,0,0,0,0,0,90,21,62.212666034698486 +48,, +49,, +49,BOWL,SUM,0,0,0,0,0,8,0,12.491016149520874 +49,CUP,SUM,0,0,0,0,0,18,5,11.428593873977661 +49,SPOON,SUM,0,0,0,0,6,61,6,23.46119499206543 +49,,SUM,0,0,0,0,6,87,11,47.380805015563965 +49,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/kvr_pr2_orig_varhalf_best.csv b/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/kvr_pr2_orig_varhalf_best.csv new file mode 100644 index 0000000000..e856c5c9cc --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/old_10.12.2019/kvr_pr2_orig_varhalf_best.csv @@ -0,0 +1,291 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +50,, +50,BOWL,SUM,0,0,0,0,0,14,4,10.599961042404175 +50,CUP,SUM,0,0,0,0,0,5,0,6.82976508140564 +50,SPOON,SUM,1,0,1,0,2,1581,0,0.0 +50,,SUM,1,0,1,0,2,1600,4,17.429726123809814 +50,, +51,, +51,BOWL,SUM,0,0,0,0,0,12,0,8.819735050201416 +51,CUP,SUM,0,0,0,0,2,50,5,13.62477707862854 +51,SPOON,SUM,0,0,0,0,0,0,0,11.77640700340271 +51,,SUM,0,0,0,0,2,62,5,34.220919132232666 +51,, +52,, +52,BOWL,SUM,0,0,0,0,0,43,0,10.358792066574097 +52,CUP,SUM,0,0,0,0,2,12,4,7.626431941986084 +52,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +52,,SUM,1,0,1,0,2,1636,4,17.98522400856018 +52,, +53,, +53,BOWL,SUM,0,0,0,0,0,30,12,15.279633045196533 +53,CUP,SUM,0,0,0,0,0,16,7,8.061570882797241 +53,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +53,,SUM,1,0,1,0,0,1627,19,23.341203927993774 +53,, +54,, +54,BOWL,SUM,0,0,0,0,0,20,0,8.824887990951538 +54,CUP,SUM,0,0,0,0,0,46,2,7.7838640213012695 +54,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +54,,SUM,1,0,1,0,0,1647,2,16.608752012252808 +54,, +55,, +55,BOWL,SUM,0,0,0,0,0,22,2,9.265057802200317 +55,CUP,SUM,1,0,1,0,0,261,111,0.0 +55,SPOON,SUM,0,0,0,0,0,0,6,14.802527904510498 +55,,SUM,1,0,1,0,0,283,119,24.067585706710815 +55,, +56,, +56,BOWL,SUM,0,0,0,0,0,11,4,10.86034893989563 +56,CUP,SUM,0,0,0,0,0,32,1,9.013726949691772 +56,SPOON,SUM,0,0,0,0,0,0,7,16.014787197113037 +56,,SUM,0,0,0,0,0,43,12,35.88886308670044 +56,, +57,, +57,BOWL,SUM,0,0,0,0,0,12,0,8.734523057937622 +57,CUP,SUM,0,0,0,0,42,59,86,71.68465900421143 +57,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +57,,SUM,1,0,1,0,42,1652,86,80.41918206214905 +57,, +58,, +58,BOWL,SUM,0,0,0,0,0,18,3,10.268955945968628 +58,CUP,SUM,0,0,0,0,2,197,38,42.9977490901947 +58,SPOON,SUM,1,0,1,0,2,1326,42,0.0 +58,,SUM,1,0,1,0,4,1541,83,53.26670503616333 +58,, +59,, +59,BOWL,SUM,0,0,0,0,2,31,0,9.98353886604309 +59,CUP,SUM,0,0,0,0,0,30,14,18.098119020462036 +59,SPOON,SUM,0,0,0,0,6,6,3,15.140197038650513 +59,,SUM,0,0,0,0,8,67,17,43.22185492515564 +59,, +60,, +60,BOWL,SUM,0,0,0,0,0,37,0,10.481428861618042 +60,CUP,SUM,0,0,0,0,0,61,13,17.97027897834778 +60,SPOON,SUM,0,0,0,0,0,0,0,12.089012861251831 +60,,SUM,0,0,0,0,0,98,13,40.54072070121765 +60,, +61,, +61,BOWL,SUM,0,0,0,0,0,23,4,10.518329858779907 +61,CUP,SUM,0,0,0,0,2,10,8,8.249943971633911 +61,SPOON,SUM,0,0,0,0,0,33,5,15.682204961776733 +61,,SUM,0,0,0,0,2,66,17,34.45047879219055 +61,, +62,, +62,BOWL,SUM,0,0,0,0,2,3,0,9.43644905090332 +62,CUP,SUM,0,0,0,0,0,83,13,18.08749008178711 +62,SPOON,SUM,0,0,0,0,0,367,2,29.182981967926025 +62,,SUM,0,0,0,0,2,453,15,56.706921100616455 +62,, +63,, +63,BOWL,SUM,0,0,0,0,6,2,0,10.693027973175049 +63,CUP,SUM,0,0,0,0,0,104,22,19.450329065322876 +63,SPOON,SUM,1,0,1,0,2,1581,0,0.0 +63,,SUM,1,0,1,0,8,1687,22,30.143357038497925 +63,, +64,, +64,BOWL,SUM,1,0,1,0,0,1285,40,0.0 +64,CUP,SUM,0,0,0,0,0,35,0,7.634438991546631 +64,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +64,,SUM,2,0,2,0,0,2901,40,7.634438991546631 +64,, +65,, +65,BOWL,SUM,1,0,1,0,0,549,102,0.0 +65,CUP,SUM,0,0,0,0,0,26,1,7.4246909618377686 +65,SPOON,SUM,0,0,0,0,0,0,1,12.8157958984375 +65,,SUM,1,0,1,0,0,575,104,20.24048686027527 +65,, +66,, +66,BOWL,SUM,0,0,0,0,0,10,2,9.116393089294434 +66,CUP,SUM,0,0,0,0,38,52,13,29.734323978424072 +66,SPOON,SUM,0,0,0,0,0,34,29,28.66660189628601 +66,,SUM,0,0,0,0,38,96,44,67.51731896400452 +66,, +67,, +67,BOWL,SUM,1,1,0,0,160,78,0,0.0 +67,CUP,SUM,0,0,0,0,0,14,7,8.952981948852539 +67,SPOON,SUM,1,0,1,0,0,1582,0,0.0 +67,,SUM,2,1,1,0,160,1674,7,8.952981948852539 +67,, +68,, +68,BOWL,SUM,0,0,0,0,0,16,0,9.423910140991211 +68,CUP,SUM,0,0,0,0,0,26,10,12.244262933731079 +68,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +68,,SUM,1,0,1,0,0,1623,10,21.66817307472229 +68,, +69,, +69,BOWL,SUM,0,0,0,0,0,10,0,8.93390703201294 +69,CUP,SUM,1,0,0,1,0,285,51,0.0 +69,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +69,,SUM,2,0,1,1,0,1876,51,8.93390703201294 +69,, +70,, +70,BOWL,SUM,0,0,0,0,0,8,0,9.032894134521484 +70,CUP,SUM,1,0,1,0,4,244,71,0.0 +70,SPOON,SUM,0,0,0,0,0,176,4,23.54850196838379 +70,,SUM,1,0,1,0,4,428,75,32.58139610290527 +70,, +71,, +71,BOWL,SUM,0,0,0,0,0,13,0,9.875010013580322 +71,CUP,SUM,0,0,0,0,0,28,0,7.775708913803101 +71,SPOON,SUM,1,0,1,0,0,592,102,0.0 +71,,SUM,1,0,1,0,0,633,102,17.650718927383423 +71,, +72,, +72,BOWL,SUM,0,0,0,0,0,14,0,9.158792972564697 +72,CUP,SUM,1,0,0,1,0,242,53,0.0 +72,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +72,,SUM,2,0,1,1,0,1837,53,9.158792972564697 +72,, +73,, +73,BOWL,SUM,0,0,0,0,0,8,4,10.863928079605103 +73,CUP,SUM,0,0,0,0,0,14,7,9.10171389579773 +73,SPOON,SUM,0,0,0,0,0,0,1,13.112598180770874 +73,,SUM,0,0,0,0,0,22,12,33.078240156173706 +73,, +74,, +74,BOWL,SUM,1,0,1,0,0,1581,0,0.0 +74,CUP,SUM,0,0,0,0,0,298,40,46.43463110923767 +74,SPOON,SUM,0,0,0,0,0,11,2,14.50262999534607 +74,,SUM,1,0,1,0,0,1890,42,60.93726110458374 +74,, +75,, +75,BOWL,SUM,0,0,0,0,0,10,2,9.391451835632324 +75,CUP,SUM,0,0,0,0,2,5,8,8.284360885620117 +75,SPOON,SUM,0,0,0,0,0,27,0,12.70317792892456 +75,,SUM,0,0,0,0,2,42,10,30.378990650177002 +75,, +76,, +76,BOWL,SUM,0,0,0,0,2,17,8,13.663438081741333 +76,CUP,SUM,0,0,0,0,0,162,47,42.28623414039612 +76,SPOON,SUM,1,0,1,0,54,1062,0,0.0 +76,,SUM,1,0,1,0,56,1241,55,55.94967222213745 +76,, +77,, +77,BOWL,SUM,0,0,0,0,0,31,6,11.966325998306274 +77,CUP,SUM,1,0,0,1,0,305,51,0.0 +77,SPOON,SUM,0,0,0,0,0,77,1,16.68572688102722 +77,,SUM,1,0,0,1,0,413,58,28.652052879333496 +77,, +78,, +78,BOWL,SUM,0,0,0,0,0,7,0,9.105072021484375 +78,CUP,SUM,0,0,0,0,0,51,10,14.868062019348145 +78,SPOON,SUM,0,0,0,0,0,0,2,12.604153871536255 +78,,SUM,0,0,0,0,0,58,12,36.577287912368774 +78,, +79,, +79,BOWL,SUM,0,0,0,0,0,19,1,9.620437860488892 +79,CUP,SUM,1,0,1,0,0,143,112,0.0 +79,SPOON,SUM,1,0,1,0,0,899,78,0.0 +79,,SUM,2,0,2,0,0,1061,191,9.620437860488892 +79,, +80,, +80,BOWL,SUM,0,0,0,0,0,12,8,12.730754137039185 +80,CUP,SUM,0,0,0,0,0,18,5,10.660567045211792 +80,SPOON,SUM,0,0,0,0,0,6,13,20.492497205734253 +80,,SUM,0,0,0,0,0,36,26,43.88381838798523 +80,, +81,, +81,BOWL,SUM,0,0,0,0,0,14,8,13.050469160079956 +81,CUP,SUM,0,0,0,0,0,148,32,36.885241985321045 +81,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +81,,SUM,1,0,1,0,0,1743,40,49.935711145401 +81,, +82,, +82,BOWL,SUM,0,0,0,0,0,271,2,22.20917582511902 +82,CUP,SUM,0,0,0,0,0,85,30,29.510241985321045 +82,SPOON,SUM,1,0,1,0,10,1587,0,0.0 +82,,SUM,1,0,1,0,10,1943,32,51.71941781044006 +82,, +83,, +83,BOWL,SUM,0,0,0,0,0,14,0,9.251063823699951 +83,CUP,SUM,0,0,0,0,0,41,5,9.406798839569092 +83,SPOON,SUM,1,0,1,0,2,1581,0,0.0 +83,,SUM,1,0,1,0,2,1636,5,18.657862663269043 +83,, +84,, +84,BOWL,SUM,0,0,0,0,0,35,6,12.497748136520386 +84,CUP,SUM,1,0,1,0,4,320,110,0.0 +84,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +84,,SUM,2,0,2,0,4,1936,116,12.497748136520386 +84,, +85,, +85,BOWL,SUM,0,0,0,0,0,120,2,14.380787134170532 +85,CUP,SUM,0,0,0,0,6,93,31,36.29663109779358 +85,SPOON,SUM,0,0,0,0,0,38,0,14.628196001052856 +85,,SUM,0,0,0,0,6,251,33,65.30561423301697 +85,, +86,, +86,BOWL,SUM,1,0,1,0,0,1013,64,0.0 +86,CUP,SUM,0,0,0,0,0,20,4,8.184858083724976 +86,SPOON,SUM,0,0,0,0,0,0,2,12.805813074111938 +86,,SUM,1,0,1,0,0,1033,70,20.990671157836914 +86,, +87,, +87,BOWL,SUM,0,0,0,0,0,17,1,10.491102933883667 +87,CUP,SUM,0,0,0,0,2,106,30,27.989120960235596 +87,SPOON,SUM,0,0,0,0,0,2,7,17.713347911834717 +87,,SUM,0,0,0,0,2,125,38,56.19357180595398 +87,, +88,, +88,BOWL,SUM,1,0,1,0,0,491,102,0.0 +88,CUP,SUM,0,0,0,0,0,23,9,9.6980140209198 +88,SPOON,SUM,0,0,0,0,0,0,4,13.845911979675293 +88,,SUM,1,0,1,0,0,514,115,23.543926000595093 +88,, +89,, +89,BOWL,SUM,0,0,0,0,72,112,4,48.080251932144165 +89,CUP,SUM,0,0,0,0,0,17,2,9.52760910987854 +89,SPOON,SUM,0,0,0,0,0,4,2,12.896147966384888 +89,,SUM,0,0,0,0,72,133,8,70.50400900840759 +89,, +90,, +90,BOWL,SUM,1,0,1,0,0,714,88,0.0 +90,CUP,SUM,0,0,0,0,6,6,9,13.423007011413574 +90,SPOON,SUM,1,0,1,0,0,1590,0,0.0 +90,,SUM,2,0,2,0,6,2310,97,13.423007011413574 +90,, +91,, +91,BOWL,SUM,0,0,0,0,6,201,12,24.63028907775879 +91,CUP,SUM,1,0,0,1,0,357,58,0.0 +91,SPOON,SUM,0,0,0,0,0,0,14,19.229068994522095 +91,,SUM,1,0,0,1,6,558,84,43.859358072280884 +91,, +92,, +92,BOWL,SUM,0,0,0,0,0,11,0,9.569445133209229 +92,CUP,SUM,1,0,0,1,2,288,57,0.0 +92,SPOON,SUM,1,0,1,0,16,1452,0,0.0 +92,,SUM,2,0,1,1,18,1751,57,9.569445133209229 +92,, +93,, +93,BOWL,SUM,0,0,0,0,0,2,0,9.265429973602295 +93,CUP,SUM,0,0,0,0,0,5,0,7.2139599323272705 +93,SPOON,SUM,0,0,0,0,4,9,4,15.813823938369751 +93,,SUM,0,0,0,0,4,16,4,32.293213844299316 +93,, +94,, +94,BOWL,SUM,0,0,0,0,0,85,19,22.648711919784546 +94,CUP,SUM,0,0,0,0,0,22,2,8.69812798500061 +94,SPOON,SUM,0,0,0,0,4,4,10,19.86899209022522 +94,,SUM,0,0,0,0,4,111,31,51.215831995010376 +94,, +95,, +95,BOWL,SUM,0,0,0,0,0,32,0,10.771960020065308 +95,CUP,SUM,1,0,0,1,0,338,54,0.0 +95,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +95,,SUM,2,0,1,1,0,1951,54,10.771960020065308 +95,, +96,, +96,BOWL,SUM,0,0,0,0,0,39,6,13.384937047958374 +96,CUP,SUM,0,0,0,0,0,27,4,8.436053037643433 +96,SPOON,SUM,1,0,1,0,0,1582,0,0.0 +96,,SUM,1,0,1,0,0,1648,10,21.820990085601807 +96,, +97,, +97,BOWL,SUM,1,0,1,0,0,933,76,0.0 +97,CUP,SUM,1,0,0,1,0,251,55,0.0 +97,SPOON,SUM,0,0,0,0,4,311,0,28.879663944244385 +97,,SUM,2,0,1,1,4,1495,131,28.879663944244385 +97,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/failures_VR.csv b/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/failures_VR.csv new file mode 100644 index 0000000000..b97e7bdfad --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/failures_VR.csv @@ -0,0 +1,113 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,0,90,5,26.146669149398804 +0,CUP,SUM,0,0,0,0,0,3,2,9.97815203666687 +0,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +0,,SUM,1,1,0,0,0,1612,7,36.124821186065674 +0,, +1,, +1,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +1,CUP,SUM,0,0,0,0,2,106,12,20.07645893096924 +1,SPOON,SUM,0,0,0,0,0,95,4,26.837361812591553 +1,,SUM,1,1,0,0,2,1720,16,46.91382074356079 +1,, +2,, +2,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +2,CUP,SUM,1,1,0,0,0,1519,0,0.0 +2,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +2,,SUM,3,3,0,0,0,4557,0,0.0 +2,, +3,, +3,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +3,CUP,SUM,0,0,0,0,0,48,6,15.514100790023804 +3,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +3,,SUM,2,2,0,0,0,3086,6,15.514100790023804 +3,, +4,, +4,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +4,CUP,SUM,1,1,0,0,0,1519,0,0.0 +4,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +4,,SUM,3,3,0,0,0,4557,0,0.0 +4,, +5,, +5,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +5,CUP,SUM,1,1,0,0,0,1519,0,0.0 +5,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +5,,SUM,3,3,0,0,0,4557,0,0.0 +5,, +6,, +6,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +6,CUP,SUM,1,1,0,0,0,1519,0,0.0 +6,SPOON,SUM,0,0,0,0,0,431,0,40.24056816101074 +6,,SUM,2,2,0,0,0,3469,0,40.24056816101074 +6,, +7,, +7,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +7,CUP,SUM,1,1,0,0,0,1519,0,0.0 +7,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +7,,SUM,3,3,0,0,0,4557,0,0.0 +7,, +8,, +8,BOWL,SUM,1,0,1,0,0,1589,0,0.0 +8,CUP,SUM,1,1,0,0,0,1519,0,0.0 +8,SPOON,SUM,0,0,0,0,0,0,0,15.104079961776733 +8,,SUM,2,1,1,0,0,3108,0,15.104079961776733 +8,, +9,, +9,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +9,CUP,SUM,1,1,0,0,0,1519,0,0.0 +9,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +9,,SUM,3,3,0,0,0,4557,0,0.0 +9,, +10,, +10,BOWL,SUM,0,0,0,0,32,23,0,28.552817821502686 +10,CUP,SUM,1,1,0,0,0,1519,0,0.0 +10,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +10,,SUM,2,2,0,0,32,3061,0,28.552817821502686 +10,, +11,, +11,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +11,CUP,SUM,1,1,0,0,0,1519,0,0.0 +11,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +11,,SUM,3,3,0,0,0,4557,0,0.0 +11,, +12,, +12,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +12,CUP,SUM,1,1,0,0,0,1519,0,0.0 +12,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +12,,SUM,3,3,0,0,0,4557,0,0.0 +12,, +13,, +13,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +13,CUP,SUM,0,0,0,0,0,4,1,11.309921979904175 +13,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +13,,SUM,2,2,0,0,0,3042,1,11.309921979904175 +13,, +14,, +14,BOWL,SUM,0,0,0,0,0,56,4,19.901787042617798 +14,CUP,SUM,1,1,0,0,0,1519,0,0.0 +14,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +14,,SUM,2,2,0,0,0,3094,4,19.901787042617798 +14,, +15,, +15,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +15,CUP,SUM,0,0,0,0,0,80,19,35.60285711288452 +15,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +15,,SUM,2,2,0,0,0,3118,19,35.60285711288452 +15,, +16,, +16,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +16,CUP,SUM,1,1,0,0,0,1519,0,0.0 +16,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +16,,SUM,3,3,0,0,0,4557,0,0.0 +16,, +17,, +17,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +17,CUP,SUM,1,1,0,0,0,1519,0,0.0 +17,SPOON,SUM,0,0,0,0,0,14,0,15.217566013336182 +17,,SUM,2,2,0,0,0,3052,0,15.217566013336182 +17,, +18,, +18,BOWL,SUM,1,1,0,0,0,1519,0,0.0 diff --git a/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/heur_boxy_new.csv b/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/heur_boxy_new.csv new file mode 100644 index 0000000000..2838427ce5 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/heur_boxy_new.csv @@ -0,0 +1,1206 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,6,6,15.7989089489 +0,CUP,SUM,0,0,0,0,2,3,8,8.3967828751 +0,SPOON,SUM,0,0,0,0,0,1,0,11.3606410027 +0,,SUM,0,0,0,0,2,10,14,35.5563328266 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,16,11,0,15.0820300579 +1,CUP,SUM,0,0,0,0,0,3,20,14.1886210442 +1,SPOON,SUM,0,0,0,0,0,1,0,11.2034759521 +1,,SUM,0,0,0,0,16,15,20,40.4741270542 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,8,5,0,11.8901760578 +2,CUP,SUM,0,0,0,0,0,3,8,7.711370945 +2,SPOON,SUM,0,0,0,0,8,17,0,14.9883639812 +2,,SUM,0,0,0,0,16,25,8,34.589910984 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,16,7,41,32.0300071239 +3,CUP,SUM,0,0,0,0,0,5,77,27.8288981915 +3,SPOON,SUM,1,0,1,0,0,23,19,0 +3,,SUM,1,0,1,0,16,35,137,59.8589053154 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,3,0,7.6659319401 +4,CUP,SUM,0,0,0,0,2,5,38,15.7413299084 +4,SPOON,SUM,1,0,1,0,0,342,0,0 +4,,SUM,1,0,1,0,2,350,38,23.4072618484 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,0,2,1,10.6052951813 +5,CUP,SUM,0,0,0,0,8,6,17,15.5771460533 +5,SPOON,SUM,1,0,1,0,0,9,11,0 +5,,SUM,1,0,1,0,8,17,29,26.1824412346 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,24,5,0,19.4739069939 +6,CUP,SUM,0,0,0,0,0,8,8,7.7932510376 +6,SPOON,SUM,1,0,1,0,0,20,11,0 +6,,SUM,1,0,1,0,24,33,19,27.2671580315 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,0,5,12,11.8866109848 +7,CUP,SUM,0,0,0,0,0,6,8,7.5841121674 +7,SPOON,SUM,1,0,1,0,0,41,10,0 +7,,SUM,1,0,1,0,0,52,30,19.4707231522 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,0,8,21,18.0371940136 +8,CUP,SUM,0,0,0,0,0,10,23,13.657638073 +8,SPOON,SUM,1,0,1,0,0,66,10,0 +8,,SUM,1,0,1,0,0,84,54,31.6948320866 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,1,0,7.8348038197 +9,CUP,SUM,0,0,0,0,8,6,8,11.8644549847 +9,SPOON,SUM,0,0,0,0,0,12,1,12.2061028481 +9,,SUM,0,0,0,0,8,19,9,31.9053616524 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,4,7,15.7883968353 +10,CUP,SUM,0,0,0,0,0,12,8,9.3832139969 +10,SPOON,SUM,0,0,0,0,0,3,0,11.7502429485 +10,,SUM,0,0,0,0,0,19,15,36.9218537807 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,0,1,1,8.5644159317 +11,CUP,SUM,0,0,0,0,0,10,28,19.3353888988 +11,SPOON,SUM,0,0,0,0,0,3,2,13.7747700214 +11,,SUM,0,0,0,0,0,14,31,41.674574852 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,1,0,1,0,8,12,20,0 +12,CUP,SUM,0,0,0,0,0,4,16,16.2316439152 +12,SPOON,SUM,0,0,0,0,2,2,4,13.7078499794 +12,,SUM,1,0,1,0,10,18,40,29.9394938946 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,0,6,4,10.5884041786 +13,CUP,SUM,1,0,1,0,0,10,55,0 +13,SPOON,SUM,0,0,0,0,0,0,0,10.3811428547 +13,,SUM,1,0,1,0,0,16,59,20.9695470333 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,0,8,32,18.9185340405 +14,CUP,SUM,0,0,0,0,0,1,8,7.8663451672 +14,SPOON,SUM,0,0,0,0,0,5,7,16.8005578518 +14,,SUM,0,0,0,0,0,14,47,43.5854370594 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,0,5,0,8.3545849323 +15,CUP,SUM,1,0,1,0,24,8,114,0 +15,SPOON,SUM,0,0,0,0,0,5,0,11.1025650501 +15,,SUM,1,0,1,0,24,18,114,19.4571499825 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,1,1,0,0,0,42,0,0 +16,CUP,SUM,1,1,0,0,0,42,0,0 +16,SPOON,SUM,1,1,0,0,0,42,0,0 +16,,SUM,3,3,0,0,0,126,0,0 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,8,27,21,25.2107310295 +17,CUP,SUM,1,1,0,0,0,42,0,0 +17,SPOON,SUM,0,0,0,0,16,28,0,23.3357667923 +17,,SUM,1,1,0,0,24,97,21,48.5464978218 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,0,3,0,8.2551240921 +18,CUP,SUM,0,0,0,0,0,5,54,25.2994511127 +18,SPOON,SUM,0,0,0,0,0,1,0,10.6246819496 +18,,SUM,0,0,0,0,0,9,54,44.1792571545 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,0,0,8.556732893 +19,CUP,SUM,0,0,0,0,0,5,9,9.7596869469 +19,SPOON,SUM,1,0,1,0,8,9,11,0 +19,,SUM,1,0,1,0,8,14,20,18.3164198399 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,0,6,0,7.9355909824 +20,CUP,SUM,0,0,0,0,0,19,47,22.8868961334 +20,SPOON,SUM,0,0,0,0,0,0,0,10.7301909924 +20,,SUM,0,0,0,0,0,25,47,41.5526781082 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,1,0,1,0,2,11,44,0 +21,CUP,SUM,0,0,0,0,0,8,9,9.1454179287 +21,SPOON,SUM,0,0,0,0,0,5,0,10.8612658978 +21,,SUM,1,0,1,0,2,24,53,20.0066838264 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,8,22,0,12.7297110558 +22,CUP,SUM,0,0,0,0,32,6,21,29.9222960472 +22,SPOON,SUM,1,0,1,0,0,15,11,0 +22,,SUM,1,0,1,0,40,43,32,42.652007103 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,2,8,17.9260070324 +23,CUP,SUM,1,0,1,0,0,38,40,0 +23,SPOON,SUM,0,0,0,0,0,2,0,10.7280480862 +23,,SUM,1,0,1,0,0,42,48,28.6540551186 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,0,3,0,8.613795042 +24,CUP,SUM,0,0,0,0,0,1,9,9.6961321831 +24,SPOON,SUM,0,0,0,0,0,2,0,10.6809098721 +24,,SUM,0,0,0,0,0,6,9,28.9908370972 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,1,1,0,0,0,42,0,0 +25,CUP,SUM,1,0,1,0,0,19,60,0 +25,SPOON,SUM,0,0,0,0,0,5,17,26.0749690533 +25,,SUM,2,1,1,0,0,66,77,26.0749690533 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,0,6,12,13.8332350254 +26,CUP,SUM,0,0,0,0,0,6,14,10.3836598396 +26,SPOON,SUM,0,0,0,0,0,1,0,11.5986471176 +26,,SUM,0,0,0,0,0,13,26,35.8155419827 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,0,0,1,9.1369149685 +27,CUP,SUM,0,0,0,0,0,24,14,12.5124130249 +27,SPOON,SUM,1,0,1,0,0,341,0,0 +27,,SUM,1,0,1,0,0,365,15,21.6493279934 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,16,1,0,14.2331030369 +28,CUP,SUM,1,0,1,0,0,73,81,0 +28,SPOON,SUM,0,0,0,0,0,7,20,19.1855859756 +28,,SUM,1,0,1,0,16,81,101,33.4186890125 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,0,0,0,7.7040529251 +29,CUP,SUM,0,0,0,0,0,3,32,15.3843021393 +29,SPOON,SUM,1,0,1,0,0,20,44,0 +29,,SUM,1,0,1,0,0,23,76,23.0883550644 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,48,4,4,29.9289579391 +30,CUP,SUM,0,0,0,0,0,3,8,8.5302209854 +30,SPOON,SUM,1,0,1,0,8,57,10,0 +30,,SUM,1,0,1,0,56,64,22,38.4591789246 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,1,0,1,0,0,53,30,0 +31,CUP,SUM,0,0,0,0,0,8,9,9.8512098789 +31,SPOON,SUM,0,0,0,0,0,3,0,11.2837209702 +31,,SUM,1,0,1,0,0,64,39,21.1349308491 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,2,26,9,15.8571550846 +32,CUP,SUM,0,0,0,0,0,11,15,11.2879869938 +32,SPOON,SUM,0,0,0,0,2,0,0,11.4098339081 +32,,SUM,0,0,0,0,4,37,24,38.5549759865 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,5,1,9.4858760834 +33,CUP,SUM,0,0,0,0,8,6,9,14.161864996 +33,SPOON,SUM,0,0,0,0,16,28,10,29.0999810696 +33,,SUM,0,0,0,0,24,39,20,52.7477221489 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,0,2,16,14.5165309906 +34,CUP,SUM,1,0,1,0,10,24,125,0 +34,SPOON,SUM,0,0,0,0,16,5,4,19.2714159489 +34,,SUM,1,0,1,0,26,31,145,33.7879469395 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,0,3,0,8.1997702122 +35,CUP,SUM,0,0,0,0,0,11,8,8.203690052 +35,SPOON,SUM,0,0,0,0,0,0,0,11.3666920662 +35,,SUM,0,0,0,0,0,14,8,27.7701523304 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,0,14,1,11.3382301331 +36,CUP,SUM,1,0,1,0,0,4,38,0 +36,SPOON,SUM,0,0,0,0,0,0,0,10.2406609058 +36,,SUM,1,0,1,0,0,18,39,21.5788910389 +36,,,,,,,,,, +37,,,,,,,,,, +37,BOWL,SUM,1,0,1,0,8,10,41,0 +37,CUP,SUM,0,0,0,0,0,2,8,9.0133681297 +37,SPOON,SUM,0,0,0,0,0,2,8,15.4804620743 +37,,SUM,1,0,1,0,8,14,57,24.493830204 +37,,,,,,,,,, +38,,,,,,,,,, +38,BOWL,SUM,0,0,0,0,0,0,0,7.6489210129 +38,CUP,SUM,0,0,0,0,0,2,20,11.286206007 +38,SPOON,SUM,0,0,0,0,0,7,0,10.8063669205 +38,,SUM,0,0,0,0,0,9,20,29.7414939404 +38,,,,,,,,,, +39,,,,,,,,,, +39,BOWL,SUM,0,0,0,0,8,61,0,15.7717840672 +39,CUP,SUM,0,0,0,0,0,2,25,13.7106769085 +39,SPOON,SUM,0,0,0,0,16,11,0,19.0684878826 +39,,SUM,0,0,0,0,24,74,25,48.5509488583 +39,,,,,,,,,, +40,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,0,4,9,12.2625281811 +40,CUP,SUM,0,0,0,0,0,8,10,9.947715044 +40,SPOON,SUM,0,0,0,0,0,4,8,11.8111031055 +40,,SUM,0,0,0,0,0,16,27,34.0213463306 +40,,,,,,,,,, +41,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,8,2,0,12.0384340286 +41,CUP,SUM,0,0,0,0,0,5,8,9.573007822 +41,SPOON,SUM,1,0,1,0,2,120,8,0 +41,,SUM,1,0,1,0,10,127,16,21.6114418507 +41,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,0,15,0,8.8791720867 +42,CUP,SUM,0,0,0,0,0,1,18,13.2037460804 +42,SPOON,SUM,0,0,0,0,0,1,0,10.9812421799 +42,,SUM,0,0,0,0,0,17,18,33.064160347 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,8,6,16,17.123814106 +43,CUP,SUM,0,0,0,0,0,8,29,20.8613641262 +43,SPOON,SUM,0,0,0,0,0,12,0,11.2136998177 +43,,SUM,0,0,0,0,8,26,45,49.1988780499 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,0,6,4,12.8930578232 +44,CUP,SUM,1,0,1,0,0,10,91,0 +44,SPOON,SUM,0,0,0,0,0,5,0,10.8758749962 +44,,SUM,1,0,1,0,0,21,95,23.7689328194 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,0,25,1,11.1726751328 +45,CUP,SUM,0,0,0,0,0,11,84,33.2223689556 +45,SPOON,SUM,1,1,0,0,0,72,0,0 +45,,SUM,1,1,0,0,0,108,85,44.3950440884 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,0,1,5,10.3954000473 +46,CUP,SUM,1,0,1,0,0,14,77,0 +46,SPOON,SUM,0,0,0,0,0,2,0,11.46935606 +46,,SUM,1,0,1,0,0,17,82,21.8647561073 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,1,1,0,0,0,42,0,0 +47,CUP,SUM,1,1,0,0,0,42,0,0 +47,SPOON,SUM,0,0,0,0,0,5,4,12.9049758911 +47,,SUM,2,2,0,0,0,89,4,12.9049758911 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,0,1,0,7.9808881283 +48,CUP,SUM,0,0,0,0,0,2,12,12.1390988827 +48,SPOON,SUM,0,0,0,0,0,11,0,11.8105919361 +48,,SUM,0,0,0,0,0,14,12,31.9305789471 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,0,10,0,8.1406919956 +49,CUP,SUM,0,0,0,0,2,9,8,10.4428071976 +49,SPOON,SUM,0,0,0,0,0,3,0,11.1029160023 +49,,SUM,0,0,0,0,2,22,8,29.6864151955 +49,,,,,,,,,, +50,,,,,,,,,, +50,BOWL,SUM,1,0,1,0,2,7,44,0 +50,CUP,SUM,1,0,1,0,0,4,61,0 +50,SPOON,SUM,0,0,0,0,8,1,2,14.6231129169 +50,,SUM,2,0,2,0,10,12,107,14.6231129169 +50,,,,,,,,,, +51,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,0,3,0,9.517457962 +51,CUP,SUM,0,0,0,0,0,18,108,40.1570248604 +51,SPOON,SUM,0,0,0,0,0,2,0,11.0952630043 +51,,SUM,0,0,0,0,0,23,108,60.7697458267 +51,,,,,,,,,, +52,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,2,2,1,9.1849300861 +52,CUP,SUM,0,0,0,0,2,4,12,8.7280049324 +52,SPOON,SUM,0,0,0,0,40,14,0,28.5264849663 +52,,SUM,0,0,0,0,44,20,13,46.4394199848 +52,,,,,,,,,, +53,,,,,,,,,, +53,BOWL,SUM,0,0,0,0,0,18,4,12.4301438332 +53,CUP,SUM,0,0,0,0,0,4,8,7.7957139015 +53,SPOON,SUM,1,1,0,0,0,72,0,0 +53,,SUM,1,1,0,0,0,94,12,20.2258577347 +53,,,,,,,,,, +54,,,,,,,,,, +54,BOWL,SUM,0,0,0,0,24,29,0,19.955477953 +54,CUP,SUM,1,0,0,1,0,20,53,0 +54,SPOON,SUM,1,0,1,0,0,26,44,0 +54,,SUM,2,0,1,1,24,75,97,19.955477953 +54,,,,,,,,,, +55,,,,,,,,,, +55,BOWL,SUM,0,0,0,0,0,2,0,8.2090289593 +55,CUP,SUM,0,0,0,0,0,5,9,10.2763059139 +55,SPOON,SUM,0,0,0,0,0,1,8,15.3454201221 +55,,SUM,0,0,0,0,0,8,17,33.8307549953 +55,,,,,,,,,, +56,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,10,43,4,17.6249010563 +56,CUP,SUM,1,0,1,0,0,9,46,0 +56,SPOON,SUM,0,0,0,0,0,3,0,10.68334198 +56,,SUM,1,0,1,0,10,55,50,28.3082430363 +56,,,,,,,,,, +57,,,,,,,,,, +57,BOWL,SUM,0,0,0,0,4,5,0,9.7522201538 +57,CUP,SUM,0,0,0,0,0,0,8,7.8045890331 +57,SPOON,SUM,0,0,0,0,0,8,0,11.6346371174 +57,,SUM,0,0,0,0,4,13,8,29.1914463043 +57,,,,,,,,,, +58,,,,,,,,,, +58,BOWL,SUM,0,0,0,0,0,0,4,14.4267239571 +58,CUP,SUM,0,0,0,0,0,3,23,13.5170929432 +58,SPOON,SUM,1,0,1,0,0,53,10,0 +58,,SUM,1,0,1,0,0,56,37,27.9438169003 +58,,,,,,,,,, +59,,,,,,,,,, +59,BOWL,SUM,0,0,0,0,0,4,1,9.4996738434 +59,CUP,SUM,0,0,0,0,0,31,50,27.3361949921 +59,SPOON,SUM,0,0,0,0,8,9,0,14.4981529713 +59,,SUM,0,0,0,0,8,44,51,51.3340218067 +59,,,,,,,,,, +60,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,0,7,7,11.9396460056 +60,CUP,SUM,0,0,0,0,8,29,49,35.7933499813 +60,SPOON,SUM,1,0,1,0,0,342,0,0 +60,,SUM,1,0,1,0,8,378,56,47.7329959869 +60,,,,,,,,,, +61,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,0,2,1,9.1835758686 +61,CUP,SUM,1,0,1,0,8,18,165,0 +61,SPOON,SUM,0,0,0,0,8,2,1,14.9727959633 +61,,SUM,1,0,1,0,16,22,167,24.1563718319 +61,,,,,,,,,, +62,,,,,,,,,, +62,BOWL,SUM,0,0,0,0,0,0,0,8.4736099243 +62,CUP,SUM,1,0,1,0,10,12,132,0 +62,SPOON,SUM,0,0,0,0,8,1,0,15.6323661804 +62,,SUM,1,0,1,0,18,13,132,24.1059761047 +62,,,,,,,,,, +63,,,,,,,,,, +63,BOWL,SUM,1,0,1,0,0,6,44,0 +63,CUP,SUM,0,0,0,0,16,3,15,19.9689090252 +63,SPOON,SUM,0,0,0,0,0,4,12,16.4342830181 +63,,SUM,1,0,1,0,16,13,71,36.4031920433 +63,,,,,,,,,, +64,,,,,,,,,, +64,BOWL,SUM,1,0,1,0,0,9,38,0 +64,CUP,SUM,0,0,0,0,0,1,20,11.6264269352 +64,SPOON,SUM,0,0,0,0,0,1,0,11.3121669292 +64,,SUM,1,0,1,0,0,11,58,22.9385938644 +64,,,,,,,,,, +65,,,,,,,,,, +65,BOWL,SUM,1,0,0,1,0,9,39,0 +65,CUP,SUM,1,0,1,0,24,15,11,0 +65,SPOON,SUM,0,0,0,0,0,4,0,11.4336879253 +65,,SUM,2,0,1,1,24,28,50,11.4336879253 +65,,,,,,,,,, +66,,,,,,,,,, +66,BOWL,SUM,0,0,0,0,8,5,0,11.3199560642 +66,CUP,SUM,0,0,0,0,0,11,16,12.1162080765 +66,SPOON,SUM,1,0,1,0,16,342,0,0 +66,,SUM,1,0,1,0,24,358,16,23.4361641407 +66,,,,,,,,,, +67,,,,,,,,,, +67,BOWL,SUM,0,0,0,0,0,3,1,9.0403380394 +67,CUP,SUM,1,0,1,0,0,9,120,0 +67,SPOON,SUM,0,0,0,0,16,1,0,17.8474371433 +67,,SUM,1,0,1,0,16,13,121,26.8877751827 +67,,,,,,,,,, +68,,,,,,,,,, +68,BOWL,SUM,0,0,0,0,16,18,9,20.1750719547 +68,CUP,SUM,0,0,0,0,0,3,14,11.3902609348 +68,SPOON,SUM,0,0,0,0,0,10,6,13.7627129555 +68,,SUM,0,0,0,0,16,31,29,45.328045845 +68,,,,,,,,,, +69,,,,,,,,,, +69,BOWL,SUM,0,0,0,0,2,3,5,11.9049670696 +69,CUP,SUM,0,0,0,0,0,4,8,8.1408231258 +69,SPOON,SUM,0,0,0,0,0,0,0,10.791675806 +69,,SUM,0,0,0,0,2,7,13,30.8374660015 +69,,,,,,,,,, +70,,,,,,,,,, +70,BOWL,SUM,0,0,0,0,0,5,20,15.617194891 +70,CUP,SUM,1,0,1,0,8,311,12,0 +70,SPOON,SUM,1,1,0,0,0,42,0,0 +70,,SUM,2,1,1,0,8,358,32,15.617194891 +70,,,,,,,,,, +71,,,,,,,,,, +71,BOWL,SUM,0,0,0,0,0,4,0,8.889605999 +71,CUP,SUM,1,0,1,0,2,22,55,0 +71,SPOON,SUM,0,0,0,0,0,0,0,11.9026219845 +71,,SUM,1,0,1,0,2,26,55,20.7922279835 +71,,,,,,,,,, +72,,,,,,,,,, +72,BOWL,SUM,0,0,0,0,0,3,0,8.3523201942 +72,CUP,SUM,0,0,0,0,0,11,9,11.3410670757 +72,SPOON,SUM,1,0,1,0,0,14,11,0 +72,,SUM,1,0,1,0,0,28,20,19.69338727 +72,,,,,,,,,, +73,,,,,,,,,, +73,BOWL,SUM,0,0,0,0,0,1,0,8.1731960773 +73,CUP,SUM,0,0,0,0,0,5,57,23.8641250134 +73,SPOON,SUM,0,0,0,0,0,2,0,11.1556720734 +73,,SUM,0,0,0,0,0,8,57,43.1929931641 +73,,,,,,,,,, +74,,,,,,,,,, +74,BOWL,SUM,0,0,0,0,0,0,0,8.307060957 +74,CUP,SUM,1,1,0,0,0,42,0,0 +74,SPOON,SUM,0,0,0,0,0,12,0,13.5193171501 +74,,SUM,1,1,0,0,0,54,0,21.8263781071 +74,,,,,,,,,, +75,,,,,,,,,, +75,BOWL,SUM,1,0,1,0,2,49,10,0 +75,CUP,SUM,0,0,0,0,8,3,22,19.3627328873 +75,SPOON,SUM,0,0,0,0,0,3,0,11.9470798969 +75,,SUM,1,0,1,0,10,55,32,31.3098127842 +75,,,,,,,,,, +76,,,,,,,,,, +76,BOWL,SUM,0,0,0,0,0,1,0,7.545732975 +76,CUP,SUM,0,0,0,0,2,5,48,25.6370260715 +76,SPOON,SUM,1,0,1,0,0,29,14,0 +76,,SUM,1,0,1,0,2,35,62,33.1827590466 +76,,,,,,,,,, +77,,,,,,,,,, +77,BOWL,SUM,0,0,0,0,0,13,31,26.2335560322 +77,CUP,SUM,1,0,1,0,0,8,42,0 +77,SPOON,SUM,0,0,0,0,0,6,0,10.8221240044 +77,,SUM,1,0,1,0,0,27,73,37.0556800365 +77,,,,,,,,,, +78,,,,,,,,,, +78,BOWL,SUM,0,0,0,0,24,19,0,22.076818943 +78,CUP,SUM,1,0,1,0,0,20,99,0 +78,SPOON,SUM,0,0,0,0,8,5,0,16.2747468948 +78,,SUM,1,0,1,0,32,44,99,38.3515658379 +78,,,,,,,,,, +79,,,,,,,,,, +79,BOWL,SUM,1,0,1,0,0,69,9,0 +79,CUP,SUM,0,0,0,0,0,2,8,8.0221960545 +79,SPOON,SUM,0,0,0,0,8,5,5,18.5069761276 +79,,SUM,1,0,1,0,8,76,22,26.5291721821 +79,,,,,,,,,, +80,,,,,,,,,, +80,BOWL,SUM,0,0,0,0,4,3,8,14.3890018463 +80,CUP,SUM,1,1,0,0,0,42,0,0 +80,SPOON,SUM,1,1,0,0,0,72,0,0 +80,,SUM,2,2,0,0,4,117,8,14.3890018463 +80,,,,,,,,,, +81,,,,,,,,,, +81,BOWL,SUM,0,0,0,0,0,5,17,17.2387650013 +81,CUP,SUM,1,0,1,0,16,9,47,0 +81,SPOON,SUM,0,0,0,0,0,5,0,11.7413449287 +81,,SUM,1,0,1,0,16,19,64,28.98010993 +81,,,,,,,,,, +82,,,,,,,,,, +82,BOWL,SUM,0,0,0,0,0,6,21,17.9587540627 +82,CUP,SUM,0,0,0,0,0,3,9,10.4868311882 +82,SPOON,SUM,0,0,0,0,0,8,0,10.6558570862 +82,,SUM,0,0,0,0,0,17,30,39.101442337 +82,,,,,,,,,, +83,,,,,,,,,, +83,BOWL,SUM,1,0,1,0,0,46,11,0 +83,CUP,SUM,0,0,0,0,0,6,8,8.8584330082 +83,SPOON,SUM,0,0,0,0,8,2,0,14.8223791122 +83,,SUM,1,0,1,0,8,54,19,23.6808121204 +83,,,,,,,,,, +84,,,,,,,,,, +84,BOWL,SUM,0,0,0,0,8,1,4,16.7374031544 +84,CUP,SUM,0,0,0,0,8,6,14,15.8277690411 +84,SPOON,SUM,0,0,0,0,0,3,0,10.1969761848 +84,,SUM,0,0,0,0,16,10,18,42.7621483803 +84,,,,,,,,,, +85,,,,,,,,,, +85,BOWL,SUM,1,0,1,0,0,314,6,0 +85,CUP,SUM,1,1,0,0,0,42,0,0 +85,SPOON,SUM,0,0,0,0,0,2,0,12.738120079 +85,,SUM,2,1,1,0,0,358,6,12.738120079 +85,,,,,,,,,, +86,,,,,,,,,, +86,BOWL,SUM,1,1,0,0,0,42,0,0 +86,CUP,SUM,0,0,0,0,0,5,16,11.9750409126 +86,SPOON,SUM,0,0,0,0,24,4,0,23.8428771496 +86,,SUM,1,1,0,0,24,51,16,35.8179180622 +86,,,,,,,,,, +87,,,,,,,,,, +87,BOWL,SUM,0,0,0,0,0,29,12,15.8929898739 +87,CUP,SUM,0,0,0,0,24,9,32,33.3028659821 +87,SPOON,SUM,0,0,0,0,0,9,0,11.6347029209 +87,,SUM,0,0,0,0,24,47,44,60.8305587769 +87,,,,,,,,,, +88,,,,,,,,,, +88,BOWL,SUM,0,0,0,0,8,1,4,13.2198240757 +88,CUP,SUM,0,0,0,0,0,3,8,9.7535300255 +88,SPOON,SUM,0,0,0,0,8,9,20,22.9323379993 +88,,SUM,0,0,0,0,16,13,32,45.9056921005 +88,,,,,,,,,, +89,,,,,,,,,, +89,BOWL,SUM,0,0,0,0,8,18,8,28.5738799572 +89,CUP,SUM,0,0,0,0,0,7,10,10.3885629177 +89,SPOON,SUM,1,0,0,1,0,12,55,0 +89,,SUM,1,0,0,1,8,37,73,38.9624428749 +89,,,,,,,,,, +90,,,,,,,,,, +90,BOWL,SUM,1,0,1,0,32,45,30,0 +90,CUP,SUM,0,0,0,0,32,4,8,21.4391958714 +90,SPOON,SUM,0,0,0,0,2,3,0,12.1154930592 +90,,SUM,1,0,1,0,66,52,38,33.5546889305 +90,,,,,,,,,, +91,,,,,,,,,, +91,BOWL,SUM,0,0,0,0,0,4,16,16.1027719975 +91,CUP,SUM,0,0,0,0,0,3,8,8.0849909782 +91,SPOON,SUM,1,1,0,0,0,42,0,0 +91,,SUM,1,1,0,0,0,49,24,24.1877629757 +91,,,,,,,,,, +92,,,,,,,,,, +92,BOWL,SUM,0,0,0,0,0,5,0,9.307874918 +92,CUP,SUM,0,0,0,0,0,9,9,10.2494652271 +92,SPOON,SUM,1,1,0,0,96,20,0,0 +92,,SUM,1,1,0,0,96,34,9,19.5573401451 +92,,,,,,,,,, +93,,,,,,,,,, +93,BOWL,SUM,0,0,0,0,2,2,0,9.1924538612 +93,CUP,SUM,0,0,0,0,40,54,30,35.8064169884 +93,SPOON,SUM,0,0,0,0,8,8,0,18.4042019844 +93,,SUM,0,0,0,0,50,64,30,63.403072834 +93,,,,,,,,,, +94,,,,,,,,,, +94,BOWL,SUM,0,0,0,0,40,16,0,25.1938471794 +94,CUP,SUM,0,0,0,0,4,7,11,14.4121940136 +94,SPOON,SUM,1,0,1,0,0,361,0,0 +94,,SUM,1,0,1,0,44,384,11,39.606041193 +94,,,,,,,,,, +95,,,,,,,,,, +95,BOWL,SUM,0,0,0,0,24,1,0,18.373552084 +95,CUP,SUM,0,0,0,0,0,2,27,16.5521068573 +95,SPOON,SUM,0,0,0,0,0,3,0,11.6442029476 +95,,SUM,0,0,0,0,24,6,27,46.5698618889 +95,,,,,,,,,, +96,,,,,,,,,, +96,BOWL,SUM,1,0,1,0,0,22,38,0 +96,CUP,SUM,0,0,0,0,0,2,8,9.1134240627 +96,SPOON,SUM,0,0,0,0,0,2,0,11.5625269413 +96,,SUM,1,0,1,0,0,26,46,20.675951004 +96,,,,,,,,,, +97,,,,,,,,,, +97,BOWL,SUM,0,0,0,0,0,2,0,9.0327119827 +97,CUP,SUM,0,0,0,0,18,6,8,16.0756151676 +97,SPOON,SUM,0,0,0,0,0,2,0,11.3403460979 +97,,SUM,0,0,0,0,18,10,8,36.4486732483 +97,,,,,,,,,, +98,,,,,,,,,, +98,BOWL,SUM,0,0,0,0,0,0,0,7.7469608784 +98,CUP,SUM,1,0,1,0,8,13,79,0 +98,SPOON,SUM,0,0,0,0,0,0,0,10.4791748524 +98,,SUM,1,0,1,0,8,13,79,18.2261357307 +98,,,,,,,,,, +99,,,,,,,,,, +99,BOWL,SUM,0,0,0,0,0,20,16,20.2070548534 +99,CUP,SUM,0,0,0,0,0,3,8,8.6429131031 +99,SPOON,SUM,0,0,0,0,2,3,12,18.0320868492 +99,,SUM,0,0,0,0,2,26,36,46.8820548058 +99,,,,,,,,,, +100,,,,,,,,,, +100,BOWL,SUM,1,0,1,0,0,51,30,0 +100,CUP,SUM,0,0,0,0,0,9,59,28.5886909962 +100,SPOON,SUM,0,0,0,0,2,2,0,12.2631449699 +100,,SUM,1,0,1,0,2,62,89,40.8518359661 +100,,,,,,,,,, +101,,,,,,,,,, +101,BOWL,SUM,0,0,0,0,0,6,0,8.8281478882 +101,CUP,SUM,0,0,0,0,16,8,29,24.9434189796 +101,SPOON,SUM,0,0,0,0,8,8,1,17.1204330921 +101,,SUM,0,0,0,0,24,22,30,50.8919999599 +101,,,,,,,,,, +102,,,,,,,,,, +102,BOWL,SUM,1,0,1,0,0,12,44,0 +102,CUP,SUM,0,0,0,0,0,3,19,12.2765171528 +102,SPOON,SUM,0,0,0,0,0,3,0,11.5999081135 +102,,SUM,1,0,1,0,0,18,63,23.8764252663 +102,,,,,,,,,, +103,,,,,,,,,, +103,BOWL,SUM,1,0,1,0,0,9,44,0 +103,CUP,SUM,0,0,0,0,0,2,8,8.0685369968 +103,SPOON,SUM,0,0,0,0,0,1,0,11.3350570202 +103,,SUM,1,0,1,0,0,12,52,19.403594017 +103,,,,,,,,,, +104,,,,,,,,,, +104,BOWL,SUM,0,0,0,0,0,5,28,18.596875906 +104,CUP,SUM,0,0,0,0,16,5,9,16.3705711365 +104,SPOON,SUM,0,0,0,0,0,1,0,11.3912630081 +104,,SUM,0,0,0,0,16,11,37,46.3587100506 +104,,,,,,,,,, +105,,,,,,,,,, +105,BOWL,SUM,0,0,0,0,8,7,1,13.6029539108 +105,CUP,SUM,0,0,0,0,0,7,47,21.2515428066 +105,SPOON,SUM,0,0,0,0,16,4,0,19.3931949139 +105,,SUM,0,0,0,0,24,18,48,54.2476916313 +105,,,,,,,,,, +106,,,,,,,,,, +106,BOWL,SUM,0,0,0,0,0,1,0,8.7409307957 +106,CUP,SUM,0,0,0,0,0,7,21,15.7069048882 +106,SPOON,SUM,0,0,0,0,0,4,4,13.6534910202 +106,,SUM,0,0,0,0,0,12,25,38.101326704 +106,,,,,,,,,, +107,,,,,,,,,, +107,BOWL,SUM,0,0,0,0,0,2,1,9.7461419106 +107,CUP,SUM,1,0,0,1,0,11,19,0 +107,SPOON,SUM,0,0,0,0,0,24,9,17.9580130577 +107,,SUM,1,0,0,1,0,37,29,27.7041549683 +107,,,,,,,,,, +108,,,,,,,,,, +108,BOWL,SUM,0,0,0,0,0,1,1,10.3801178932 +108,CUP,SUM,0,0,0,0,24,6,10,21.3853509426 +108,,,,,,,,,, +108,BOWL,SUM,0,0,0,0,4,10,0,10.7576980591 +108,CUP,SUM,0,0,0,0,8,14,59,30.788880825 +108,SPOON,SUM,0,0,0,0,0,1,0,10.881677866 +108,,SUM,0,0,0,0,12,25,59,52.4282567501 +108,,,,,,,,,, +109,,,,,,,,,, +109,BOWL,SUM,0,0,0,0,16,3,1,16.4841089249 +109,CUP,SUM,0,0,0,0,0,0,8,8.2346510887 +109,SPOON,SUM,1,1,0,0,40,12,0,0 +109,,SUM,1,1,0,0,56,15,9,24.7187600136 +109,,,,,,,,,, +110,,,,,,,,,, +110,BOWL,SUM,0,0,0,0,0,3,0,9.3827819824 +110,CUP,SUM,0,0,0,0,2,10,18,19.2549309731 +110,SPOON,SUM,0,0,0,0,8,5,0,16.1870911121 +110,,SUM,0,0,0,0,10,18,18,44.8248040676 +110,,,,,,,,,, +111,,,,,,,,,, +111,BOWL,SUM,1,1,0,0,48,9,0,0 +111,CUP,SUM,1,0,1,0,0,15,82,0 +111,SPOON,SUM,0,0,0,0,0,2,0,10.657889843 +111,,SUM,2,1,1,0,48,26,82,10.657889843 +111,,,,,,,,,, +112,,,,,,,,,, +112,BOWL,SUM,0,0,0,0,0,2,6,8.7813270092 +112,CUP,SUM,0,0,0,0,0,17,108,44.0257298946 +112,SPOON,SUM,0,0,0,0,0,1,0,11.0253348351 +112,,SUM,0,0,0,0,0,20,114,63.8323917389 +112,,,,,,,,,, +113,,,,,,,,,, +113,BOWL,SUM,0,0,0,0,16,1,0,16.831649065 +113,CUP,SUM,0,0,0,0,2,12,49,29.4508709908 +113,SPOON,SUM,0,0,0,0,0,1,0,10.8326590061 +113,,SUM,0,0,0,0,18,14,49,57.1151790619 +113,,,,,,,,,, +114,,,,,,,,,, +114,BOWL,SUM,0,0,0,0,0,10,1,10.4362258911 +114,CUP,SUM,0,0,0,0,10,4,8,13.4629919529 +114,SPOON,SUM,0,0,0,0,0,0,0,10.7700150013 +114,,SUM,0,0,0,0,10,14,9,34.6692328453 +114,,,,,,,,,, +115,,,,,,,,,, +115,BOWL,SUM,0,0,0,0,0,0,0,8.5033340454 +115,CUP,SUM,0,0,0,0,0,5,57,27.0560419559 +115,SPOON,SUM,1,0,1,0,12,341,0,0 +115,,SUM,1,0,1,0,12,346,57,35.5593760014 +115,,,,,,,,,, +116,,,,,,,,,, +116,BOWL,SUM,0,0,0,0,0,9,0,9.5714070797 +116,CUP,SUM,0,0,0,0,0,30,12,14.8506498337 +116,SPOON,SUM,0,0,0,0,2,6,12,17.9250040054 +116,,SUM,0,0,0,0,2,45,24,42.3470609188 +116,,,,,,,,,, +117,,,,,,,,,, +117,BOWL,SUM,0,0,0,0,0,3,2,8.4649291039 +117,CUP,SUM,0,0,0,0,0,7,15,13.3390471935 +117,SPOON,SUM,0,0,0,0,0,0,4,12.6347830296 +117,,SUM,0,0,0,0,0,10,21,34.4387593269 +117,,,,,,,,,, +118,,,,,,,,,, +118,BOWL,SUM,1,1,0,0,0,42,0,0 +118,CUP,SUM,0,0,0,0,0,2,8,9.0611100197 +118,SPOON,SUM,0,0,0,0,0,5,0,12.9496879578 +118,,SUM,1,1,0,0,0,49,8,22.0107979774 +118,,,,,,,,,, +119,,,,,,,,,, +119,BOWL,SUM,1,0,1,0,2,5,50,0 +119,CUP,SUM,0,0,0,0,0,4,9,9.1399791241 +119,SPOON,SUM,1,0,1,0,0,342,0,0 +119,,SUM,2,0,2,0,2,351,59,9.1399791241 +119,,,,,,,,,, +120,,,,,,,,,, +120,BOWL,SUM,0,0,0,0,0,2,1,9.1138739586 +120,CUP,SUM,0,0,0,0,8,7,20,16.5214138031 +120,SPOON,SUM,0,0,0,0,0,6,0,11.1972098351 +120,,SUM,0,0,0,0,8,15,21,36.8324975967 +120,,,,,,,,,, +121,,,,,,,,,, +121,BOWL,SUM,1,0,1,0,0,19,11,0 +121,CUP,SUM,0,0,0,0,0,6,8,9.2009871006 +121,SPOON,SUM,0,0,0,0,8,10,0,15.7024199963 +121,,SUM,1,0,1,0,8,35,19,24.9034070969 +121,,,,,,,,,, +122,,,,,,,,,, +122,BOWL,SUM,0,0,0,0,0,4,1,9.0722010136 +122,CUP,SUM,1,0,1,0,0,10,33,0 +122,SPOON,SUM,0,0,0,0,0,0,0,10.9185729027 +122,,SUM,1,0,1,0,0,14,34,19.9907739162 +122,,,,,,,,,, +123,,,,,,,,,, +123,BOWL,SUM,0,0,0,0,0,3,20,18.418582201 +123,CUP,SUM,0,0,0,0,0,9,48,23.9578020573 +123,SPOON,SUM,1,1,0,0,0,42,0,0 +123,,SUM,1,1,0,0,0,54,68,42.3763842583 +123,,,,,,,,,, +124,,,,,,,,,, +124,BOWL,SUM,1,0,1,0,0,18,44,0 +124,CUP,SUM,0,0,0,0,0,4,9,8.8620390892 +124,SPOON,SUM,0,0,0,0,8,5,0,15.1320450306 +124,,SUM,1,0,1,0,8,27,53,23.9940841198 +124,,,,,,,,,, +125,,,,,,,,,, +125,BOWL,SUM,0,0,0,0,0,3,6,11.5709300041 +125,CUP,SUM,0,0,0,0,16,6,20,20.8550000191 +125,SPOON,SUM,1,0,1,0,0,93,9,0 +125,,SUM,1,0,1,0,16,102,35,32.4259300232 +125,,,,,,,,,, +126,,,,,,,,,, +126,BOWL,SUM,0,0,0,0,0,8,0,9.8833200932 +126,CUP,SUM,0,0,0,0,0,11,87,43.4661738873 +126,SPOON,SUM,0,0,0,0,0,3,4,13.7089869976 +126,,SUM,0,0,0,0,0,22,91,67.058480978 +126,,,,,,,,,, +127,,,,,,,,,, +127,BOWL,SUM,1,0,1,0,0,41,44,0 +127,CUP,SUM,0,0,0,0,0,2,13,12.3954589367 +127,SPOON,SUM,0,0,0,0,0,2,0,11.9779598713 +127,,SUM,1,0,1,0,0,45,57,24.373418808 +127,,,,,,,,,, +128,,,,,,,,,, +128,BOWL,SUM,0,0,0,0,0,1,0,8.0316560268 +128,CUP,SUM,0,0,0,0,0,4,28,15.4799580574 +128,SPOON,SUM,1,0,1,0,8,342,0,0 +128,,SUM,1,0,1,0,8,347,28,23.5116140842 +128,,,,,,,,,, +129,,,,,,,,,, +129,BOWL,SUM,0,0,0,0,2,2,0,9.8502550125 +129,CUP,SUM,0,0,0,0,0,8,34,20.0191850662 +129,SPOON,SUM,0,0,0,0,0,3,0,10.942964077 +129,,SUM,0,0,0,0,2,13,34,40.8124041557 +129,,,,,,,,,, +130,,,,,,,,,, +130,BOWL,SUM,0,0,0,0,0,6,1,10.0340189934 +130,CUP,SUM,0,0,0,0,0,5,9,10.0756111145 +130,SPOON,SUM,0,0,0,0,0,2,0,11.1657710075 +130,,SUM,0,0,0,0,0,13,10,31.2754011154 +130,,,,,,,,,, +131,,,,,,,,,, +131,BOWL,SUM,0,0,0,0,2,3,0,15.1406280994 +131,CUP,SUM,1,0,1,0,0,13,101,0 +131,SPOON,SUM,0,0,0,0,16,7,12,24.9761459827 +131,,SUM,1,0,1,0,18,23,113,40.1167740822 +131,,,,,,,,,, +132,,,,,,,,,, +132,BOWL,SUM,1,0,1,0,0,310,6,0 +132,CUP,SUM,0,0,0,0,0,18,38,20.8264279366 +132,SPOON,SUM,1,1,0,0,0,42,0,0 +132,,SUM,2,1,1,0,0,370,44,20.8264279366 +132,,,,,,,,,, +133,,,,,,,,,, +133,BOWL,SUM,1,0,1,0,0,212,20,0 +133,CUP,SUM,0,0,0,0,8,7,8,12.9781098366 +133,SPOON,SUM,0,0,0,0,0,7,10,16.2347621918 +133,,SUM,1,0,1,0,8,226,38,29.2128720284 +133,,,,,,,,,, +134,,,,,,,,,, +134,BOWL,SUM,1,0,1,0,0,8,38,0 +134,CUP,SUM,0,0,0,0,0,2,8,8.2135541439 +134,SPOON,SUM,0,0,0,0,0,2,0,11.0819818974 +134,,SUM,1,0,1,0,0,12,46,19.2955360413 +134,,,,,,,,,, +135,,,,,,,,,, +135,BOWL,SUM,0,0,0,0,0,4,8,12.0925822258 +135,CUP,SUM,0,0,0,0,0,9,94,36.1058969498 +135,SPOON,SUM,0,0,0,0,8,8,8,21.1426010132 +135,,SUM,0,0,0,0,8,21,110,69.3410801888 +135,,,,,,,,,, +136,,,,,,,,,, +136,BOWL,SUM,1,0,0,1,8,7,19,0 +136,CUP,SUM,0,0,0,0,32,24,9,26.795814991 +136,SPOON,SUM,0,0,0,0,0,18,19,33.696449995 +136,,SUM,1,0,0,1,40,49,47,60.492264986 +136,,,,,,,,,, +137,,,,,,,,,, +137,BOWL,SUM,0,0,0,0,0,1,0,9.9491641521 +137,CUP,SUM,0,0,0,0,0,3,8,7.7106821537 +137,SPOON,SUM,1,0,1,0,8,19,11,0 +137,,SUM,1,0,1,0,8,23,19,17.6598463058 +137,,,,,,,,,, +138,,,,,,,,,, +138,BOWL,SUM,0,0,0,0,0,3,0,9.0378501415 +138,CUP,SUM,0,0,0,0,2,10,8,10.4377419949 +138,SPOON,SUM,0,0,0,0,8,4,0,16.6773099899 +138,,SUM,0,0,0,0,10,17,8,36.1529021263 +138,,,,,,,,,, +139,,,,,,,,,, +139,BOWL,SUM,0,0,0,0,0,4,0,9.5939559937 +139,CUP,SUM,0,0,0,0,0,2,40,20.5960559845 +139,SPOON,SUM,0,0,0,0,0,3,0,11.9254970551 +139,,SUM,0,0,0,0,0,9,40,42.1155090332 +139,,,,,,,,,, +140,,,,,,,,,, +140,BOWL,SUM,1,0,1,0,0,342,0,0 +140,CUP,SUM,0,0,0,0,0,3,8,9.4786419868 +140,SPOON,SUM,0,0,0,0,0,0,0,12.455739975 +140,,SUM,1,0,1,0,0,345,8,21.9343819618 +140,,,,,,,,,, +141,,,,,,,,,, +141,BOWL,SUM,0,0,0,0,8,11,0,17.7361288071 +141,CUP,SUM,0,0,0,0,8,5,8,12.6336388588 +141,SPOON,SUM,0,0,0,0,0,10,0,12.7326850891 +141,,SUM,0,0,0,0,16,26,8,43.102452755 +141,,,,,,,,,, +142,,,,,,,,,, +142,BOWL,SUM,1,0,1,0,2,36,10,0 +142,CUP,SUM,0,0,0,0,0,3,65,26.8453950882 +142,SPOON,SUM,0,0,0,0,0,1,0,11.6833760738 +142,,SUM,1,0,1,0,2,40,75,38.528771162 +142,,,,,,,,,, +143,,,,,,,,,, +143,BOWL,SUM,0,0,0,0,0,4,0,9.954406023 +143,CUP,SUM,1,0,0,1,0,13,19,0 +143,SPOON,SUM,1,0,1,0,0,341,0,0 +143,,SUM,2,0,1,1,0,358,19,9.954406023 +143,,,,,,,,,, +144,,,,,,,,,, +144,BOWL,SUM,0,0,0,0,0,2,10,13.8585529327 +144,CUP,SUM,0,0,0,0,0,14,69,29.1017830372 +144,SPOON,SUM,0,0,0,0,0,0,0,10.9305579662 +144,,SUM,0,0,0,0,0,16,79,53.8908939362 +144,,,,,,,,,, +145,,,,,,,,,, +145,BOWL,SUM,0,0,0,0,0,7,0,9.9729058743 +145,CUP,SUM,1,0,1,0,0,11,88,0 +145,SPOON,SUM,0,0,0,0,8,4,0,15.4520478249 +145,,SUM,1,0,1,0,8,22,88,25.4249536991 +145,,,,,,,,,, +146,,,,,,,,,, +146,BOWL,SUM,1,0,1,0,2,312,4,0 +146,CUP,SUM,1,0,0,1,0,10,29,0 +146,SPOON,SUM,0,0,0,0,0,3,0,11.6363310814 +146,,SUM,2,0,1,1,2,325,33,11.6363310814 +146,,,,,,,,,, +147,,,,,,,,,, +147,BOWL,SUM,0,0,0,0,0,0,0,8.9174051285 +147,CUP,SUM,0,0,0,0,0,21,129,45.5053060055 +147,SPOON,SUM,0,0,0,0,0,1,0,11.7565159798 +147,,SUM,0,0,0,0,0,22,129,66.1792271137 +147,,,,,,,,,, +148,,,,,,,,,, +148,BOWL,SUM,0,0,0,0,0,3,0,8.7557418346 +148,CUP,SUM,0,0,0,0,8,4,23,23.3109471798 +148,SPOON,SUM,1,0,1,0,0,246,5,0 +148,,SUM,1,0,1,0,8,253,28,32.0666890144 +148,,,,,,,,,, +149,,,,,,,,,, +149,BOWL,SUM,0,0,0,0,0,1,1,9.2679650784 +149,CUP,SUM,0,0,0,0,16,5,8,16.1122260094 +149,SPOON,SUM,1,1,0,0,0,42,0,0 +149,,SUM,1,1,0,0,16,48,9,25.3801910877 +149,,,,,,,,,, +150,,,,,,,,,, +150,BOWL,SUM,0,0,0,0,0,5,0,8.4575488567 +150,CUP,SUM,0,0,0,0,0,3,8,7.8124678135 +150,SPOON,SUM,1,0,1,0,8,53,40,0 +150,,SUM,1,0,1,0,8,61,48,16.2700166702 +150,,,,,,,,,, +151,,,,,,,,,, +151,BOWL,SUM,1,0,1,0,0,12,11,0 +151,CUP,SUM,1,0,1,0,0,13,39,0 +151,SPOON,SUM,0,0,0,0,0,5,0,11.354501009 +151,,SUM,2,0,2,0,0,30,50,11.354501009 +151,,,,,,,,,, +152,,,,,,,,,, +152,BOWL,SUM,1,1,0,0,0,43,0,0 +152,CUP,SUM,1,1,0,0,0,42,0,0 +152,SPOON,SUM,0,0,0,0,24,5,2,23.744063139 +152,,SUM,2,2,0,0,24,90,2,23.744063139 +152,,,,,,,,,, +153,,,,,,,,,, +153,BOWL,SUM,0,0,0,0,0,6,1,9.4277830124 +153,CUP,SUM,1,0,1,0,0,15,33,0 +153,SPOON,SUM,0,0,0,0,24,2,0,21.9531230927 +153,,SUM,1,0,1,0,24,23,34,31.380906105 +153,,,,,,,,,, +154,,,,,,,,,, +154,BOWL,SUM,1,0,1,0,0,38,40,0 +154,CUP,SUM,0,0,0,0,0,2,8,7.8469769955 +154,SPOON,SUM,0,0,0,0,0,0,0,11.0993199348 +154,,SUM,1,0,1,0,0,40,48,18.9462969303 +154,,,,,,,,,, +155,,,,,,,,,, +155,BOWL,SUM,1,0,1,0,8,17,11,0 +155,CUP,SUM,0,0,0,0,0,8,8,8.7488908768 +155,SPOON,SUM,0,0,0,0,8,26,7,27.9686660767 +155,,SUM,1,0,1,0,16,51,26,36.7175569534 +155,,,,,,,,,, +156,,,,,,,,,, +156,BOWL,SUM,0,0,0,0,0,6,17,14.7358009815 +156,CUP,SUM,0,0,0,0,0,5,8,8.2655608654 +156,SPOON,SUM,0,0,0,0,22,5,0,23.0830249786 +156,,SUM,0,0,0,0,22,16,25,46.0843868256 +156,,,,,,,,,, +157,,,,,,,,,, +157,BOWL,SUM,0,0,0,0,0,2,1,11.0366919041 +157,CUP,SUM,0,0,0,0,0,5,8,8.8306121826 +157,SPOON,SUM,0,0,0,0,0,1,11,16.6490578651 +157,,SUM,0,0,0,0,0,8,20,36.5163619518 +157,,,,,,,,,, +158,,,,,,,,,, +158,BOWL,SUM,0,0,0,0,0,2,0,8.6347930431 +158,CUP,SUM,1,0,1,0,0,9,82,0 +158,SPOON,SUM,0,0,0,0,8,0,4,16.6217780113 +158,,SUM,1,0,1,0,8,11,86,25.2565710545 +158,,,,,,,,,, +159,,,,,,,,,, +159,BOWL,SUM,0,0,0,0,0,39,0,12.9550199509 +159,CUP,SUM,1,0,1,0,0,30,78,0 +159,SPOON,SUM,0,0,0,0,24,7,0,21.7975959778 +159,,SUM,1,0,1,0,24,76,78,34.7526159286 +159,,,,,,,,,, +160,,,,,,,,,, +160,BOWL,SUM,0,0,0,0,0,2,0,8.6811981201 +160,CUP,SUM,0,0,0,0,0,13,19,14.9480919838 +160,SPOON,SUM,0,0,0,0,0,5,0,11.6102280617 +160,,SUM,0,0,0,0,0,20,19,35.2395181656 +160,,,,,,,,,, +161,,,,,,,,,, +161,BOWL,SUM,0,0,0,0,8,16,1,14.205275774 +161,CUP,SUM,1,0,1,0,0,32,55,0 +161,SPOON,SUM,0,0,0,0,0,4,0,11.4811360836 +161,,SUM,1,0,1,0,8,52,56,25.6864118576 +161,,,,,,,,,, +162,,,,,,,,,, +162,BOWL,SUM,0,0,0,0,0,3,0,8.6149880886 +162,CUP,SUM,0,0,0,0,0,18,24,17.0443739891 +162,SPOON,SUM,0,0,0,0,16,2,0,18.350383997 +162,,SUM,0,0,0,0,16,23,24,44.0097460747 +162,,,,,,,,,, +163,,,,,,,,,, +163,BOWL,SUM,0,0,0,0,0,1,5,10.0289349556 +163,CUP,SUM,0,0,0,0,0,6,15,12.0761761665 +163,SPOON,SUM,1,1,0,0,0,42,0,0 +163,,SUM,1,1,0,0,0,49,20,22.1051111221 +163,,,,,,,,,, +164,,,,,,,,,, +164,BOWL,SUM,0,0,0,0,0,4,35,24.4752209187 +164,CUP,SUM,0,0,0,0,0,6,17,11.9829611778 +164,SPOON,SUM,0,0,0,0,0,0,0,10.9920251369 +164,,SUM,0,0,0,0,0,10,52,47.4502072334 +164,,,,,,,,,, +165,,,,,,,,,, +165,BOWL,SUM,0,0,0,0,0,1,7,14.0200760365 +165,CUP,SUM,1,0,1,0,0,12,44,0 +165,SPOON,SUM,0,0,0,0,0,3,6,13.6580021381 +165,,SUM,1,0,1,0,0,16,57,27.6780781746 +165,,,,,,,,,, +166,,,,,,,,,, +166,BOWL,SUM,0,0,0,0,8,35,13,21.7541248798 +166,CUP,SUM,0,0,0,0,8,3,28,20.1614391804 +166,SPOON,SUM,1,0,1,0,0,12,23,0 +166,,SUM,1,0,1,0,16,50,64,41.9155640602 +166,,,,,,,,,, +167,,,,,,,,,, +167,BOWL,SUM,0,0,0,0,12,9,6,23.2574300766 +167,CUP,SUM,1,0,0,1,0,17,25,0 +167,SPOON,SUM,0,0,0,0,0,2,0,11.5566151142 +167,,SUM,1,0,0,1,12,28,31,34.8140451908 +167,,,,,,,,,, +168,,,,,,,,,, +168,BOWL,SUM,0,0,0,0,0,5,8,11.9835910797 +168,CUP,SUM,0,0,0,0,2,30,96,42.4896190166 +168,SPOON,SUM,1,0,0,1,0,6,17,0 +168,,SUM,1,0,0,1,2,41,121,54.4732100964 +168,,,,,,,,,, +169,,,,,,,,,, +169,BOWL,SUM,0,0,0,0,8,3,1,14.0096969604 +169,CUP,SUM,1,0,1,0,34,18,90,0 +169,SPOON,SUM,0,0,0,0,0,0,0,11.0295181274 +169,,SUM,1,0,1,0,42,21,91,25.0392150879 +169,,,,,,,,,, +170,,,,,,,,,, +170,BOWL,SUM,1,0,1,0,8,314,4,0 +170,CUP,SUM,0,0,0,0,0,4,69,29.6658730507 +170,SPOON,SUM,0,0,0,0,2,4,4,15.3396978378 +170,,SUM,1,0,1,0,10,322,77,45.0055708885 +170,,,,,,,,,, +171,,,,,,,,,, +171,BOWL,SUM,0,0,0,0,0,2,24,20.7709648609 +171,CUP,SUM,0,0,0,0,0,4,8,8.7038669586 +171,SPOON,SUM,0,0,0,0,24,3,4,23.8422141075 +171,,SUM,0,0,0,0,24,9,36,53.317045927 +171,,,,,,,,,, +172,,,,,,,,,, +172,BOWL,SUM,0,0,0,0,0,1,0,8.9295430183 +172,CUP,SUM,0,0,0,0,0,4,33,18.9539880753 +172,SPOON,SUM,1,0,1,0,0,341,0,0 +172,,SUM,1,0,1,0,0,346,33,27.8835310936 +172,,,,,,,,,, +173,,,,,,,,,, +173,BOWL,SUM,0,0,0,0,0,5,1,9.3530399799 +173,CUP,SUM,0,0,0,0,0,4,16,16.4590559006 +173,SPOON,SUM,1,0,1,0,16,160,6,0 +173,,SUM,1,0,1,0,16,169,23,25.8120958805 +173,,,,,,,,,, +174,,,,,,,,,, +174,BOWL,SUM,0,0,0,0,32,3,0,25.162209034 +174,CUP,SUM,0,0,0,0,0,11,13,12.3132190704 +174,SPOON,SUM,1,0,1,0,8,32,44,0 +174,,SUM,1,0,1,0,40,46,57,37.4754281044 +174,,,,,,,,,, +175,,,,,,,,,, +175,BOWL,SUM,1,0,1,0,8,17,26,0 +175,CUP,SUM,0,0,0,0,0,4,9,9.0225539207 +175,SPOON,SUM,0,0,0,0,0,1,0,11.7374610901 +175,,SUM,1,0,1,0,8,22,35,20.7600150108 +175,,,,,,,,,, +176,,,,,,,,,, +176,BOWL,SUM,0,0,0,0,0,2,0,8.6301648617 +176,CUP,SUM,0,0,0,0,0,2,23,13.4372601509 +176,SPOON,SUM,0,0,0,0,0,3,0,11.3744459152 +176,,SUM,0,0,0,0,0,7,23,33.4418709278 +176,,,,,,,,,, +177,,,,,,,,,, +177,BOWL,SUM,0,0,0,0,0,1,0,9.6303358078 +177,CUP,SUM,0,0,0,0,4,1,18,13.4696350098 +177,SPOON,SUM,0,0,0,0,32,13,0,24.945982933 +177,,SUM,0,0,0,0,36,15,18,48.0459537506 +177,,,,,,,,,, +178,,,,,,,,,, +178,BOWL,SUM,0,0,0,0,0,8,34,22.274171114 +178,CUP,SUM,0,0,0,0,8,31,8,14.3191080093 +178,SPOON,SUM,0,0,0,0,0,1,0,11.0167181492 +178,,SUM,0,0,0,0,8,40,42,47.6099972725 +178,,,,,,,,,, +179,,,,,,,,,, +179,BOWL,SUM,0,0,0,0,0,0,0,8.9029471874 +179,CUP,SUM,1,0,1,0,0,10,11,0 +179,SPOON,SUM,0,0,0,0,0,1,0,11.6876502037 +179,,SUM,1,0,1,0,0,11,11,20.5905973911 +179,,,,,,,,,, +180,,,,,,,,,, +180,BOWL,SUM,0,0,0,0,16,4,13,20.5839710236 +180,CUP,SUM,1,0,1,0,0,189,90,0 +180,SPOON,SUM,0,0,0,0,0,3,4,12.9913170338 +180,,SUM,1,0,1,0,16,196,107,33.5752880573 +180,,,,,,,,,, +181,,,,,,,,,, +181,BOWL,SUM,0,0,0,0,0,2,4,14.7504971027 +181,CUP,SUM,0,0,0,0,0,1,8,7.8154909611 +181,SPOON,SUM,0,0,0,0,8,2,4,16.3284499645 +181,,SUM,0,0,0,0,8,5,16,38.8944380283 +181,,,,,,,,,, +182,,,,,,,,,, +182,BOWL,SUM,0,0,0,0,0,2,1,10.2859611511 +182,CUP,SUM,0,0,0,0,0,1,8,7.9186599255 +182,SPOON,SUM,0,0,0,0,0,12,6,16.406744957 +182,,SUM,0,0,0,0,0,15,15,34.6113660336 +182,,,,,,,,,, +183,,,,,,,,,, +183,BOWL,SUM,0,0,0,0,4,26,16,18.0001749992 +183,CUP,SUM,0,0,0,0,2,3,8,9.6655068398 +183,SPOON,SUM,0,0,0,0,8,4,0,15.3916289806 +183,,SUM,0,0,0,0,14,33,24,43.0573108196 +183,,,,,,,,,, +184,,,,,,,,,, +184,BOWL,SUM,1,0,1,0,0,20,34,0 +184,CUP,SUM,1,0,1,0,0,4,71,0 +184,SPOON,SUM,0,0,0,0,0,3,0,12.0019099712 +184,,SUM,2,0,2,0,0,27,105,12.0019099712 +184,,,,,,,,,, +185,,,,,,,,,, +185,BOWL,SUM,1,1,0,0,0,42,0,0 +185,CUP,SUM,0,0,0,0,0,18,8,10.152641058 +185,SPOON,SUM,0,0,0,0,24,12,0,21.2039091587 +185,,SUM,1,1,0,0,24,72,8,31.3565502167 +185,,,,,,,,,, +186,,,,,,,,,, +186,BOWL,SUM,0,0,0,0,0,9,12,14.8376431465 +186,CUP,SUM,0,0,0,0,0,3,17,13.4184381962 +186,SPOON,SUM,0,0,0,0,0,0,0,11.7017118931 +186,,SUM,0,0,0,0,0,12,29,39.9577932358 +186,,,,,,,,,, +187,,,,,,,,,, +187,BOWL,SUM,0,0,0,0,0,0,0,9.7001399994 +187,CUP,SUM,0,0,0,0,16,4,9,17.4645328522 +187,SPOON,SUM,0,0,0,0,2,3,0,12.2501251698 +187,,SUM,0,0,0,0,18,7,9,39.4147980213 +187,,,,,,,,,, +188,,,,,,,,,, +188,BOWL,SUM,1,1,0,0,0,72,0,0 +188,CUP,SUM,0,0,0,0,24,111,8,27.7974998951 +188,SPOON,SUM,0,0,0,0,0,22,20,20.8323979378 +188,,SUM,1,1,0,0,24,205,28,48.6298978329 +188,,,,,,,,,, +189,,,,,,,,,, +189,BOWL,SUM,0,0,0,0,0,3,0,8.5945119858 +189,CUP,SUM,0,0,0,0,24,3,8,18.4282598495 +189,SPOON,SUM,0,0,0,0,0,1,8,15.73686409 +189,,SUM,0,0,0,0,24,7,16,42.7596359253 +189,,,,,,,,,, +190,,,,,,,,,, +190,BOWL,SUM,0,0,0,0,2,0,0,10.1482059956 +190,CUP,SUM,0,0,0,0,24,4,18,22.8122620583 +190,SPOON,SUM,0,0,0,0,8,2,4,16.3566961288 +190,,SUM,0,0,0,0,34,6,22,49.3171641827 +190,,,,,,,,,, +191,,,,,,,,,, +191,BOWL,SUM,0,0,0,0,0,3,0,10.7414991856 +191,CUP,SUM,0,0,0,0,0,2,9,9.4464211464 +191,SPOON,SUM,0,0,0,0,0,7,0,11.0649299622 +191,,SUM,0,0,0,0,0,12,9,31.2528502941 +191,,,,,,,,,, +192,,,,,,,,,, +192,BOWL,SUM,0,0,0,0,0,1,0,7.8895831108 +192,CUP,SUM,0,0,0,0,0,6,44,28.6548631191 +192,SPOON,SUM,0,0,0,0,8,0,0,14.8078248501 +192,,SUM,0,0,0,0,8,7,44,51.35227108 +192,,,,,,,,,, +193,,,,,,,,,, +193,BOWL,SUM,0,0,0,0,2,3,9,16.1422801018 +193,CUP,SUM,0,0,0,0,24,7,8,19.4897119999 +193,SPOON,SUM,0,0,0,0,8,8,8,17.3715538979 +193,,SUM,0,0,0,0,34,18,25,53.0035459995 +193,,,,,,,,,, +194,,,,,,,,,, +194,BOWL,SUM,0,0,0,0,8,3,0,11.8641891479 +194,CUP,SUM,0,0,0,0,8,1,12,15.9840319157 +194,SPOON,SUM,0,0,0,0,0,4,0,11.1842370033 +194,,SUM,0,0,0,0,16,8,12,39.0324580669 +194,,,,,,,,,, +195,,,,,,,,,, +195,BOWL,SUM,0,0,0,0,0,36,35,25.696696043 +195,CUP,SUM,0,0,0,0,0,7,49,23.7543320656 +195,SPOON,SUM,0,0,0,0,0,1,0,11.3550732136 +195,,SUM,0,0,0,0,0,44,84,60.8061013222 +195,,,,,,,,,, +196,,,,,,,,,, +196,BOWL,SUM,0,0,0,0,8,7,29,24.3789548874 +196,CUP,SUM,0,0,0,0,0,5,12,11.5825619698 +196,SPOON,SUM,0,0,0,0,24,3,7,24.6045107841 +196,,SUM,0,0,0,0,32,15,48,60.5660276413 +196,,,,,,,,,, +197,,,,,,,,,, +197,BOWL,SUM,1,0,1,0,8,7,26,0 +197,CUP,SUM,0,0,0,0,0,6,10,10.5314278603 +197,SPOON,SUM,0,0,0,0,16,1,0,17.8695468903 +197,,SUM,1,0,1,0,24,14,36,28.4009747505 +197,,,,,,,,,, +198,,,,,,,,,, +198,BOWL,SUM,0,0,0,0,0,1,0,8.0187740326 +198,CUP,SUM,0,0,0,0,0,3,16,13.2952549458 +198,SPOON,SUM,0,0,0,0,0,22,2,14.4820871353 +198,,SUM,0,0,0,0,0,26,18,35.7961161137 +198,,,,,,,,,, +199,,,,,,,,,, +199,BOWL,SUM,0,0,0,0,8,9,34,27.9556062222 +199,CUP,SUM,1,0,0,1,0,11,31,0 +199,SPOON,SUM,0,0,0,0,0,19,1,14.6248419285 +199,,SUM,1,0,0,1,8,39,66,42.5804481506 +199,,,,,,,,,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/heur_boxy_orig.csv b/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/heur_boxy_orig.csv new file mode 100644 index 0000000000..5cb237b941 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/heur_boxy_orig.csv @@ -0,0 +1,1203 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,2,9,9,16.9717421532 +0,CUP,SUM,0,0,0,0,0,0,9,9.3507969379 +0,SPOON,SUM,0,0,0,0,0,2,0,11.3196239471 +0,,SUM,0,0,0,0,2,11,18,37.6421630383 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,14,3,2,20.4612090588 +1,CUP,SUM,0,0,0,0,0,2,37,19.2070088387 +1,SPOON,SUM,0,0,0,0,0,1,0,12.7714338303 +1,,SUM,0,0,0,0,14,6,39,52.4396517277 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,0,1,0,7.7722299099 +2,CUP,SUM,0,0,0,0,0,6,9,9.5963861942 +2,SPOON,SUM,0,0,0,0,0,16,0,14.573086977 +2,,SUM,0,0,0,0,0,23,9,31.9417030811 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,0,3,0,8.2646989822 +3,CUP,SUM,0,0,0,0,0,1,27,13.6423377991 +3,SPOON,SUM,0,0,0,0,0,1,0,11.5122010708 +3,,SUM,0,0,0,0,0,5,27,33.4192378521 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,8,10,34,23.7731590271 +4,CUP,SUM,0,0,0,0,2,0,9,10.6240410805 +4,SPOON,SUM,0,0,0,0,0,5,6,14.2518231869 +4,,SUM,0,0,0,0,10,15,49,48.6490232944 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,8,6,9,16.1566970348 +5,CUP,SUM,0,0,0,0,0,3,21,12.8821470737 +5,SPOON,SUM,0,0,0,0,8,3,0,15.3631789684 +5,,SUM,0,0,0,0,16,12,30,44.402023077 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,1,0,1,0,0,8,44,0 +6,CUP,SUM,0,0,0,0,8,4,28,19.1580660343 +6,SPOON,SUM,0,0,0,0,8,1,0,16.1478590965 +6,,SUM,1,0,1,0,16,13,72,35.3059251308 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,0,1,0,9.707310915 +7,CUP,SUM,0,0,0,0,2,2,8,9.6947798729 +7,SPOON,SUM,0,0,0,0,0,4,0,13.0249509811 +7,,SUM,0,0,0,0,2,7,8,32.427041769 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,16,2,1,15.8578429222 +8,CUP,SUM,1,0,1,0,16,9,51,0 +8,SPOON,SUM,0,0,0,0,0,0,0,10.6815829277 +8,,SUM,1,0,1,0,32,11,52,26.5394258499 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,8,5,1,16.6525259018 +9,CUP,SUM,1,0,1,0,0,8,77,0 +9,SPOON,SUM,0,0,0,0,2,8,5,17.160061121 +9,,SUM,1,0,1,0,10,21,83,33.8125870228 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,1,4,11.2783408165 +10,CUP,SUM,0,0,0,0,2,2,9,10.6009430885 +10,SPOON,SUM,1,0,1,0,8,11,46,0 +10,,SUM,1,0,1,0,10,14,59,21.879283905 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,8,1,0,12.5772099495 +11,CUP,SUM,0,0,0,0,16,13,21,26.2377009392 +11,SPOON,SUM,0,0,0,0,2,4,4,14.1772770882 +11,,SUM,0,0,0,0,26,18,25,52.9921879768 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,2,2,0,8.9823708534 +12,CUP,SUM,0,0,0,0,0,0,8,8.8555550575 +12,SPOON,SUM,0,0,0,0,0,2,0,11.5703251362 +12,,SUM,0,0,0,0,2,4,8,29.4082510471 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,0,4,12,14.0004370213 +13,CUP,SUM,0,0,0,0,0,1,18,11.6863739491 +13,SPOON,SUM,0,0,0,0,0,3,13,26.2072279453 +13,,SUM,0,0,0,0,0,8,43,51.8940389156 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,8,7,0,20.3477108479 +14,CUP,SUM,0,0,0,0,0,4,8,9.0264968872 +14,SPOON,SUM,0,0,0,0,0,0,0,11.8731069565 +14,,SUM,0,0,0,0,8,11,8,41.2473146915 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,16,0,0,17.3071060181 +15,CUP,SUM,1,0,1,0,0,22,135,0 +15,SPOON,SUM,0,0,0,0,0,3,4,11.158069849 +15,,SUM,1,0,1,0,16,25,139,28.4651758671 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,2,1,10.1254820824 +16,CUP,SUM,0,0,0,0,0,2,8,8.728292942 +16,SPOON,SUM,0,0,0,0,0,3,0,11.8376059532 +16,,SUM,0,0,0,0,0,7,9,30.6913809776 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,0,21,0,10.954241991 +17,CUP,SUM,1,0,1,0,0,17,119,0 +17,SPOON,SUM,0,0,0,0,8,1,0,18.6359820366 +17,,SUM,1,0,1,0,8,39,119,29.5902240276 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,2,0,0,9.6949870586 +18,CUP,SUM,0,0,0,0,16,8,23,27.3437838554 +18,SPOON,SUM,0,0,0,0,0,3,0,11.921710968 +18,,SUM,0,0,0,0,18,11,23,48.9604818821 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,2,16,15.3963210583 +19,CUP,SUM,0,0,0,0,8,3,8,13.2041780949 +19,SPOON,SUM,0,0,0,0,8,8,0,16.7728919983 +19,,SUM,0,0,0,0,16,13,24,45.3733911514 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,8,17,4,14.6609909534 +20,CUP,SUM,0,0,0,0,0,0,8,8.3860759735 +20,SPOON,SUM,0,0,0,0,0,2,2,12.1838591099 +20,,SUM,0,0,0,0,8,19,14,35.2309260368 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,5,0,9.230670929 +21,CUP,SUM,0,0,0,0,0,1,9,9.5877718925 +21,SPOON,SUM,0,0,0,0,0,1,0,12.4756240845 +21,,SUM,0,0,0,0,0,7,9,31.294066906 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,1,0,1,0,0,10,42,0 +22,CUP,SUM,0,0,0,0,0,3,28,20.4541969299 +22,SPOON,SUM,0,0,0,0,0,11,28,31.9305028915 +22,,SUM,1,0,1,0,0,24,98,52.3846998215 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,2,8,11.4138410091 +23,CUP,SUM,0,0,0,0,0,4,8,8.707971096 +23,SPOON,SUM,0,0,0,0,0,7,0,12.1867408752 +23,,SUM,0,0,0,0,0,13,16,32.3085529804 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,8,21,11,20.2077829838 +24,CUP,SUM,1,0,1,0,0,8,53,0 +24,SPOON,SUM,0,0,0,0,0,11,4,15.0933139324 +24,,SUM,1,0,1,0,8,40,68,35.3010969162 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,0,1,1,10.5093741417 +25,CUP,SUM,0,0,0,0,0,5,20,13.6296570301 +25,SPOON,SUM,0,0,0,0,0,3,0,12.8190040588 +25,,SUM,0,0,0,0,0,9,21,36.9580352306 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,0,2,0,8.7630689144 +26,CUP,SUM,0,0,0,0,0,6,67,29.5159230232 +26,SPOON,SUM,0,0,0,0,2,5,0,14.0800030231 +26,,SUM,0,0,0,0,2,13,67,52.3589949608 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,0,12,15,15.7760391235 +27,CUP,SUM,1,0,1,0,4,7,63,0 +27,SPOON,SUM,0,0,0,0,0,1,0,11.1880750656 +27,,SUM,1,0,1,0,4,20,78,26.9641141891 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,8,0,0,12.2287199497 +28,CUP,SUM,0,0,0,0,2,5,14,15.2370860577 +28,SPOON,SUM,0,0,0,0,0,1,0,11.9742369652 +28,,SUM,0,0,0,0,10,6,14,39.4400429726 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,0,1,12,12.2445600033 +29,CUP,SUM,0,0,0,0,2,3,8,9.5869560242 +29,SPOON,SUM,0,0,0,0,0,1,0,11.8435199261 +29,,SUM,0,0,0,0,2,5,20,33.6750359535 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,8,2,0,13.2759017944 +30,CUP,SUM,1,0,1,0,8,9,78,0 +30,SPOON,SUM,0,0,0,0,0,0,0,11.5793261528 +30,,SUM,1,0,1,0,16,11,78,24.8552279472 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,0,5,1,10.5650980473 +31,CUP,SUM,0,0,0,0,56,7,13,39.4731760025 +31,SPOON,SUM,0,0,0,0,0,6,5,15.2004930973 +31,,SUM,0,0,0,0,56,18,19,65.2387671471 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,0,6,4,9.5678398609 +32,CUP,SUM,0,0,0,0,0,4,17,13.4210259914 +32,SPOON,SUM,0,0,0,0,0,10,19,21.6733129025 +32,,SUM,0,0,0,0,0,20,40,44.6621787548 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,7,1,11.9677848816 +33,CUP,SUM,0,0,0,0,0,0,8,8.0657060146 +33,SPOON,SUM,0,0,0,0,0,3,0,12.6144011021 +33,,SUM,0,0,0,0,0,10,9,32.6478919983 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,0,22,12,17.4163069725 +34,CUP,SUM,0,0,0,0,0,16,20,15.4738252163 +34,SPOON,SUM,0,0,0,0,2,9,0,13.774533987 +34,,SUM,0,0,0,0,2,47,32,46.6646661758 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,0,4,12,13.4264099598 +35,CUP,SUM,0,0,0,0,0,7,42,20.0566101074 +35,SPOON,SUM,0,0,0,0,0,1,0,11.6704871655 +35,,SUM,0,0,0,0,0,12,54,45.1535072327 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,18,5,28,27.5118420124 +36,CUP,SUM,0,0,0,0,0,9,8,9.7879698277 +36,SPOON,SUM,0,0,0,0,0,7,0,12.2516438961 +36,,SUM,0,0,0,0,18,21,36,49.5514557362 +36,,,,,,,,,, +37,,,,,,,,,, +37,BOWL,SUM,0,0,0,0,0,5,14,15.6454558372 +37,CUP,SUM,0,0,0,0,0,14,8,10.7782480717 +37,SPOON,SUM,1,0,1,0,0,14,11,0 +37,,SUM,1,0,1,0,0,33,33,26.4237039089 +37,,,,,,,,,, +38,,,,,,,,,, +38,BOWL,SUM,0,0,0,0,0,4,5,14.1167960167 +38,CUP,SUM,0,0,0,0,4,1,13,12.5199439526 +38,SPOON,SUM,0,0,0,0,16,13,4,36.6234500408 +38,,SUM,0,0,0,0,20,18,22,63.2601900101 +38,,,,,,,,,, +39,,,,,,,,,, +39,BOWL,SUM,0,0,0,0,0,6,0,10.3418669701 +39,CUP,SUM,0,0,0,0,24,16,34,32.7770171165 +39,SPOON,SUM,0,0,0,0,0,3,2,16.1665430069 +39,,SUM,0,0,0,0,24,25,36,59.2854270935 +39,,,,,,,,,, +40,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,2,9,9,16.9705109596 +40,CUP,SUM,0,0,0,0,0,0,9,9.6154749393 +40,SPOON,SUM,0,0,0,0,0,2,0,11.5821318626 +40,,SUM,0,0,0,0,2,11,18,38.1681177616 +40,,,,,,,,,, +41,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,14,3,2,20.8754580021 +41,CUP,SUM,0,0,0,0,0,2,37,19.9478378296 +41,SPOON,SUM,0,0,0,0,0,1,0,12.5008699894 +41,,SUM,0,0,0,0,14,6,39,53.3241658211 +41,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,0,1,0,7.5073490143 +42,CUP,SUM,0,0,0,0,0,6,9,9.8881540298 +42,SPOON,SUM,0,0,0,0,0,16,0,14.7964019775 +42,,SUM,0,0,0,0,0,23,9,32.1919050217 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,0,3,0,7.903952837 +43,CUP,SUM,0,0,0,0,0,1,27,13.9570481777 +43,SPOON,SUM,0,0,0,0,0,1,0,11.8767831326 +43,,SUM,0,0,0,0,0,5,27,33.7377841473 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,8,10,34,24.576764822 +44,CUP,SUM,0,0,0,0,2,0,9,11.0100951195 +44,SPOON,SUM,0,0,0,0,0,5,6,14.1839520931 +44,,SUM,0,0,0,0,10,15,49,49.7708120346 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,8,6,9,16.3589339256 +45,CUP,SUM,0,0,0,0,0,3,21,12.9235911369 +45,SPOON,SUM,0,0,0,0,8,3,0,15.5897431374 +45,,SUM,0,0,0,0,16,12,30,44.8722681999 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,1,0,1,0,0,8,44,0 +46,CUP,SUM,0,0,0,0,8,4,28,19.3622040749 +46,SPOON,SUM,0,0,0,0,8,1,0,16.2506937981 +46,,SUM,1,0,1,0,16,13,72,35.6128978729 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,0,0,0,0,0,1,0,9.3366611004 +47,CUP,SUM,0,0,0,0,2,2,8,9.9086480141 +47,SPOON,SUM,0,0,0,0,0,4,0,13.2733139992 +47,,SUM,0,0,0,0,2,7,8,32.5186231136 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,16,2,1,15.4800958633 +48,CUP,SUM,1,0,1,0,16,9,51,0 +48,SPOON,SUM,0,0,0,0,0,0,0,10.7432470322 +48,,SUM,1,0,1,0,32,11,52,26.2233428955 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,8,5,1,15.9619131088 +49,CUP,SUM,1,0,1,0,0,8,77,0 +49,SPOON,SUM,0,0,0,0,2,8,5,16.8286688328 +49,,SUM,1,0,1,0,10,21,83,32.7905819416 +49,,,,,,,,,, +50,,,,,,,,,, +50,BOWL,SUM,0,0,0,0,0,1,4,11.3818280697 +50,CUP,SUM,0,0,0,0,2,2,9,10.2579791546 +50,SPOON,SUM,1,0,1,0,8,11,46,0 +50,,SUM,1,0,1,0,10,14,59,21.6398072243 +50,,,,,,,,,, +51,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,8,1,0,12.1865301132 +51,CUP,SUM,0,0,0,0,16,13,21,26.327188015 +51,SPOON,SUM,0,0,0,0,2,4,4,14.2243080139 +51,,SUM,0,0,0,0,26,18,25,52.7380261421 +51,,,,,,,,,, +52,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,2,2,0,8.9843690395 +52,CUP,SUM,0,0,0,0,0,0,8,8.7611358166 +52,SPOON,SUM,0,0,0,0,0,2,0,12.0582890511 +52,,SUM,0,0,0,0,2,4,8,29.8037939072 +52,,,,,,,,,, +53,,,,,,,,,, +53,BOWL,SUM,0,0,0,0,0,4,12,13.9443809986 +53,CUP,SUM,0,0,0,0,0,1,18,11.4342019558 +53,SPOON,SUM,0,0,0,0,0,3,13,26.958147049 +53,,SUM,0,0,0,0,0,8,43,52.3367300034 +53,,,,,,,,,, +54,,,,,,,,,, +54,BOWL,SUM,0,0,0,0,8,7,0,20.0399370193 +54,CUP,SUM,0,0,0,0,0,4,8,9.0392341614 +54,SPOON,SUM,0,0,0,0,0,0,0,11.9590539932 +54,,SUM,0,0,0,0,8,11,8,41.038225174 +54,,,,,,,,,, +55,,,,,,,,,, +55,BOWL,SUM,0,0,0,0,16,0,0,17.2234749794 +55,CUP,SUM,1,0,1,0,0,22,135,0 +55,SPOON,SUM,0,0,0,0,0,3,4,11.0856480598 +55,,SUM,1,0,1,0,16,25,139,28.3091230392 +55,,,,,,,,,, +56,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,0,2,1,10.0545377731 +56,CUP,SUM,0,0,0,0,0,2,8,8.7348787785 +56,SPOON,SUM,0,0,0,0,0,3,0,11.915060997 +56,,SUM,0,0,0,0,0,7,9,30.7044775486 +56,,,,,,,,,, +57,,,,,,,,,, +57,BOWL,SUM,0,0,0,0,0,21,0,10.7666630745 +57,CUP,SUM,1,0,1,0,0,17,119,0 +57,SPOON,SUM,0,0,0,0,8,1,0,18.182464838 +57,,SUM,1,0,1,0,8,39,119,28.9491279125 +57,,,,,,,,,, +58,,,,,,,,,, +58,BOWL,SUM,0,0,0,0,2,0,0,9.4779970646 +58,CUP,SUM,0,0,0,0,16,8,23,27.578758955 +58,SPOON,SUM,0,0,0,0,0,3,0,12.3301131725 +58,,SUM,0,0,0,0,18,11,23,49.3868691921 +58,,,,,,,,,, +59,,,,,,,,,, +59,BOWL,SUM,0,0,0,0,0,2,16,15.3572249413 +59,CUP,SUM,0,0,0,0,8,3,8,13.2178461552 +59,SPOON,SUM,0,0,0,0,8,8,0,16.7570710182 +59,,SUM,0,0,0,0,16,13,24,45.3321421146 +59,,,,,,,,,, +60,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,8,17,4,14.5749878883 +60,CUP,SUM,0,0,0,0,0,0,8,8.6219570637 +60,SPOON,SUM,0,0,0,0,0,2,2,12.4710600376 +60,,SUM,0,0,0,0,8,19,14,35.6680049896 +60,,,,,,,,,, +61,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,0,5,0,9.4131758213 +61,CUP,SUM,0,0,0,0,0,1,9,9.2570340633 +61,SPOON,SUM,0,0,0,0,0,1,0,12.6277678013 +61,,SUM,0,0,0,0,0,7,9,31.2979776859 +61,,,,,,,,,, +62,,,,,,,,,, +62,BOWL,SUM,1,0,1,0,0,10,42,0 +62,CUP,SUM,0,0,0,0,0,3,28,21.1628861427 +62,SPOON,SUM,0,0,0,0,0,11,28,32.5177648067 +62,,SUM,1,0,1,0,0,24,98,53.6806509495 +62,,,,,,,,,, +63,,,,,,,,,, +63,BOWL,SUM,0,0,0,0,0,2,8,11.7775421143 +63,CUP,SUM,0,0,0,0,0,4,8,8.9378311634 +63,SPOON,SUM,0,0,0,0,0,7,0,12.4155600071 +63,,SUM,0,0,0,0,0,13,16,33.1309332848 +63,,,,,,,,,, +64,,,,,,,,,, +64,BOWL,SUM,0,0,0,0,8,21,11,20.5141060352 +64,CUP,SUM,1,0,1,0,0,8,53,0 +64,SPOON,SUM,0,0,0,0,0,11,4,14.9224128723 +64,,SUM,1,0,1,0,8,40,68,35.4365189075 +64,,,,,,,,,, +65,,,,,,,,,, +65,BOWL,SUM,0,0,0,0,0,1,1,10.4428038597 +65,CUP,SUM,0,0,0,0,0,5,20,14.1611599922 +65,SPOON,SUM,0,0,0,0,0,3,0,12.5926070213 +65,,SUM,0,0,0,0,0,9,21,37.1965708733 +65,,,,,,,,,, +66,,,,,,,,,, +66,BOWL,SUM,0,0,0,0,0,2,0,8.6577911377 +66,CUP,SUM,0,0,0,0,0,6,67,30.5818729401 +66,SPOON,SUM,0,0,0,0,2,5,0,13.8763139248 +66,,SUM,0,0,0,0,2,13,67,53.1159780025 +66,,,,,,,,,, +67,,,,,,,,,, +67,BOWL,SUM,0,0,0,0,0,12,15,15.9300789833 +67,CUP,SUM,1,0,1,0,4,7,63,0 +67,SPOON,SUM,0,0,0,0,0,1,0,11.2523219585 +67,,SUM,1,0,1,0,4,20,78,27.1824009418 +67,,,,,,,,,, +68,,,,,,,,,, +68,BOWL,SUM,0,0,0,0,8,0,0,11.6198208332 +68,CUP,SUM,0,0,0,0,2,5,14,15.6083889008 +68,SPOON,SUM,0,0,0,0,0,1,0,12.0422189236 +68,,SUM,0,0,0,0,10,6,14,39.2704286575 +68,,,,,,,,,, +69,,,,,,,,,, +69,BOWL,SUM,0,0,0,0,0,1,12,12.202881813 +69,CUP,SUM,0,0,0,0,2,3,8,9.9741330147 +69,SPOON,SUM,0,0,0,0,0,1,0,11.9872598648 +69,,SUM,0,0,0,0,2,5,20,34.1642746925 +69,,,,,,,,,, +70,,,,,,,,,, +70,BOWL,SUM,0,0,0,0,8,2,0,13.1749141216 +70,CUP,SUM,1,0,1,0,8,9,78,0 +70,SPOON,SUM,0,0,0,0,0,0,0,11.2089328766 +70,,SUM,1,0,1,0,16,11,78,24.3838469982 +70,,,,,,,,,, +71,,,,,,,,,, +71,BOWL,SUM,0,0,0,0,0,5,1,10.6148161888 +71,CUP,SUM,0,0,0,0,56,7,13,39.7586920261 +71,SPOON,SUM,0,0,0,0,0,6,5,15.0494308472 +71,,SUM,0,0,0,0,56,18,19,65.4229390621 +71,,,,,,,,,, +72,,,,,,,,,, +72,BOWL,SUM,0,0,0,0,0,6,4,9.8789288998 +72,CUP,SUM,0,0,0,0,0,4,17,13.5467891693 +72,SPOON,SUM,0,0,0,0,0,10,19,22.0361969471 +72,,SUM,0,0,0,0,0,20,40,45.4619150162 +72,,,,,,,,,, +73,,,,,,,,,, +73,BOWL,SUM,0,0,0,0,0,7,1,11.9781820774 +73,CUP,SUM,0,0,0,0,0,0,8,8.0586650372 +73,SPOON,SUM,0,0,0,0,0,3,0,12.7171919346 +73,,SUM,0,0,0,0,0,10,9,32.7540390491 +73,,,,,,,,,, +74,,,,,,,,,, +74,BOWL,SUM,0,0,0,0,8,8,0,13.1716458797 +74,CUP,SUM,0,0,0,0,0,16,26,17.0292191505 +74,SPOON,SUM,0,0,0,0,2,0,0,12.8939201832 +74,,SUM,0,0,0,0,10,24,26,43.0947852135 +74,,,,,,,,,, +75,,,,,,,,,, +75,BOWL,SUM,1,0,0,1,8,8,35,0 +75,CUP,SUM,0,0,0,0,10,7,52,32.3454859257 +75,SPOON,SUM,0,0,0,0,0,3,9,16.6799402237 +75,,SUM,1,0,0,1,18,18,96,49.0254261494 +75,,,,,,,,,, +76,,,,,,,,,, +76,BOWL,SUM,0,0,0,0,0,2,8,17.6890158653 +76,CUP,SUM,0,0,0,0,0,2,31,18.3480980396 +76,SPOON,SUM,0,0,0,0,0,2,0,11.5113668442 +76,,SUM,0,0,0,0,0,6,39,47.5484807491 +76,,,,,,,,,, +77,,,,,,,,,, +77,BOWL,SUM,0,0,0,0,0,1,0,8.2897741795 +77,CUP,SUM,0,0,0,0,8,0,8,11.8973419666 +77,SPOON,SUM,0,0,0,0,0,16,22,20.7913160324 +77,,SUM,0,0,0,0,8,17,30,40.9784321785 +77,,,,,,,,,, +78,,,,,,,,,, +78,BOWL,SUM,0,0,0,0,2,2,3,13.7646708488 +78,CUP,SUM,0,0,0,0,0,6,8,10.6656548977 +78,SPOON,SUM,0,0,0,0,0,3,0,12.6343328953 +78,,SUM,0,0,0,0,2,11,11,37.0646586418 +78,,,,,,,,,, +79,,,,,,,,,, +79,BOWL,SUM,0,0,0,0,0,13,10,12.8353478909 +79,CUP,SUM,0,0,0,0,8,7,8,13.6929280758 +79,SPOON,SUM,0,0,0,0,8,8,5,24.2914118767 +79,,SUM,0,0,0,0,16,28,23,50.8196878433 +79,,,,,,,,,, +80,,,,,,,,,, +80,BOWL,SUM,0,0,0,0,0,0,0,8.8202590942 +80,CUP,SUM,0,0,0,0,10,6,46,29.2234630585 +80,SPOON,SUM,0,0,0,0,8,0,0,16.5579969883 +80,,SUM,0,0,0,0,18,6,46,54.601719141 +80,,,,,,,,,, +81,,,,,,,,,, +81,BOWL,SUM,0,0,0,0,0,3,0,9.3924088478 +81,CUP,SUM,0,0,0,0,0,1,9,9.9047038555 +81,SPOON,SUM,0,0,0,0,0,7,1,14.0745661259 +81,,SUM,0,0,0,0,0,11,10,33.3716788292 +81,,,,,,,,,, +82,,,,,,,,,, +82,BOWL,SUM,0,0,0,0,16,1,8,21.037596941 +82,CUP,SUM,0,0,0,0,2,5,8,10.0474328995 +82,SPOON,SUM,0,0,0,0,0,0,4,13.4084510803 +82,,SUM,0,0,0,0,18,6,20,44.4934809208 +82,,,,,,,,,, +83,,,,,,,,,, +83,BOWL,SUM,0,0,0,0,0,1,0,9.2715330124 +83,CUP,SUM,0,0,0,0,0,2,9,9.9233140945 +83,SPOON,SUM,0,0,0,0,0,7,0,13.6907441616 +83,,SUM,0,0,0,0,0,10,9,32.8855912685 +83,,,,,,,,,, +84,,,,,,,,,, +84,BOWL,SUM,1,0,1,0,0,7,50,0 +84,CUP,SUM,0,0,0,0,0,6,46,21.3091490269 +84,SPOON,SUM,0,0,0,0,0,5,0,13.0033919811 +84,,SUM,1,0,1,0,0,18,96,34.312541008 +84,,,,,,,,,, +85,,,,,,,,,, +85,BOWL,SUM,0,0,0,0,0,1,2,9.81153512 +85,CUP,SUM,1,0,1,0,2,7,82,0 +85,SPOON,SUM,0,0,0,0,0,7,24,22.0011050701 +85,,SUM,1,0,1,0,2,15,108,31.8126401901 +85,,,,,,,,,, +86,,,,,,,,,, +86,BOWL,SUM,0,0,0,0,20,4,24,30.3210780621 +86,CUP,SUM,0,0,0,0,0,6,67,31.7467520237 +86,SPOON,SUM,0,0,0,0,2,3,0,12.543628931 +86,,SUM,0,0,0,0,22,13,91,74.6114590168 +86,,,,,,,,,, +87,,,,,,,,,, +87,BOWL,SUM,0,0,0,0,0,3,0,8.8535299301 +87,CUP,SUM,0,0,0,0,0,6,10,11.5513458252 +87,SPOON,SUM,0,0,0,0,8,10,1,18.9038031101 +87,,SUM,0,0,0,0,8,19,11,39.3086788654 +87,,,,,,,,,, +88,,,,,,,,,, +88,BOWL,SUM,0,0,0,0,0,2,0,8.176787138 +88,CUP,SUM,0,0,0,0,0,7,25,14.5087330341 +88,SPOON,SUM,0,0,0,0,0,3,1,14.4591498375 +88,,SUM,0,0,0,0,0,12,26,37.1446700096 +88,,,,,,,,,, +89,,,,,,,,,, +89,BOWL,SUM,0,0,0,0,0,1,1,10.9441628456 +89,CUP,SUM,0,0,0,0,0,2,8,8.7023880482 +89,SPOON,SUM,0,0,0,0,0,0,0,11.8025960922 +89,,SUM,0,0,0,0,0,3,9,31.449146986 +89,,,,,,,,,, +90,,,,,,,,,, +90,BOWL,SUM,0,0,0,0,10,13,2,17.6294960976 +90,CUP,SUM,0,0,0,0,2,0,8,9.3437690735 +90,SPOON,SUM,0,0,0,0,0,3,4,15.9582970142 +90,,SUM,0,0,0,0,12,16,14,42.9315621853 +90,,,,,,,,,, +91,,,,,,,,,, +91,BOWL,SUM,0,0,0,0,8,4,18,21.1909818649 +91,CUP,SUM,0,0,0,0,2,5,49,26.1136558056 +91,SPOON,SUM,0,0,0,0,0,7,17,23.8210988045 +91,,SUM,0,0,0,0,10,16,84,71.125736475 +91,,,,,,,,,, +92,,,,,,,,,, +92,BOWL,SUM,0,0,0,0,0,9,0,9.7193210125 +92,CUP,SUM,0,0,0,0,8,3,8,13.6172029972 +92,SPOON,SUM,0,0,0,0,14,5,0,22.2221279144 +92,,SUM,0,0,0,0,22,17,8,45.5586519241 +92,,,,,,,,,, +93,,,,,,,,,, +93,BOWL,SUM,1,0,1,0,0,6,44,0 +93,CUP,SUM,0,0,0,0,0,1,11,10.3774721622 +93,SPOON,SUM,0,0,0,0,0,1,0,11.7362718582 +93,,SUM,1,0,1,0,0,8,55,22.1137440205 +93,,,,,,,,,, +94,,,,,,,,,, +94,BOWL,SUM,0,0,0,0,2,0,4,9.5504350662 +94,CUP,SUM,0,0,0,0,0,4,17,12.5650060177 +94,SPOON,SUM,0,0,0,0,0,1,8,14.831182003 +94,,SUM,0,0,0,0,2,5,29,36.9466230869 +94,,,,,,,,,, +95,,,,,,,,,, +95,BOWL,SUM,0,0,0,0,2,9,9,16.8295280933 +95,CUP,SUM,0,0,0,0,0,0,9,9.8726351261 +95,SPOON,SUM,0,0,0,0,0,2,0,11.1721999645 +95,,SUM,0,0,0,0,2,11,18,37.874363184 +95,,,,,,,,,, +96,,,,,,,,,, +96,BOWL,SUM,0,0,0,0,14,3,2,21.2055969238 +96,CUP,SUM,0,0,0,0,0,2,37,20.6349389553 +96,SPOON,SUM,0,0,0,0,0,1,0,12.838547945 +96,,SUM,0,0,0,0,14,6,39,54.6790838242 +96,,,,,,,,,, +97,,,,,,,,,, +97,BOWL,SUM,0,0,0,0,0,1,0,7.5711941719 +97,CUP,SUM,0,0,0,0,0,6,9,9.9341030121 +97,SPOON,SUM,0,0,0,0,0,16,0,14.9681229591 +97,,SUM,0,0,0,0,0,23,9,32.4734201431 +97,,,,,,,,,, +98,,,,,,,,,, +98,BOWL,SUM,0,0,0,0,0,3,0,8.077917099 +98,CUP,SUM,0,0,0,0,0,1,27,14.1048429012 +98,SPOON,SUM,0,0,0,0,0,1,0,12.1434412003 +98,,SUM,0,0,0,0,0,5,27,34.3262012005 +98,,,,,,,,,, +99,,,,,,,,,, +99,BOWL,SUM,0,0,0,0,8,10,34,24.9848151207 +99,CUP,SUM,0,0,0,0,2,0,9,11.6440911293 +99,SPOON,SUM,0,0,0,0,0,5,6,14.6617000103 +99,,SUM,0,0,0,0,10,15,49,51.2906062603 +99,,,,,,,,,, +100,,,,,,,,,, +100,BOWL,SUM,0,0,0,0,8,6,9,16.6319000721 +100,CUP,SUM,0,0,0,0,0,3,21,13.7950179577 +100,SPOON,SUM,0,0,0,0,8,3,0,16.1928889751 +100,,SUM,0,0,0,0,16,12,30,46.6198070049 +100,,,,,,,,,, +101,,,,,,,,,, +101,BOWL,SUM,1,0,1,0,0,8,44,0 +101,CUP,SUM,0,0,0,0,8,4,28,20.0306360722 +101,SPOON,SUM,0,0,0,0,8,1,0,16.71179986 +101,,SUM,1,0,1,0,16,13,72,36.7424359322 +101,,,,,,,,,, +102,,,,,,,,,, +102,BOWL,SUM,0,0,0,0,0,1,0,9.5115101337 +102,CUP,SUM,0,0,0,0,2,2,8,9.9822981358 +102,SPOON,SUM,0,0,0,0,0,4,0,13.7404060364 +102,,SUM,0,0,0,0,2,7,8,33.2342143059 +102,,,,,,,,,, +103,,,,,,,,,, +103,BOWL,SUM,0,0,0,0,16,2,1,15.6639871597 +103,CUP,SUM,1,0,1,0,16,9,51,0 +103,SPOON,SUM,0,0,0,0,0,0,0,11.109803915 +103,,SUM,1,0,1,0,32,11,52,26.7737910748 +103,,,,,,,,,, +104,,,,,,,,,, +104,BOWL,SUM,0,0,0,0,8,5,1,16.3822968006 +104,CUP,SUM,1,0,1,0,0,8,77,0 +104,SPOON,SUM,0,0,0,0,2,8,5,17.3608489037 +104,,SUM,1,0,1,0,10,21,83,33.7431457043 +104,,,,,,,,,, +105,,,,,,,,,, +105,BOWL,SUM,0,0,0,0,0,1,4,11.5469229221 +105,CUP,SUM,0,0,0,0,2,2,9,10.271479845 +105,SPOON,SUM,1,0,1,0,8,11,46,0 +105,,SUM,1,0,1,0,10,14,59,21.8184027672 +105,,,,,,,,,, +106,,,,,,,,,, +106,BOWL,SUM,0,0,0,0,8,1,0,12.520072937 +106,CUP,SUM,0,0,0,0,16,13,21,26.7877368927 +106,SPOON,SUM,0,0,0,0,2,4,4,14.6401979923 +106,,SUM,0,0,0,0,26,18,25,53.948007822 +106,,,,,,,,,, +107,,,,,,,,,, +107,BOWL,SUM,0,0,0,0,2,2,0,8.8939509392 +107,CUP,SUM,0,0,0,0,0,0,8,8.7469089031 +107,SPOON,SUM,0,0,0,0,0,2,0,12.1294250488 +107,,SUM,0,0,0,0,2,4,8,29.7702848911 +107,,,,,,,,,, +108,,,,,,,,,, +108,BOWL,SUM,0,0,0,0,0,4,12,14.0969569683 +108,CUP,SUM,0,0,0,0,0,1,18,11.749614954 +108,SPOON,SUM,0,0,0,0,0,3,13,26.8417870998 +108,,SUM,0,0,0,0,0,8,43,52.6883590221 +108,,,,,,,,,, +109,,,,,,,,,, +109,BOWL,SUM,0,0,0,0,8,7,0,20.296364069 +109,CUP,SUM,0,0,0,0,0,4,8,9.1306929588 +109,SPOON,SUM,0,0,0,0,0,0,0,12.1252682209 +109,,SUM,0,0,0,0,8,11,8,41.5523252487 +109,,,,,,,,,, +110,,,,,,,,,, +110,BOWL,SUM,0,0,0,0,16,0,0,17.5314068794 +110,CUP,SUM,1,0,1,0,0,22,135,0 +110,SPOON,SUM,0,0,0,0,0,3,4,11.5408620834 +110,,SUM,1,0,1,0,16,25,139,29.0722689629 +110,,,,,,,,,, +111,,,,,,,,,, +111,BOWL,SUM,0,0,0,0,0,2,1,10.2117409706 +111,CUP,SUM,0,0,0,0,0,2,8,9.0250599384 +111,SPOON,SUM,0,0,0,0,0,3,0,11.8206629753 +111,,SUM,0,0,0,0,0,7,9,31.0574638844 +111,,,,,,,,,, +112,,,,,,,,,, +112,BOWL,SUM,0,0,0,0,0,21,0,10.8600468636 +112,CUP,SUM,1,0,1,0,0,17,119,0 +112,SPOON,SUM,0,0,0,0,8,1,0,18.4818348885 +112,,SUM,1,0,1,0,8,39,119,29.341881752 +112,,,,,,,,,, +113,,,,,,,,,, +113,BOWL,SUM,0,0,0,0,2,0,0,9.8451619148 +113,CUP,SUM,0,0,0,0,16,8,23,27.0057740211 +113,SPOON,SUM,0,0,0,0,0,3,0,12.8208341599 +113,,SUM,0,0,0,0,18,11,23,49.6717700958 +113,,,,,,,,,, +114,,,,,,,,,, +114,BOWL,SUM,0,0,0,0,0,2,16,15.5217041969 +114,CUP,SUM,0,0,0,0,8,3,8,14.0651209354 +114,SPOON,SUM,0,0,0,0,8,8,0,16.9467549324 +114,,SUM,0,0,0,0,16,13,24,46.5335800648 +114,,,,,,,,,, +115,,,,,,,,,, +115,BOWL,SUM,0,0,0,0,8,17,4,15.1020817757 +115,CUP,SUM,0,0,0,0,0,0,8,8.5815749168 +115,SPOON,SUM,0,0,0,0,0,2,2,12.7029480934 +115,,SUM,0,0,0,0,8,19,14,36.3866047859 +115,,,,,,,,,, +116,,,,,,,,,, +116,BOWL,SUM,0,0,0,0,0,5,0,9.5931780338 +116,CUP,SUM,0,0,0,0,0,1,9,9.3947200775 +116,SPOON,SUM,0,0,0,0,0,1,0,13.0033590794 +116,,SUM,0,0,0,0,0,7,9,31.9912571907 +116,,,,,,,,,, +117,,,,,,,,,, +117,BOWL,SUM,1,0,1,0,0,10,42,0 +117,CUP,SUM,0,0,0,0,0,3,28,21.7019751072 +117,SPOON,SUM,0,0,0,0,0,11,28,33.0930240154 +117,,SUM,1,0,1,0,0,24,98,54.7949991226 +117,,,,,,,,,, +118,,,,,,,,,, +118,BOWL,SUM,0,0,0,0,0,2,8,12.1588830948 +118,CUP,SUM,0,0,0,0,0,4,8,9.0444731712 +118,SPOON,SUM,0,0,0,0,0,7,0,12.9072160721 +118,,SUM,0,0,0,0,0,13,16,34.1105723381 +118,,,,,,,,,, +119,,,,,,,,,, +119,BOWL,SUM,0,0,0,0,8,21,11,20.5797851086 +119,CUP,SUM,1,0,1,0,0,8,53,0 +119,SPOON,SUM,0,0,0,0,0,11,4,15.5039110184 +119,,SUM,1,0,1,0,8,40,68,36.0836961269 +119,,,,,,,,,, +120,,,,,,,,,, +120,BOWL,SUM,0,0,0,0,0,1,1,10.6489179134 +120,CUP,SUM,0,0,0,0,0,5,20,14.144382 +120,SPOON,SUM,0,0,0,0,0,3,0,12.9957549572 +120,,SUM,0,0,0,0,0,9,21,37.7890548706 +120,,,,,,,,,, +121,,,,,,,,,, +121,BOWL,SUM,0,0,0,0,0,2,0,8.9371979237 +121,CUP,SUM,0,0,0,0,0,6,67,30.8375749588 +121,SPOON,SUM,0,0,0,0,2,5,0,14.4463419914 +121,,SUM,0,0,0,0,2,13,67,54.2211148739 +121,,,,,,,,,, +122,,,,,,,,,, +122,BOWL,SUM,0,0,0,0,0,12,15,15.8068780899 +122,CUP,SUM,1,0,1,0,4,7,63,0 +122,SPOON,SUM,0,0,0,0,0,1,0,11.5770280361 +122,,SUM,1,0,1,0,4,20,78,27.383906126 +122,,,,,,,,,, +123,,,,,,,,,, +123,BOWL,SUM,0,0,0,0,8,0,0,12.0141150951 +123,CUP,SUM,0,0,0,0,2,5,14,15.7797811031 +123,SPOON,SUM,0,0,0,0,0,1,0,12.3976700306 +123,,SUM,0,0,0,0,10,6,14,40.1915662289 +123,,,,,,,,,, +124,,,,,,,,,, +124,BOWL,SUM,0,0,0,0,0,1,12,12.3331639767 +124,CUP,SUM,0,0,0,0,2,3,8,10.0667610168 +124,SPOON,SUM,0,0,0,0,0,1,0,12.356896162 +124,,SUM,0,0,0,0,2,5,20,34.7568211555 +124,,,,,,,,,, +125,,,,,,,,,, +125,BOWL,SUM,0,0,0,0,8,2,0,13.2340250015 +125,CUP,SUM,1,0,1,0,8,9,78,0 +125,SPOON,SUM,0,0,0,0,0,0,0,11.1414489746 +125,,SUM,1,0,1,0,16,11,78,24.3754739761 +125,,,,,,,,,, +126,,,,,,,,,, +126,BOWL,SUM,0,0,0,0,0,5,1,10.7816548347 +126,CUP,SUM,0,0,0,0,56,7,13,40.2000989914 +126,SPOON,SUM,0,0,0,0,0,6,5,15.1644020081 +126,,SUM,0,0,0,0,56,18,19,66.1461558342 +126,,,,,,,,,, +127,,,,,,,,,, +127,BOWL,SUM,0,0,0,0,0,6,4,9.8695020676 +127,CUP,SUM,0,0,0,0,0,4,17,13.8128650188 +127,SPOON,SUM,0,0,0,0,0,10,19,21.8556649685 +127,,SUM,0,0,0,0,0,20,40,45.5380320549 +127,,,,,,,,,, +128,,,,,,,,,, +128,BOWL,SUM,0,0,0,0,0,7,1,12.3377430439 +128,CUP,SUM,0,0,0,0,0,0,8,8.1055619717 +128,SPOON,SUM,0,0,0,0,0,3,0,13.2631878853 +128,,SUM,0,0,0,0,0,10,9,33.7064929008 +128,,,,,,,,,, +129,,,,,,,,,, +129,BOWL,SUM,0,0,0,0,0,22,12,17.484167099 +129,CUP,SUM,0,0,0,0,0,16,20,15.8541278839 +129,SPOON,SUM,0,0,0,0,2,9,0,14.2880139351 +129,,SUM,0,0,0,0,2,47,32,47.626308918 +129,,,,,,,,,, +130,,,,,,,,,, +130,BOWL,SUM,0,0,0,0,0,4,12,13.7268381119 +130,CUP,SUM,0,0,0,0,0,7,42,21.0261740685 +130,SPOON,SUM,0,0,0,0,0,1,0,11.6369509697 +130,,SUM,0,0,0,0,0,12,54,46.38996315 +130,,,,,,,,,, +131,,,,,,,,,, +131,BOWL,SUM,0,0,0,0,18,5,28,26.8971281052 +131,CUP,SUM,0,0,0,0,0,9,8,10.7678720951 +131,SPOON,SUM,0,0,0,0,0,7,0,12.0308258533 +131,,SUM,0,0,0,0,18,21,36,49.6958260536 +131,,,,,,,,,, +132,,,,,,,,,, +132,BOWL,SUM,0,0,0,0,0,5,14,15.9205322266 +132,CUP,SUM,0,0,0,0,0,14,8,10.7989420891 +132,SPOON,SUM,1,0,1,0,0,14,11,0 +132,,SUM,1,0,1,0,0,33,33,26.7194743156 +132,,,,,,,,,, +133,,,,,,,,,, +133,BOWL,SUM,0,0,0,0,0,4,5,14.1082930565 +133,CUP,SUM,0,0,0,0,4,1,13,12.7270030975 +133,SPOON,SUM,0,0,0,0,16,13,4,36.9019489288 +133,,SUM,0,0,0,0,20,18,22,63.7372450829 +133,,,,,,,,,, +134,,,,,,,,,, +134,BOWL,SUM,0,0,0,0,0,6,0,10.4737198353 +134,CUP,SUM,0,0,0,0,24,16,34,33.523555994 +134,SPOON,SUM,0,0,0,0,0,3,2,15.5895130634 +134,,SUM,0,0,0,0,24,25,36,59.5867888927 +134,,,,,,,,,, +135,,,,,,,,,, +135,BOWL,SUM,0,0,0,0,0,2,0,9.5275111198 +135,CUP,SUM,0,0,0,0,2,2,23,16.0832350254 +135,SPOON,SUM,0,0,0,0,2,5,10,18.8270280361 +135,,SUM,0,0,0,0,4,9,33,44.4377741814 +135,,,,,,,,,, +136,,,,,,,,,, +136,BOWL,SUM,0,0,0,0,0,15,4,16.9680140018 +136,CUP,SUM,1,0,1,0,0,9,106,0 +136,SPOON,SUM,0,0,0,0,24,7,4,24.1122329235 +136,,SUM,1,0,1,0,24,31,114,41.0802469254 +136,,,,,,,,,, +137,,,,,,,,,, +137,BOWL,SUM,0,0,0,0,22,3,2,23.3682181835 +137,CUP,SUM,0,0,0,0,2,8,8,10.9837861061 +137,SPOON,SUM,0,0,0,0,0,3,0,13.0956449509 +137,,SUM,0,0,0,0,24,14,10,47.4476492405 +137,,,,,,,,,, +138,,,,,,,,,, +138,BOWL,SUM,0,0,0,0,0,0,4,9.4308941364 +138,CUP,SUM,0,0,0,0,0,3,8,10.1117010117 +138,SPOON,SUM,0,0,0,0,8,0,0,17.3162419796 +138,,SUM,0,0,0,0,8,3,12,36.8588371277 +138,,,,,,,,,, +139,,,,,,,,,, +139,BOWL,SUM,0,0,0,0,0,1,0,9.2899258137 +139,CUP,SUM,0,0,0,0,16,12,71,42.8380079269 +139,SPOON,SUM,0,0,0,0,0,8,19,22.1764428616 +139,,SUM,0,0,0,0,16,21,90,74.3043766022 +139,,,,,,,,,, +140,,,,,,,,,, +140,BOWL,SUM,0,0,0,0,8,3,9,16.3059420586 +140,CUP,SUM,0,0,0,0,10,8,49,33.7361040115 +140,SPOON,SUM,1,0,1,0,0,9,11,0 +140,,SUM,1,0,1,0,18,20,69,50.0420460701 +140,,,,,,,,,, +141,,,,,,,,,, +141,BOWL,SUM,0,0,0,0,8,1,0,16.6043851376 +141,CUP,SUM,1,0,1,0,20,7,126,0 +141,SPOON,SUM,1,0,1,0,32,12,11,0 +141,,SUM,2,0,2,0,60,20,137,16.6043851376 +141,,,,,,,,,, +142,,,,,,,,,, +142,BOWL,SUM,0,0,0,0,8,0,0,17.4152309895 +142,CUP,SUM,0,0,0,0,0,7,109,45.5534880161 +142,SPOON,SUM,0,0,0,0,0,18,7,17.5913360119 +142,,SUM,0,0,0,0,8,25,116,80.5600550175 +142,,,,,,,,,, +143,,,,,,,,,, +143,BOWL,SUM,0,0,0,0,8,17,12,20.6115529537 +143,CUP,SUM,0,0,0,0,0,1,11,10.9092340469 +143,SPOON,SUM,0,0,0,0,2,3,1,13.686756134 +143,,SUM,0,0,0,0,10,21,24,45.2075431347 +143,,,,,,,,,, +144,,,,,,,,,, +144,BOWL,SUM,0,0,0,0,0,2,0,8.893504858 +144,CUP,SUM,0,0,0,0,0,1,29,18.4887700081 +144,SPOON,SUM,0,0,0,0,0,12,7,18.5192329884 +144,,SUM,0,0,0,0,0,15,36,45.9015078545 +144,,,,,,,,,, +145,,,,,,,,,, +145,BOWL,SUM,0,0,0,0,0,5,4,13.5352010727 +145,CUP,SUM,0,0,0,0,2,6,13,19.6412708759 +145,SPOON,SUM,0,0,0,0,8,1,0,20.3212730885 +145,,SUM,0,0,0,0,10,12,17,53.4977450371 +145,,,,,,,,,, +146,,,,,,,,,, +146,BOWL,SUM,0,0,0,0,0,1,1,10.1164069176 +146,CUP,SUM,0,0,0,0,16,7,8,20.7620549202 +146,SPOON,SUM,1,0,1,0,0,11,11,0 +146,,SUM,1,0,1,0,16,19,20,30.8784618378 +146,,,,,,,,,, +147,,,,,,,,,, +147,BOWL,SUM,0,0,0,0,8,9,30,29.637816906 +147,CUP,SUM,0,0,0,0,0,1,9,10.688603878 +147,SPOON,SUM,0,0,0,0,8,2,0,17.4911358356 +147,,SUM,0,0,0,0,16,12,39,57.8175566196 +147,,,,,,,,,, +148,,,,,,,,,, +148,BOWL,SUM,0,0,0,0,0,7,9,13.0492727757 +148,CUP,SUM,0,0,0,0,8,1,10,14.2250959873 +148,SPOON,SUM,0,0,0,0,0,5,11,21.153922081 +148,,SUM,0,0,0,0,8,13,30,48.428290844 +148,,,,,,,,,, +149,,,,,,,,,, +149,BOWL,SUM,0,0,0,0,2,9,9,16.5710780621 +149,CUP,SUM,0,0,0,0,0,0,9,9.7253911495 +149,SPOON,SUM,0,0,0,0,0,2,0,10.9943780899 +149,,SUM,0,0,0,0,2,11,18,37.2908473015 +149,,,,,,,,,, +150,,,,,,,,,, +150,BOWL,SUM,0,0,0,0,14,3,2,20.5547230244 +150,CUP,SUM,0,0,0,0,0,2,37,18.9707920551 +150,SPOON,SUM,0,0,0,0,0,1,0,13.0611550808 +150,,SUM,0,0,0,0,14,6,39,52.5866701603 +150,,,,,,,,,, +151,,,,,,,,,, +151,BOWL,SUM,0,0,0,0,0,1,0,7.5482809544 +151,CUP,SUM,0,0,0,0,0,6,9,9.5270559788 +151,SPOON,SUM,0,0,0,0,0,16,0,14.7426860332 +151,,SUM,0,0,0,0,0,23,9,31.8180229664 +151,,,,,,,,,, +152,,,,,,,,,, +152,BOWL,SUM,0,0,0,0,0,3,0,7.6704599857 +152,CUP,SUM,0,0,0,0,0,1,27,13.5985081196 +152,SPOON,SUM,0,0,0,0,0,1,0,11.7748138905 +152,,SUM,0,0,0,0,0,5,27,33.0437819958 +152,,,,,,,,,, +153,,,,,,,,,, +153,BOWL,SUM,0,0,0,0,8,10,34,23.4281308651 +153,CUP,SUM,0,0,0,0,2,0,9,10.5171349049 +153,SPOON,SUM,0,0,0,0,0,5,6,14.3733201027 +153,,SUM,0,0,0,0,10,15,49,48.3185858727 +153,,,,,,,,,, +154,,,,,,,,,, +154,BOWL,SUM,0,0,0,0,8,6,9,15.7407851219 +154,CUP,SUM,0,0,0,0,0,3,21,12.4679927826 +154,SPOON,SUM,0,0,0,0,8,3,0,15.1039841175 +154,,SUM,0,0,0,0,16,12,30,43.312762022 +154,,,,,,,,,, +155,,,,,,,,,, +155,BOWL,SUM,1,0,1,0,0,8,44,0 +155,CUP,SUM,0,0,0,0,8,4,28,18.9013140202 +155,SPOON,SUM,0,0,0,0,8,1,0,15.8874628544 +155,,SUM,1,0,1,0,16,13,72,34.7887768745 +155,,,,,,,,,, +156,,,,,,,,,, +156,BOWL,SUM,0,0,0,0,0,1,0,9.3529009819 +156,CUP,SUM,0,0,0,0,2,2,8,9.54134202 +156,SPOON,SUM,0,0,0,0,0,4,0,13.2791109085 +156,,SUM,0,0,0,0,2,7,8,32.1733539104 +156,,,,,,,,,, +157,,,,,,,,,, +157,BOWL,SUM,0,0,0,0,16,2,1,14.4753739834 +157,CUP,SUM,1,0,1,0,16,9,51,0 +157,SPOON,SUM,0,0,0,0,0,0,0,10.7643082142 +157,,SUM,1,0,1,0,32,11,52,25.2396821976 +157,,,,,,,,,, +158,,,,,,,,,, +158,BOWL,SUM,0,0,0,0,8,5,1,15.519356966 +158,CUP,SUM,1,0,1,0,0,8,77,0 +158,SPOON,SUM,0,0,0,0,2,8,5,16.472463131 +158,,SUM,1,0,1,0,10,21,83,31.991820097 +158,,,,,,,,,, +159,,,,,,,,,, +159,BOWL,SUM,0,0,0,0,0,1,4,11.1084070206 +159,CUP,SUM,0,0,0,0,2,2,9,9.9092440605 +159,SPOON,SUM,1,0,1,0,8,11,46,0 +159,,SUM,1,0,1,0,10,14,59,21.0176510811 +159,,,,,,,,,, +160,,,,,,,,,, +160,BOWL,SUM,0,0,0,0,8,1,0,11.9087779522 +160,CUP,SUM,0,0,0,0,16,13,21,25.5116438866 +160,SPOON,SUM,0,0,0,0,2,4,4,14.2284789085 +160,,SUM,0,0,0,0,26,18,25,51.6489007473 +160,,,,,,,,,, +161,,,,,,,,,, +161,BOWL,SUM,0,0,0,0,2,2,0,8.7800588608 +161,CUP,SUM,0,0,0,0,0,0,8,8.5091378689 +161,SPOON,SUM,0,0,0,0,0,2,0,11.9040141106 +161,,SUM,0,0,0,0,2,4,8,29.1932108402 +161,,,,,,,,,, +162,,,,,,,,,, +162,BOWL,SUM,0,0,0,0,0,4,12,13.8613197803 +162,CUP,SUM,0,0,0,0,0,1,18,11.4546701908 +162,SPOON,SUM,0,0,0,0,0,3,13,26.8410189152 +162,,SUM,0,0,0,0,0,8,43,52.1570088863 +162,,,,,,,,,, +163,,,,,,,,,, +163,BOWL,SUM,0,0,0,0,8,7,0,19.321598053 +163,CUP,SUM,0,0,0,0,0,4,8,8.8551170826 +163,SPOON,SUM,0,0,0,0,0,0,0,11.8299710751 +163,,SUM,0,0,0,0,8,11,8,40.0066862106 +163,,,,,,,,,, +164,,,,,,,,,, +164,BOWL,SUM,0,0,0,0,16,0,0,16.3501670361 +164,CUP,SUM,1,0,1,0,0,22,135,0 +164,SPOON,SUM,0,0,0,0,0,3,4,11.0021181107 +164,,SUM,1,0,1,0,16,25,139,27.3522851467 +164,,,,,,,,,, +165,,,,,,,,,, +165,BOWL,SUM,0,0,0,0,0,2,1,9.814811945 +165,CUP,SUM,0,0,0,0,0,2,8,8.6740849018 +165,SPOON,SUM,0,0,0,0,0,3,0,11.6359701157 +165,,SUM,0,0,0,0,0,7,9,30.1248669624 +165,,,,,,,,,, +166,,,,,,,,,, +166,BOWL,SUM,0,0,0,0,0,21,0,10.7826371193 +166,CUP,SUM,1,0,1,0,0,17,119,0 +166,SPOON,SUM,0,0,0,0,8,1,0,17.7291870117 +166,,SUM,1,0,1,0,8,39,119,28.511824131 +166,,,,,,,,,, +167,,,,,,,,,, +167,BOWL,SUM,0,0,0,0,2,0,0,9.1797139645 +167,CUP,SUM,0,0,0,0,16,8,23,26.0081038475 +167,SPOON,SUM,0,0,0,0,0,3,0,12.0188400745 +167,,SUM,0,0,0,0,18,11,23,47.2066578865 +167,,,,,,,,,, +168,,,,,,,,,, +168,BOWL,SUM,0,0,0,0,0,2,16,15.1203789711 +168,CUP,SUM,0,0,0,0,8,3,8,12.5509371758 +168,SPOON,SUM,0,0,0,0,8,8,0,16.38575387 +168,,SUM,0,0,0,0,16,13,24,44.0570700169 +168,,,,,,,,,, +169,,,,,,,,,, +169,BOWL,SUM,0,0,0,0,8,17,4,14.2173280716 +169,CUP,SUM,0,0,0,0,0,0,8,8.3387839794 +169,SPOON,SUM,0,0,0,0,0,2,2,12.5175168514 +169,,SUM,0,0,0,0,8,19,14,35.0736289024 +169,,,,,,,,,, +170,,,,,,,,,, +170,BOWL,SUM,0,0,0,0,0,5,0,9.2157459259 +170,CUP,SUM,0,0,0,0,0,1,9,9.2396688461 +170,SPOON,SUM,0,0,0,0,0,1,0,12.4581029415 +170,,SUM,0,0,0,0,0,7,9,30.9135177135 +170,,,,,,,,,, +171,,,,,,,,,, +171,BOWL,SUM,1,0,1,0,0,10,42,0 +171,CUP,SUM,0,0,0,0,0,3,28,20.7623169422 +171,SPOON,SUM,0,0,0,0,0,11,28,31.6724450588 +171,,SUM,1,0,1,0,0,24,98,52.434762001 +171,,,,,,,,,, +172,,,,,,,,,, +172,BOWL,SUM,0,0,0,0,0,2,8,11.5977959633 +172,CUP,SUM,0,0,0,0,0,4,8,8.8810348511 +172,SPOON,SUM,0,0,0,0,0,7,0,12.1853890419 +172,,SUM,0,0,0,0,0,13,16,32.6642198563 +172,,,,,,,,,, +173,,,,,,,,,, +173,BOWL,SUM,0,0,0,0,8,21,11,19.5221409798 +173,CUP,SUM,1,0,1,0,0,8,53,0 +173,SPOON,SUM,0,0,0,0,0,11,4,14.7901911736 +173,,SUM,1,0,1,0,8,40,68,34.3123321533 +173,,,,,,,,,, +174,,,,,,,,,, +174,BOWL,SUM,0,0,0,0,0,1,1,10.287293911 +174,CUP,SUM,0,0,0,0,0,5,20,13.8196630478 +174,SPOON,SUM,0,0,0,0,0,3,0,12.4159939289 +174,,SUM,0,0,0,0,0,9,21,36.5229508877 +174,,,,,,,,,, +175,,,,,,,,,, +175,BOWL,SUM,0,0,0,0,0,2,0,8.4828579426 +175,CUP,SUM,0,0,0,0,0,6,67,30.3520700932 +175,SPOON,SUM,0,0,0,0,2,5,0,13.8513331413 +175,,SUM,0,0,0,0,2,13,67,52.6862611771 +175,,,,,,,,,, +176,,,,,,,,,, +176,BOWL,SUM,0,0,0,0,0,12,15,15.7096729279 +176,CUP,SUM,1,0,1,0,4,7,63,0 +176,SPOON,SUM,0,0,0,0,0,1,0,11.0305950642 +176,,SUM,1,0,1,0,4,20,78,26.740267992 +176,,,,,,,,,, +177,,,,,,,,,, +177,BOWL,SUM,0,0,0,0,8,0,0,11.3227498531 +177,CUP,SUM,0,0,0,0,2,5,14,15.2432849407 +177,SPOON,SUM,0,0,0,0,0,1,0,11.8735527992 +177,,SUM,0,0,0,0,10,6,14,38.4395875931 +177,,,,,,,,,, +178,,,,,,,,,, +178,BOWL,SUM,0,0,0,0,0,1,12,12.0997440815 +178,CUP,SUM,0,0,0,0,2,3,8,9.5297150612 +178,SPOON,SUM,0,0,0,0,0,1,0,11.9877660275 +178,,SUM,0,0,0,0,2,5,20,33.6172251701 +178,,,,,,,,,, +179,,,,,,,,,, +179,BOWL,SUM,0,0,0,0,8,2,0,12.7518279552 +179,CUP,SUM,1,0,1,0,8,9,78,0 +179,SPOON,SUM,0,0,0,0,0,0,0,11.1834151745 +179,,SUM,1,0,1,0,16,11,78,23.9352431297 +179,,,,,,,,,, +180,,,,,,,,,, +180,BOWL,SUM,0,0,0,0,0,5,1,10.4692001343 +180,CUP,SUM,0,0,0,0,56,7,13,36.7226991653 +180,SPOON,SUM,0,0,0,0,0,6,5,14.564136982 +180,,SUM,0,0,0,0,56,18,19,61.7560362816 +180,,,,,,,,,, +181,,,,,,,,,, +181,BOWL,SUM,0,0,0,0,0,6,4,9.8636031151 +181,CUP,SUM,0,0,0,0,0,4,17,13.4458398819 +181,SPOON,SUM,0,0,0,0,0,10,19,21.8631761074 +181,,SUM,0,0,0,0,0,20,40,45.1726191044 +181,,,,,,,,,, +182,,,,,,,,,, +182,BOWL,SUM,0,0,0,0,0,7,1,11.8912990093 +182,CUP,SUM,0,0,0,0,0,0,8,7.8630590439 +182,SPOON,SUM,0,0,0,0,0,3,0,12.5443320274 +182,,SUM,0,0,0,0,0,10,9,32.2986900806 +182,,,,,,,,,, +183,,,,,,,,,, +183,BOWL,SUM,0,0,0,0,0,22,12,17.155739069 +183,CUP,SUM,0,0,0,0,0,16,20,15.4741060734 +183,SPOON,SUM,0,0,0,0,2,9,0,13.8273839951 +183,,SUM,0,0,0,0,2,47,32,46.4572291374 +183,,,,,,,,,, +184,,,,,,,,,, +184,BOWL,SUM,0,0,0,0,0,4,12,13.700551033 +184,CUP,SUM,0,0,0,0,0,7,42,20.8035359383 +184,SPOON,SUM,0,0,0,0,0,1,0,11.4497230053 +184,,SUM,0,0,0,0,0,12,54,45.9538099766 +184,,,,,,,,,, +185,,,,,,,,,, +185,BOWL,SUM,0,0,0,0,18,5,28,25.434607029 +185,CUP,SUM,0,0,0,0,0,9,8,10.1796081066 +185,SPOON,SUM,0,0,0,0,0,7,0,12.0540821552 +185,,SUM,0,0,0,0,18,21,36,47.6682972908 +185,,,,,,,,,, +186,,,,,,,,,, +186,BOWL,SUM,0,0,0,0,0,5,14,15.4566950798 +186,CUP,SUM,0,0,0,0,0,14,8,10.8741090298 +186,SPOON,SUM,1,0,1,0,0,14,11,0 +186,,SUM,1,0,1,0,0,33,33,26.3308041096 +186,,,,,,,,,, +187,,,,,,,,,, +187,BOWL,SUM,0,0,0,0,0,4,5,13.6739640236 +187,CUP,SUM,0,0,0,0,4,1,13,12.2757570744 +187,SPOON,SUM,0,0,0,0,16,13,4,35.8456618786 +187,,SUM,0,0,0,0,20,18,22,61.7953829765 +187,,,,,,,,,, +188,,,,,,,,,, +188,BOWL,SUM,0,0,0,0,0,6,0,10.3277549744 +188,CUP,SUM,0,0,0,0,24,16,34,31.724766016 +188,SPOON,SUM,0,0,0,0,0,3,2,15.5621011257 +188,,SUM,0,0,0,0,24,25,36,57.6146221161 +188,,,,,,,,,, +189,,,,,,,,,, +189,BOWL,SUM,0,0,0,0,0,2,0,9.1651668549 +189,CUP,SUM,0,0,0,0,2,2,23,15.5984320641 +189,SPOON,SUM,0,0,0,0,2,5,10,17.8255610466 +189,,SUM,0,0,0,0,4,9,33,42.5891599655 +189,,,,,,,,,, +190,,,,,,,,,, +190,BOWL,SUM,0,0,0,0,0,15,4,16.3511359692 +190,CUP,SUM,1,0,1,0,0,9,106,0 +190,SPOON,SUM,0,0,0,0,24,7,4,22.7925560474 +190,,SUM,1,0,1,0,24,31,114,39.1436920166 +190,,,,,,,,,, +191,,,,,,,,,, +191,BOWL,SUM,0,0,0,0,22,3,2,21.8862309456 +191,CUP,SUM,0,0,0,0,2,8,8,11.2169578075 +191,SPOON,SUM,0,0,0,0,0,3,0,12.7851951122 +191,,SUM,0,0,0,0,24,14,10,45.8883838654 +191,,,,,,,,,, +192,,,,,,,,,, +192,BOWL,SUM,0,0,0,0,0,0,4,9.2299110889 +192,CUP,SUM,0,0,0,0,0,3,8,9.8890650272 +192,SPOON,SUM,0,0,0,0,8,0,0,16.2710289955 +192,,SUM,0,0,0,0,8,3,12,35.3900051117 +192,,,,,,,,,, +193,,,,,,,,,, +193,BOWL,SUM,0,0,0,0,0,1,0,8.909621954 +193,CUP,SUM,0,0,0,0,16,12,71,41.0975198746 +193,SPOON,SUM,0,0,0,0,0,8,19,21.7113130093 +193,,SUM,0,0,0,0,16,21,90,71.7184548378 +193,,,,,,,,,, +194,,,,,,,,,, +194,BOWL,SUM,0,0,0,0,8,3,9,15.7570240498 +194,CUP,SUM,0,0,0,0,10,8,49,32.808298111 +194,SPOON,SUM,1,0,1,0,0,9,11,0 +194,,SUM,1,0,1,0,18,20,69,48.5653221607 +194,,,,,,,,,, +195,,,,,,,,,, +195,BOWL,SUM,0,0,0,0,8,1,0,15.9714200497 +195,CUP,SUM,1,0,1,0,20,7,126,0 +195,SPOON,SUM,1,0,1,0,32,12,11,0 +195,,SUM,2,0,2,0,60,20,137,15.9714200497 +195,,,,,,,,,, +196,,,,,,,,,, +196,BOWL,SUM,0,0,0,0,8,0,0,17.005491972 +196,CUP,SUM,0,0,0,0,0,7,109,44.545799017 +196,SPOON,SUM,0,0,0,0,0,18,7,17.2711060047 +196,,SUM,0,0,0,0,8,25,116,78.8223969936 +196,,,,,,,,,, +197,,,,,,,,,, +197,BOWL,SUM,0,0,0,0,8,17,12,20.1240460873 +197,CUP,SUM,0,0,0,0,0,1,11,10.5506410599 +197,SPOON,SUM,0,0,0,0,2,3,1,13.9226257801 +197,,SUM,0,0,0,0,10,21,24,44.5973129272 +197,,,,,,,,,, +198,,,,,,,,,, +198,BOWL,SUM,0,0,0,0,0,2,0,8.7968699932 +198,CUP,SUM,0,0,0,0,0,1,29,18.2039649487 +198,SPOON,SUM,0,0,0,0,0,12,7,18.116245985 +198,,SUM,0,0,0,0,0,15,36,45.1170809269 +198,,,,,,,,,, +199,,,,,,,,,, +199,BOWL,SUM,1,0,1,0,6,4,44,0 +199,CUP,SUM,0,0,0,0,0,3,9,8.4732949734 +199,SPOON,SUM,0,0,0,0,2,3,4,13.6519620419 +199,,SUM,1,0,1,0,8,10,57,22.1252570152 +199,,,,,,,,,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/heur_pr2_new.csv b/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/heur_pr2_new.csv new file mode 100644 index 0000000000..34660e544d --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/heur_pr2_new.csv @@ -0,0 +1,1203 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC, +,,,,,,,,,,, +,,,,,,,,,,, +0,,,,,,,,,,, +0,BOWL,SUM,1,0,1,0,0,27,44,0, +0,CUP,SUM,1,0,1,0,8,12,73,0, +0,SPOON,SUM,0,0,0,0,0,4,17,13.5400369167, +0,,SUM,2,0,2,0,8,43,134,13.5400369167, +0,,,,,,,,,,, +1,,,,,,,,,,, +1,BOWL,SUM,1,0,0,1,0,12,19,0, +1,CUP,SUM,1,0,1,0,0,56,70,0, +1,SPOON,SUM,0,0,0,0,0,3,8,10.8458399773, +1,,SUM,2,0,1,1,0,71,97,10.8458399773, +1,,,,,,,,,,, +2,,,,,,,,,,, +2,BOWL,SUM,1,0,1,0,0,81,40,0, +2,CUP,SUM,1,0,1,0,0,15,11,0, +2,SPOON,SUM,0,0,0,0,0,2,1,10.7030098438, +2,,SUM,2,0,2,0,0,98,52,10.7030098438, +2,,,,,,,,,,, +3,,,,,,,,,,, +3,BOWL,SUM,1,0,0,1,16,10,11,0, +3,CUP,SUM,0,0,0,0,0,2,8,6.3630301952, +3,SPOON,SUM,0,0,0,0,0,11,1,9.8828501701, +3,,SUM,1,0,0,1,16,23,20,16.2458803654, +3,,,,,,,,,,, +4,,,,,,,,,,, +4,BOWL,SUM,1,0,1,0,0,39,44,0, +4,CUP,SUM,1,0,1,0,8,29,11,0, +4,SPOON,SUM,0,0,0,0,0,1,5,10.8044281006, +4,,SUM,2,0,2,0,8,69,60,10.8044281006, +4,,,,,,,,,,, +5,,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,0,1,4,7.7007250786, +5,CUP,SUM,0,0,0,0,0,2,7,6.077999115, +5,SPOON,SUM,1,0,1,0,0,343,0,0, +5,,SUM,1,0,1,0,0,346,11,13.7787241936, +5,,,,,,,,,,, +6,,,,,,,,,,, +6,BOWL,SUM,1,0,1,0,0,14,44,0, +6,CUP,SUM,0,0,0,0,0,3,4,4.4828810692, +6,SPOON,SUM,1,0,1,0,0,13,44,0, +6,,SUM,2,0,2,0,0,30,92,4.4828810692, +6,,,,,,,,,,, +7,,,,,,,,,,, +7,BOWL,SUM,1,0,1,0,0,8,44,0, +7,CUP,SUM,0,0,0,0,0,0,9,4.8672280312, +7,SPOON,SUM,1,0,1,0,0,21,44,0, +7,,SUM,2,0,2,0,0,29,97,4.8672280312, +7,,,,,,,,,,, +8,,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,0,4,12,9.7791581154, +8,CUP,SUM,0,0,0,0,0,8,22,8.3392710686, +8,SPOON,SUM,0,0,0,0,0,2,1,10.1766781807, +8,,SUM,0,0,0,0,0,14,35,28.2951073647, +8,,,,,,,,,,, +9,,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,9,20,10.2779750824, +9,CUP,SUM,0,0,0,0,0,4,9,5.6362390518, +9,SPOON,SUM,0,0,0,0,0,6,2,11.054901123, +9,,SUM,0,0,0,0,0,19,31,26.9691152573, +9,,,,,,,,,,, +10,,,,,,,,,,, +10,BOWL,SUM,1,0,1,0,0,5,44,0, +10,CUP,SUM,0,0,0,0,0,0,8,6.7623419762, +10,SPOON,SUM,0,0,0,0,0,14,3,11.8637588024, +10,,SUM,1,0,1,0,0,19,55,18.6261007786, +10,,,,,,,,,,, +11,,,,,,,,,,, +11,BOWL,SUM,1,0,1,0,0,21,44,0, +11,CUP,SUM,1,1,0,0,24,40,0,0, +11,SPOON,SUM,1,0,1,0,0,10,44,0, +11,,SUM,3,1,2,0,24,71,88,0, +11,,,,,,,,,,, +12,,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,0,8,2,7.5895960331, +12,CUP,SUM,0,0,0,0,0,2,6,5.0006430149, +12,SPOON,SUM,0,0,0,0,0,5,1,10.3595590591, +12,,SUM,0,0,0,0,0,15,9,22.9497981071, +12,,,,,,,,,,, +13,,,,,,,,,,, +13,BOWL,SUM,1,0,1,0,0,15,44,0, +13,CUP,SUM,1,0,1,0,8,5,49,0, +13,SPOON,SUM,0,0,0,0,0,7,31,16.5712828636, +13,,SUM,2,0,2,0,8,27,124,16.5712828636, +13,,,,,,,,,,, +14,,,,,,,,,,, +14,BOWL,SUM,1,0,1,0,8,26,44,0, +14,CUP,SUM,0,0,0,0,16,2,5,12.0677399635, +14,SPOON,SUM,1,0,1,0,0,14,44,0, +14,,SUM,2,0,2,0,24,42,93,12.0677399635, +14,,,,,,,,,,, +15,,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,24,10,29,20.9805870056, +15,CUP,SUM,1,0,1,0,0,9,33,0, +15,SPOON,SUM,1,0,1,0,0,10,44,0, +15,,SUM,2,0,2,0,24,29,106,20.9805870056, +15,,,,,,,,,,, +16,,,,,,,,,,, +16,BOWL,SUM,1,0,1,0,0,24,44,0, +16,CUP,SUM,0,0,0,0,0,0,38,10.8845748901, +16,SPOON,SUM,0,0,0,0,0,1,0,10.3752970695, +16,,SUM,1,0,1,0,0,25,82,21.2598719597, +16,,,,,,,,,,, +17,,,,,,,,,,, +17,BOWL,SUM,1,0,1,0,0,42,40,0, +17,CUP,SUM,0,0,0,0,0,5,3,4.9830751419, +17,SPOON,SUM,0,0,0,0,0,5,0,10.2711548805, +17,,SUM,1,0,1,0,0,52,43,15.2542300224, +17,,,,,,,,,,, +18,,,,,,,,,,, +18,BOWL,SUM,1,1,0,0,96,9,0,0, +18,CUP,SUM,1,0,1,0,0,12,33,0, +18,SPOON,SUM,0,0,0,0,0,4,4,11.0577030182, +18,,SUM,2,1,1,0,96,25,37,11.0577030182, +18,,,,,,,,,,, +19,,,,,,,,,,, +19,BOWL,SUM,1,0,1,0,0,15,44,0, +19,CUP,SUM,0,0,0,0,0,14,6,5.2752361298, +19,SPOON,SUM,0,0,0,0,8,3,9,16.3233239651, +19,,SUM,1,0,1,0,8,32,59,21.5985600948, +19,,,,,,,,,,, +20,,,,,,,,,,, +20,BOWL,SUM,1,0,1,0,0,6,44,0, +20,CUP,SUM,0,0,0,0,0,1,8,5.9818398952, +20,SPOON,SUM,1,0,1,0,0,34,44,0, +20,,SUM,2,0,2,0,0,41,96,5.9818398952, +20,,,,,,,,,,, +21,,,,,,,,,,, +21,BOWL,SUM,1,0,0,1,8,25,47,0, +21,CUP,SUM,0,0,0,0,0,7,29,8.9539978504, +21,SPOON,SUM,0,0,0,0,32,7,0,23.5252997875, +21,,SUM,1,0,0,1,40,39,76,32.4792976379, +21,,,,,,,,,,, +22,,,,,,,,,,, +22,BOWL,SUM,1,0,1,0,32,9,44,0, +22,CUP,SUM,1,0,1,0,0,41,30,0, +22,SPOON,SUM,0,0,0,0,0,2,0,10.1448099613, +22,,SUM,2,0,2,0,32,52,74,10.1448099613, +22,,,,,,,,,,, +23,,,,,,,,,,, +23,BOWL,SUM,1,0,1,0,8,36,40,0, +23,CUP,SUM,0,0,0,0,0,0,6,5.0217819214, +23,SPOON,SUM,0,0,0,0,0,1,0,9.9011011124, +23,,SUM,1,0,1,0,8,37,46,14.9228830338, +23,,,,,,,,,,, +24,,,,,,,,,,, +24,BOWL,SUM,1,0,0,1,0,2,19,0, +24,CUP,SUM,1,0,1,0,0,36,11,0, +24,SPOON,SUM,0,0,0,0,0,0,4,10.447026968, +24,,SUM,2,0,1,1,0,38,34,10.447026968, +24,,,,,,,,,,, +25,,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,0,5,37,13.2130250931, +25,CUP,SUM,1,0,1,0,0,20,33,0, +25,SPOON,SUM,0,0,0,0,0,6,28,15.6164619923, +25,,SUM,1,0,1,0,0,31,98,28.8294870853, +25,,,,,,,,,,, +26,,,,,,,,,,, +26,BOWL,SUM,1,0,1,0,0,23,44,0, +26,CUP,SUM,0,0,0,0,0,7,10,8.5528209209, +26,SPOON,SUM,0,0,0,0,0,0,6,12.0918300152, +26,,SUM,1,0,1,0,0,30,60,20.6446509361, +26,,,,,,,,,,, +27,,,,,,,,,,, +27,BOWL,SUM,1,0,1,0,0,14,44,0, +27,CUP,SUM,0,0,0,0,0,1,4,5.0635719299, +27,SPOON,SUM,1,0,1,0,0,10,44,0, +27,,SUM,2,0,2,0,0,25,92,5.0635719299, +27,,,,,,,,,,, +28,,,,,,,,,,, +28,BOWL,SUM,1,0,0,1,0,3,11,0, +28,CUP,SUM,1,0,1,0,0,20,11,0, +28,SPOON,SUM,0,0,0,0,8,1,0,14.4542222023, +28,,SUM,2,0,1,1,8,24,22,14.4542222023, +28,,,,,,,,,,, +29,,,,,,,,,,, +29,BOWL,SUM,1,0,1,0,0,10,44,0, +29,CUP,SUM,1,0,1,0,8,10,81,0, +29,SPOON,SUM,1,0,1,0,0,6,44,0, +29,,SUM,3,0,3,0,8,26,169,0, +29,,,,,,,,,,, +30,,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,0,0,4,8.610599041, +30,CUP,SUM,0,0,0,0,0,10,6,5.627518177, +30,SPOON,SUM,0,0,0,0,0,3,11,12.5609481335, +30,,SUM,0,0,0,0,0,13,21,26.7990653515, +30,,,,,,,,,,, +31,,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,8,5,40,21.3496539593, +31,CUP,SUM,1,0,1,0,0,72,45,0, +31,SPOON,SUM,0,0,0,0,0,2,24,16.9121580124, +31,,SUM,1,0,1,0,8,79,109,38.2618119717, +31,,,,,,,,,,, +32,,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,0,17,26,13.7097661495, +32,CUP,SUM,0,0,0,0,16,7,7,15.8343069553, +32,SPOON,SUM,1,0,1,0,0,10,44,0, +32,,SUM,1,0,1,0,16,34,77,29.5440731049, +32,,,,,,,,,,, +33,,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,3,9,11.7265059948, +33,CUP,SUM,0,0,0,0,0,5,4,6.0797560215, +33,SPOON,SUM,0,0,0,0,8,7,34,22.4832179546, +33,,SUM,0,0,0,0,8,15,47,40.2894799709, +33,,,,,,,,,,, +34,,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,0,11,10,9.5825929642, +34,CUP,SUM,0,0,0,0,0,1,7,7.2674689293, +34,SPOON,SUM,0,0,0,0,16,6,4,22.1296849251, +34,,SUM,0,0,0,0,16,18,21,38.9797468185, +34,,,,,,,,,,, +35,,,,,,,,,,, +35,BOWL,SUM,1,0,0,1,8,2,13,0, +35,CUP,SUM,1,0,1,0,8,16,33,0, +35,SPOON,SUM,0,0,0,0,0,0,1,11.4906909466, +35,,SUM,2,0,1,1,16,18,47,11.4906909466, +35,,,,,,,,,,, +36,,,,,,,,,,, +36,BOWL,SUM,1,0,1,0,0,26,44,0, +36,CUP,SUM,0,0,0,0,0,0,3,6.8225240707, +36,SPOON,SUM,1,0,1,0,0,11,44,0, +36,,SUM,2,0,2,0,0,37,91,6.8225240707, +36,,,,,,,,,,, +37,,,,,,,,,,, +37,BOWL,SUM,1,0,1,0,4,8,44,0, +37,CUP,SUM,0,0,0,0,0,2,6,7.3185169697, +37,SPOON,SUM,1,0,1,0,16,8,44,0, +37,,SUM,2,0,2,0,20,18,94,7.3185169697, +37,,,,,,,,,,, +38,,,,,,,,,,, +38,BOWL,SUM,1,0,1,0,0,10,44,0, +38,CUP,SUM,0,0,0,0,24,4,11,24.1062800884, +38,SPOON,SUM,1,0,1,0,0,15,44,0, +38,,SUM,2,0,2,0,24,29,99,24.1062800884, +38,,,,,,,,,,, +39,,,,,,,,,,, +39,BOWL,SUM,1,0,0,1,0,4,11,0, +39,CUP,SUM,0,0,0,0,8,64,12,38.4845230579, +39,SPOON,SUM,0,0,0,0,0,2,4,11.5273220539, +39,,SUM,1,0,0,1,8,70,27,50.0118451118, +39,,,,,,,,,,, +40,,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,0,3,18,12.0510649681, +40,CUP,SUM,0,0,0,0,16,3,4,15.7503910065, +40,SPOON,SUM,1,1,0,0,8,71,0,0, +40,,SUM,1,1,0,0,24,77,22,27.8014559746, +40,,,,,,,,,,, +41,,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,8,9,13,14.842140913, +41,CUP,SUM,1,0,1,0,12,13,11,0, +41,SPOON,SUM,0,0,0,0,48,6,12,45.0321519375, +41,,SUM,1,0,1,0,68,28,36,59.8742928505, +41,,,,,,,,,,, +42,,,,,,,,,,, +42,BOWL,SUM,1,0,0,1,32,9,11,0, +42,CUP,SUM,0,0,0,0,0,0,4,7.368407011, +42,SPOON,SUM,1,0,1,0,8,15,44,0, +42,,SUM,2,0,1,1,40,24,59,7.368407011, +42,,,,,,,,,,, +43,,,,,,,,,,, +43,BOWL,SUM,1,0,1,0,0,12,44,0, +43,CUP,SUM,0,0,0,0,0,0,6,6.9356291294, +43,SPOON,SUM,0,0,0,0,0,17,16,15.2582910061, +43,,SUM,1,0,1,0,0,29,66,22.1939201355, +43,,,,,,,,,,, +44,,,,,,,,,,, +44,BOWL,SUM,1,0,0,1,16,4,11,0, +44,CUP,SUM,0,0,0,0,0,3,9,8.5127358437, +44,SPOON,SUM,1,0,1,0,0,24,44,0, +44,,SUM,2,0,1,1,16,31,64,8.5127358437, +44,,,,,,,,,,, +45,,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,0,0,8,12.8065440655, +45,CUP,SUM,0,0,0,0,0,3,4,7.3045499325, +45,SPOON,SUM,1,0,1,0,0,157,24,0, +45,,SUM,1,0,1,0,0,160,36,20.111093998, +45,,,,,,,,,,, +46,,,,,,,,,,, +46,BOWL,SUM,1,0,0,1,0,2,11,0, +46,CUP,SUM,1,1,0,0,8,71,0,0, +46,SPOON,SUM,1,0,1,0,56,13,44,0, +46,,SUM,3,1,1,1,64,86,55,0, +46,,,,,,,,,,, +47,,,,,,,,,,, +47,BOWL,SUM,1,0,1,0,0,26,44,0, +47,CUP,SUM,1,0,1,0,8,13,43,0, +47,SPOON,SUM,0,0,0,0,0,1,8,13.2460870743, +47,,SUM,2,0,2,0,8,40,95,13.2460870743, +47,,,,,,,,,,, +48,,,,,,,,,,, +48,BOWL,SUM,1,0,1,0,0,4,44,0, +48,CUP,SUM,1,0,1,0,0,10,33,0, +48,SPOON,SUM,1,1,0,0,8,41,0,0, +48,,SUM,3,1,2,0,8,55,77,0, +48,,,,,,,,,,, +49,,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,0,2,14,12.1834981441, +49,CUP,SUM,0,0,0,0,0,3,28,11.2227091789, +49,SPOON,SUM,1,0,1,0,0,18,44,0, +49,,SUM,1,0,1,0,0,23,86,23.4062073231, +49,,,,,,,,,,, +50,,,,,,,,,,, +50,BOWL,SUM,1,0,1,0,8,9,44,0, +50,CUP,SUM,0,0,0,0,0,0,6,4.5915720463, +50,SPOON,SUM,0,0,0,0,0,7,29,15.854612112, +50,,SUM,1,0,1,0,8,16,79,20.4461841583, +50,,,,,,,,,,, +51,,,,,,,,,,, +51,BOWL,SUM,1,0,1,0,0,11,44,0, +51,CUP,SUM,0,0,0,0,60,11,24,32.5564930439, +51,SPOON,SUM,1,1,0,0,8,71,0,0, +51,,SUM,2,1,1,0,68,93,68,32.5564930439, +51,,,,,,,,,,, +52,,,,,,,,,,, +52,BOWL,SUM,1,0,1,0,0,28,44,0, +52,CUP,SUM,0,0,0,0,0,0,2,4.6323480606, +52,SPOON,SUM,0,0,0,0,0,4,20,13.4446179867, +52,,SUM,1,0,1,0,0,32,66,18.0769660473, +52,,,,,,,,,,, +53,,,,,,,,,,, +53,BOWL,SUM,1,0,1,0,0,8,44,0, +53,CUP,SUM,0,0,0,0,16,5,7,12.6101939678, +53,SPOON,SUM,0,0,0,0,0,2,0,10.2873198986, +53,,SUM,1,0,1,0,16,15,51,22.8975138664, +53,,,,,,,,,,, +54,,,,,,,,,,, +54,BOWL,SUM,1,0,1,0,0,341,0,0, +54,CUP,SUM,0,0,0,0,0,1,3,4.9721260071, +54,SPOON,SUM,0,0,0,0,0,3,16,12.8871209621, +54,,SUM,1,0,1,0,0,345,19,17.8592469692, +54,,,,,,,,,,, +55,,,,,,,,,,, +55,BOWL,SUM,1,0,1,0,0,24,44,0, +55,CUP,SUM,1,0,1,0,16,11,33,0, +55,SPOON,SUM,0,0,0,0,0,3,2,11.1226968765, +55,,SUM,2,0,2,0,16,38,79,11.1226968765, +55,,,,,,,,,,, +56,,,,,,,,,,, +56,BOWL,SUM,1,0,1,0,0,42,40,0, +56,CUP,SUM,0,0,0,0,0,0,9,4.9481818676, +56,SPOON,SUM,0,0,0,0,0,7,0,10.2461819649, +56,,SUM,1,0,1,0,0,49,49,15.1943638325, +56,,,,,,,,,,, +57,,,,,,,,,,, +57,BOWL,SUM,1,0,1,0,0,13,44,0, +57,CUP,SUM,0,0,0,0,8,6,8,9.9500939846, +57,SPOON,SUM,0,0,0,0,0,1,9,11.6489808559, +57,,SUM,1,0,1,0,8,20,61,21.5990748405, +57,,,,,,,,,,, +58,,,,,,,,,,, +58,BOWL,SUM,1,0,1,0,8,16,44,0, +58,CUP,SUM,0,0,0,0,32,5,18,21.36855793, +58,SPOON,SUM,0,0,0,0,0,4,22,15.7651488781, +58,,SUM,1,0,1,0,40,25,84,37.1337068081, +58,,,,,,,,,,, +59,,,,,,,,,,, +59,BOWL,SUM,0,0,0,0,0,15,17,10.7657368183, +59,CUP,SUM,1,0,0,1,0,5,36,0, +59,SPOON,SUM,0,0,0,0,14,9,34,23.7366280556, +59,,SUM,1,0,0,1,14,29,87,34.5023648739, +59,,,,,,,,,,, +60,,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,8,28,3,12.7926268578, +60,CUP,SUM,1,1,0,0,88,7,0,0, +60,SPOON,SUM,1,0,1,0,0,56,40,0, +60,,SUM,2,1,1,0,96,91,43,12.7926268578, +60,,,,,,,,,,, +61,,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,0,5,21,11.2028241158, +61,CUP,SUM,0,0,0,0,0,6,14,7.0317471027, +61,SPOON,SUM,0,0,0,0,0,2,0,10.2939629555, +61,,SUM,0,0,0,0,0,13,35,28.528534174, +61,,,,,,,,,,, +62,,,,,,,,,,, +62,BOWL,SUM,1,0,1,0,16,7,44,0, +62,CUP,SUM,1,0,0,1,0,3,11,0, +62,SPOON,SUM,1,0,1,0,0,13,44,0, +62,,SUM,3,0,2,1,16,23,99,0, +62,,,,,,,,,,, +63,,,,,,,,,,, +63,BOWL,SUM,0,0,0,0,0,6,37,14.1921870708, +63,CUP,SUM,1,0,0,1,0,5,17,0, +63,SPOON,SUM,0,0,0,0,0,1,7,12.4828801155, +63,,SUM,1,0,0,1,0,12,61,26.6750671864, +63,,,,,,,,,,, +64,,,,,,,,,,, +64,BOWL,SUM,0,0,0,0,0,9,50,17.8013710976, +64,CUP,SUM,0,0,0,0,0,7,14,7.0404908657, +64,SPOON,SUM,0,0,0,0,0,1,0,10.6422410011, +64,,SUM,0,0,0,0,0,17,64,35.4841029644, +64,,,,,,,,,,, +65,,,,,,,,,,, +65,BOWL,SUM,0,0,0,0,0,7,42,16.8008699417, +65,CUP,SUM,1,0,1,0,0,25,33,0, +65,SPOON,SUM,0,0,0,0,8,14,24,19.4968969822, +65,,SUM,1,0,1,0,8,46,99,36.2977669239, +65,,,,,,,,,,, +66,,,,,,,,,,, +66,BOWL,SUM,1,0,1,0,16,9,44,0, +66,CUP,SUM,0,0,0,0,0,1,13,8.4715030193, +66,SPOON,SUM,1,0,1,0,0,14,44,0, +66,,SUM,2,0,2,0,16,24,101,8.4715030193, +66,,,,,,,,,,, +67,,,,,,,,,,, +67,BOWL,SUM,0,0,0,0,0,10,14,13.3738029003, +67,CUP,SUM,0,0,0,0,16,6,16,17.3433208466, +67,SPOON,SUM,0,0,0,0,0,16,13,14.493491888, +67,,SUM,0,0,0,0,16,32,43,45.2106156349, +67,,,,,,,,,,, +68,,,,,,,,,,, +68,BOWL,SUM,0,0,0,0,0,0,5,8.5538840294, +68,CUP,SUM,0,0,0,0,0,1,5,6.1293330193, +68,SPOON,SUM,1,0,1,0,0,9,44,0, +68,,SUM,1,0,1,0,0,10,54,14.6832170486, +68,,,,,,,,,,, +69,,,,,,,,,,, +69,BOWL,SUM,1,0,0,1,8,5,11,0, +69,CUP,SUM,0,0,0,0,16,14,32,23.3946518898, +69,SPOON,SUM,0,0,0,0,0,7,19,15.6025791168, +69,,SUM,1,0,0,1,24,26,62,38.9972310066, +69,,,,,,,,,,, +70,,,,,,,,,,, +70,BOWL,SUM,0,0,0,0,0,6,17,13.3027000427, +70,CUP,SUM,1,0,1,0,0,19,11,0, +70,SPOON,SUM,0,0,0,0,0,0,1,12.5880019665, +70,,SUM,1,0,1,0,0,25,29,25.8907020092, +70,,,,,,,,,,, +71,,,,,,,,,,, +71,BOWL,SUM,1,0,1,0,0,14,44,0, +71,CUP,SUM,0,0,0,0,32,6,5,26.9268159866, +71,SPOON,SUM,0,0,0,0,0,6,6,13.432063818, +71,,SUM,1,0,1,0,32,26,55,40.3588798046, +71,,,,,,,,,,, +72,,,,,,,,,,, +72,BOWL,SUM,0,0,0,0,0,5,39,15.6998889446, +72,CUP,SUM,0,0,0,0,0,2,3,6.3949699402, +72,SPOON,SUM,1,0,1,0,0,13,44,0, +72,,SUM,1,0,1,0,0,20,86,22.0948588848, +72,,,,,,,,,,, +73,,,,,,,,,,, +73,BOWL,SUM,1,1,0,0,24,41,0,0, +73,CUP,SUM,1,0,1,0,0,15,77,0, +73,SPOON,SUM,0,0,0,0,0,9,41,19.7721829414, +73,,SUM,2,1,1,0,24,65,118,19.7721829414, +73,,,,,,,,,,, +74,,,,,,,,,,, +74,BOWL,SUM,1,0,1,0,8,20,44,0, +74,CUP,SUM,0,0,0,0,0,6,7,8.0530469418, +74,SPOON,SUM,0,0,0,0,0,6,24,17.7175290585, +74,,SUM,1,0,1,0,8,32,75,25.7705760002, +74,,,,,,,,,,, +75,,,,,,,,,,, +75,BOWL,SUM,1,0,1,0,0,12,44,0, +75,CUP,SUM,0,0,0,0,0,1,8,8.8516659737, +75,SPOON,SUM,0,0,0,0,0,2,2,13.4156200886, +75,,SUM,1,0,1,0,0,15,54,22.2672860622, +75,,,,,,,,,,, +76,,,,,,,,,,, +76,BOWL,SUM,1,0,0,1,8,1,11,0, +76,CUP,SUM,0,0,0,0,0,9,8,6.3222360611, +76,SPOON,SUM,1,0,1,0,0,9,44,0, +76,,SUM,2,0,1,1,8,19,63,6.3222360611, +76,,,,,,,,,,, +77,,,,,,,,,,, +77,BOWL,SUM,1,0,1,0,0,19,44,0, +77,CUP,SUM,0,0,0,0,0,6,5,7.5636029243, +77,SPOON,SUM,0,0,0,0,0,0,2,12.3398170471, +77,,SUM,1,0,1,0,0,25,51,19.9034199715, +77,,,,,,,,,,, +78,,,,,,,,,,, +78,BOWL,SUM,1,0,0,1,0,16,19,0, +78,CUP,SUM,0,0,0,0,0,4,11,6.5302820206, +78,SPOON,SUM,0,0,0,0,0,4,20,15.7602770329, +78,,SUM,1,0,0,1,0,24,50,22.2905590534, +78,,,,,,,,,,, +79,,,,,,,,,,, +79,BOWL,SUM,1,0,1,0,0,15,44,0, +79,CUP,SUM,0,0,0,0,8,1,23,13.3667681217, +79,SPOON,SUM,0,0,0,0,0,5,1,12.1156349182, +79,,SUM,1,0,1,0,8,21,68,25.4824030399, +79,,,,,,,,,,, +80,,,,,,,,,,, +80,BOWL,SUM,1,0,1,0,0,12,44,0, +80,CUP,SUM,1,0,1,0,8,13,77,0, +80,SPOON,SUM,0,0,0,0,0,6,44,20.4522180557, +80,,SUM,2,0,2,0,8,31,165,20.4522180557, +80,,,,,,,,,,, +81,,,,,,,,,,, +81,BOWL,SUM,0,0,0,0,8,5,5,15.7806241512, +81,CUP,SUM,1,0,1,0,8,7,33,0, +81,SPOON,SUM,0,0,0,0,4,3,17,17.670552969, +81,,SUM,1,0,1,0,20,15,55,33.4511771202, +81,,,,,,,,,,, +82,,,,,,,,,,, +82,BOWL,SUM,1,0,1,0,0,37,40,0, +82,CUP,SUM,0,0,0,0,8,2,10,14.8335299492, +82,SPOON,SUM,0,0,0,0,0,2,6,15.0019922256, +82,,SUM,1,0,1,0,8,41,56,29.8355221748, +82,,,,,,,,,,, +83,,,,,,,,,,, +83,BOWL,SUM,0,0,0,0,12,5,21,21.1763129234, +83,CUP,SUM,1,1,0,0,8,27,0,0, +83,SPOON,SUM,0,0,0,0,0,5,2,11.7200109959, +83,,SUM,1,1,0,0,20,37,23,32.8963239193, +83,,,,,,,,,,, +84,,,,,,,,,,, +84,BOWL,SUM,0,0,0,0,0,1,16,12.4908030033, +84,CUP,SUM,0,0,0,0,0,0,6,5.8719360828, +84,SPOON,SUM,0,0,0,0,0,5,0,11.4793810844, +84,,SUM,0,0,0,0,0,6,22,29.8421201706, +84,,,,,,,,,,, +85,,,,,,,,,,, +85,BOWL,SUM,1,0,0,1,8,2,15,0, +85,CUP,SUM,1,0,1,0,0,14,77,0, +85,SPOON,SUM,1,0,1,0,0,341,0,0, +85,,SUM,3,0,2,1,8,357,92,0, +85,,,,,,,,,,, +86,,,,,,,,,,, +86,BOWL,SUM,0,0,0,0,0,2,11,9.8810679913, +86,CUP,SUM,1,0,1,0,24,21,17,0, +86,SPOON,SUM,0,0,0,0,8,16,2,17.6317398548, +86,,SUM,1,0,1,0,32,39,30,27.5128078461, +86,,,,,,,,,,, +87,,,,,,,,,,, +87,BOWL,SUM,1,1,0,0,16,40,0,0, +87,CUP,SUM,0,0,0,0,0,5,17,8.2259118557, +87,SPOON,SUM,0,0,0,0,40,9,7,37.3156759739, +87,,SUM,1,1,0,0,56,54,24,45.5415878296, +87,,,,,,,,,,, +88,,,,,,,,,,, +88,BOWL,SUM,0,0,0,0,0,9,9,12.142663002, +88,CUP,SUM,0,0,0,0,0,1,6,6.2985889912, +88,SPOON,SUM,0,0,0,0,64,7,12,52.8196129799, +88,,SUM,0,0,0,0,64,17,27,71.2608649731, +88,,,,,,,,,,, +89,,,,,,,,,,, +89,BOWL,SUM,0,0,0,0,0,16,37,16.5440459251, +89,CUP,SUM,1,0,0,1,0,1,17,0, +89,SPOON,SUM,0,0,0,0,16,0,1,24.4949471951, +89,,SUM,1,0,0,1,16,17,55,41.0389931202, +89,,,,,,,,,,, +90,,,,,,,,,,, +90,BOWL,SUM,0,0,0,0,0,3,5,11.7328238487, +90,CUP,SUM,0,0,0,0,0,17,12,11.0472819805, +90,SPOON,SUM,1,0,1,0,8,20,44,0, +90,,SUM,1,0,1,0,8,40,61,22.7801058292, +90,,,,,,,,,,, +91,,,,,,,,,,, +91,BOWL,SUM,0,0,0,0,0,13,41,16.8758180141, +91,CUP,SUM,0,0,0,0,16,51,10,33.8195250034, +91,SPOON,SUM,0,0,0,0,0,2,5,13.7576839924, +91,,SUM,0,0,0,0,16,66,56,64.45302701, +91,,,,,,,,,,, +92,,,,,,,,,,, +92,BOWL,SUM,1,0,1,0,0,13,44,0, +92,CUP,SUM,1,0,1,0,16,8,11,0, +92,SPOON,SUM,0,0,0,0,0,10,17,15.3774459362, +92,,SUM,2,0,2,0,16,31,72,15.3774459362, +92,,,,,,,,,,, +93,,,,,,,,,,, +93,BOWL,SUM,0,0,0,0,0,3,8,12.3671450615, +93,CUP,SUM,0,0,0,0,0,13,6,8.6578369141, +93,SPOON,SUM,0,0,0,0,8,3,18,20.6980750561, +93,,SUM,0,0,0,0,8,19,32,41.7230570316, +93,,,,,,,,,,, +94,,,,,,,,,,, +94,BOWL,SUM,0,0,0,0,0,2,3,9.5711569786, +94,CUP,SUM,1,0,1,0,8,9,33,0, +94,SPOON,SUM,0,0,0,0,16,1,1,24.3515269756, +94,,SUM,1,0,1,0,24,12,37,33.9226839542, +94,,,,,,,,,,, +95,,,,,,,,,,, +95,BOWL,SUM,0,0,0,0,0,4,31,16.805629015, +95,CUP,SUM,1,0,1,0,0,27,33,0, +95,SPOON,SUM,0,0,0,0,0,7,24,16.2626509666, +95,,SUM,1,0,1,0,0,38,88,33.0682799816, +95,,,,,,,,,,, +96,,,,,,,,,,, +96,BOWL,SUM,1,0,1,0,0,12,44,0, +96,CUP,SUM,0,0,0,0,16,1,7,17.8180291653, +96,SPOON,SUM,0,0,0,0,0,1,0,11.880510807, +96,,SUM,1,0,1,0,16,14,51,29.6985399723, +96,,,,,,,,,,, +97,,,,,,,,,,, +97,BOWL,SUM,0,0,0,0,0,1,1,8.7802970409, +97,CUP,SUM,0,0,0,0,0,6,25,12.5315921307, +97,SPOON,SUM,1,1,0,0,0,42,0,0, +97,,SUM,1,1,0,0,0,49,26,21.3118891716, +97,,,,,,,,,,, +98,,,,,,,,,,, +98,BOWL,SUM,0,0,0,0,0,4,13,9.7245550156, +98,CUP,SUM,0,0,0,0,0,2,2,6.2576959133, +98,SPOON,SUM,1,0,1,0,0,27,44,0, +98,,SUM,1,0,1,0,0,33,59,15.9822509289, +98,,,,,,,,,,, +99,,,,,,,,,,, +99,BOWL,SUM,1,0,1,0,0,27,44,0, +99,CUP,SUM,1,0,1,0,8,12,73,0, +99,SPOON,SUM,0,0,0,0,0,4,17,13.7426280975, +99,,SUM,2,0,2,0,8,43,134,13.7426280975, +99,,,,,,,,,,, +100,,,,,,,,,,, +100,BOWL,SUM,0,0,0,0,0,3,20,11.8010160923, +100,CUP,SUM,1,0,1,0,0,7,11,0, +100,SPOON,SUM,0,0,0,0,16,6,1,24.7989139557, +100,,SUM,1,0,1,0,16,16,32,36.599930048, +100,,,,,,,,,,, +101,,,,,,,,,,, +101,BOWL,SUM,1,0,0,1,0,12,19,0, +101,CUP,SUM,1,0,1,0,0,56,70,0, +101,SPOON,SUM,0,0,0,0,0,3,8,11.4359250069, +101,,SUM,2,0,1,1,0,71,97,11.4359250069, +101,,,,,,,,,,, +102,,,,,,,,,,, +102,BOWL,SUM,1,0,1,0,0,81,40,0, +102,CUP,SUM,1,0,1,0,0,15,11,0, +102,SPOON,SUM,0,0,0,0,0,2,1,10.3460469246, +102,,SUM,2,0,2,0,0,98,52,10.3460469246, +102,,,,,,,,,,, +103,,,,,,,,,,, +103,BOWL,SUM,1,0,0,1,16,10,11,0, +103,CUP,SUM,0,0,0,0,0,2,8,6.3846328259, +103,SPOON,SUM,0,0,0,0,0,11,1,9.9385490417, +103,,SUM,1,0,0,1,16,23,20,16.3231818676, +103,,,,,,,,,,, +104,,,,,,,,,,, +104,BOWL,SUM,1,0,1,0,0,39,44,0, +104,CUP,SUM,1,0,1,0,8,29,11,0, +104,SPOON,SUM,0,0,0,0,0,1,5,10.4719629288, +104,,SUM,2,0,2,0,8,69,60,10.4719629288, +104,,,,,,,,,,, +105,,,,,,,,,,, +105,BOWL,SUM,0,0,0,0,0,1,4,7.6709680557, +105,CUP,SUM,0,0,0,0,0,2,7,6.2186059952, +105,SPOON,SUM,1,0,1,0,0,343,0,0, +105,,SUM,1,0,1,0,0,346,11,13.8895740509, +105,,,,,,,,,,, +106,,,,,,,,,,, +106,BOWL,SUM,1,0,1,0,0,14,44,0, +106,CUP,SUM,0,0,0,0,0,3,4,4.4082040787, +106,SPOON,SUM,1,0,1,0,0,13,44,0, +106,,SUM,2,0,2,0,0,30,92,4.4082040787, +106,,,,,,,,,,, +107,,,,,,,,,,, +107,BOWL,SUM,1,0,1,0,0,8,44,0, +107,CUP,SUM,0,0,0,0,0,0,9,4.7959961891, +107,SPOON,SUM,1,0,1,0,0,21,44,0, +107,,SUM,2,0,2,0,0,29,97,4.7959961891, +107,,,,,,,,,,, +108,,,,,,,,,,, +108,BOWL,SUM,0,0,0,0,0,4,12,9.5334329605, +108,CUP,SUM,0,0,0,0,0,8,22,8.4405250549, +108,SPOON,SUM,0,0,0,0,0,2,1,9.9288349152, +108,,SUM,0,0,0,0,0,14,35,27.9027929306, +108,,,,,,,,,,, +109,,,,,,,,,,, +109,BOWL,SUM,0,0,0,0,0,9,20,10.1935310364, +109,CUP,SUM,0,0,0,0,0,4,9,5.6742899418, +109,SPOON,SUM,0,0,0,0,0,6,2,10.6187880039, +109,,SUM,0,0,0,0,0,19,31,26.4866089821, +109,,,,,,,,,,, +110,,,,,,,,,,, +110,BOWL,SUM,1,0,1,0,0,5,44,0, +110,CUP,SUM,0,0,0,0,0,0,8,6.6443140507, +110,SPOON,SUM,0,0,0,0,0,14,3,11.3886129856, +110,,SUM,1,0,1,0,0,19,55,18.0329270363, +110,,,,,,,,,,, +111,,,,,,,,,,, +111,BOWL,SUM,1,0,1,0,0,21,44,0, +111,CUP,SUM,1,1,0,0,24,40,0,0, +111,SPOON,SUM,1,0,1,0,0,10,44,0, +111,,SUM,3,1,2,0,24,71,88,0, +111,,,,,,,,,,, +112,,,,,,,,,,, +112,BOWL,SUM,0,0,0,0,0,8,2,7.2476820946, +112,CUP,SUM,0,0,0,0,0,2,6,5.13134408, +112,SPOON,SUM,0,0,0,0,0,5,1,9.9607899189, +112,,SUM,0,0,0,0,0,15,9,22.3398160934, +112,,,,,,,,,,, +113,,,,,,,,,,, +113,BOWL,SUM,1,0,1,0,0,15,44,0, +113,CUP,SUM,1,0,1,0,8,5,49,0, +113,SPOON,SUM,0,0,0,0,0,7,31,16.161452055, +113,,SUM,2,0,2,0,8,27,124,16.161452055, +113,,,,,,,,,,, +114,,,,,,,,,,, +114,BOWL,SUM,1,0,1,0,8,26,44,0, +114,CUP,SUM,0,0,0,0,16,2,5,12.0059139729, +114,SPOON,SUM,1,0,1,0,0,14,44,0, +114,,SUM,2,0,2,0,24,42,93,12.0059139729, +114,,,,,,,,,,, +115,,,,,,,,,,, +115,BOWL,SUM,0,0,0,0,24,10,29,21.0402109623, +115,CUP,SUM,1,0,1,0,0,9,33,0, +115,SPOON,SUM,1,0,1,0,0,10,44,0, +115,,SUM,2,0,2,0,24,29,106,21.0402109623, +115,,,,,,,,,,, +116,,,,,,,,,,, +116,BOWL,SUM,1,0,1,0,0,24,44,0, +116,CUP,SUM,0,0,0,0,0,0,38,10.7499389648, +116,SPOON,SUM,0,0,0,0,0,1,0,9.9788239002, +116,,SUM,1,0,1,0,0,25,82,20.7287628651, +116,,,,,,,,,,, +117,,,,,,,,,,, +117,BOWL,SUM,1,0,1,0,0,42,40,0, +117,CUP,SUM,0,0,0,0,0,5,3,4.9641079903, +117,SPOON,SUM,0,0,0,0,0,5,0,9.9034800529, +117,,SUM,1,0,1,0,0,52,43,14.8675880432, +117,,,,,,,,,,, +118,,,,,,,,,,, +118,BOWL,SUM,1,1,0,0,96,9,0,0, +118,CUP,SUM,1,0,1,0,0,12,33,0, +118,SPOON,SUM,0,0,0,0,0,4,4,10.6765151024, +118,,SUM,2,1,1,0,96,25,37,10.6765151024, +118,,,,,,,,,,, +119,,,,,,,,,,, +119,BOWL,SUM,1,0,1,0,0,15,44,0, +119,CUP,SUM,0,0,0,0,0,14,6,5.4586949348, +119,SPOON,SUM,0,0,0,0,8,3,9,16.0127439499, +119,,SUM,1,0,1,0,8,32,59,21.4714388847, +119,,,,,,,,,,, +120,,,,,,,,,,, +120,BOWL,SUM,1,0,1,0,0,6,44,0, +120,CUP,SUM,0,0,0,0,0,1,8,6.1562922001, +120,SPOON,SUM,1,0,1,0,0,34,44,0, +120,,SUM,2,0,2,0,0,41,96,6.1562922001, +120,,,,,,,,,,, +121,,,,,,,,,,, +121,BOWL,SUM,1,0,0,1,8,25,47,0, +121,CUP,SUM,0,0,0,0,0,7,29,8.6942539215, +121,SPOON,SUM,0,0,0,0,32,7,0,22.842648983, +121,,SUM,1,0,0,1,40,39,76,31.5369029045, +121,,,,,,,,,,, +122,,,,,,,,,,, +122,BOWL,SUM,1,0,1,0,32,9,44,0, +122,CUP,SUM,1,0,1,0,0,41,30,0, +122,SPOON,SUM,0,0,0,0,0,2,0,10.0144908428, +122,,SUM,2,0,2,0,32,52,74,10.0144908428, +122,,,,,,,,,,, +123,,,,,,,,,,, +123,BOWL,SUM,1,0,1,0,8,36,40,0, +123,CUP,SUM,0,0,0,0,0,0,6,4.5151400566, +123,SPOON,SUM,0,0,0,0,0,1,0,9.7148361206, +123,,SUM,1,0,1,0,8,37,46,14.2299761772, +123,,,,,,,,,,, +124,,,,,,,,,,, +124,BOWL,SUM,1,0,0,1,0,2,19,0, +124,CUP,SUM,1,0,1,0,0,36,11,0, +124,SPOON,SUM,0,0,0,0,0,0,4,10.4653279781, +124,,SUM,2,0,1,1,0,38,34,10.4653279781, +124,,,,,,,,,,, +125,,,,,,,,,,, +125,BOWL,SUM,0,0,0,0,0,5,37,13.6137499809, +125,CUP,SUM,1,0,1,0,0,20,33,0, +125,SPOON,SUM,0,0,0,0,0,6,28,15.4622981548, +125,,SUM,1,0,1,0,0,31,98,29.0760481358, +125,,,,,,,,,,, +126,,,,,,,,,,, +126,BOWL,SUM,1,0,1,0,0,23,44,0, +126,CUP,SUM,0,0,0,0,0,7,10,8.4861087799, +126,SPOON,SUM,0,0,0,0,0,0,6,11.4946870804, +126,,SUM,1,0,1,0,0,30,60,19.9807958603, +126,,,,,,,,,,, +127,,,,,,,,,,, +127,BOWL,SUM,1,0,1,0,0,14,44,0, +127,CUP,SUM,0,0,0,0,0,1,4,5.0686948299, +127,SPOON,SUM,1,0,1,0,0,10,44,0, +127,,SUM,2,0,2,0,0,25,92,5.0686948299, +127,,,,,,,,,,, +128,,,,,,,,,,, +128,BOWL,SUM,1,0,0,1,0,3,11,0, +128,CUP,SUM,1,0,1,0,0,20,11,0, +128,SPOON,SUM,0,0,0,0,8,1,0,14.1841220856, +128,,SUM,2,0,1,1,8,24,22,14.1841220856, +128,,,,,,,,,,, +129,,,,,,,,,,, +129,BOWL,SUM,1,0,1,0,0,10,44,0, +129,CUP,SUM,1,0,1,0,8,10,81,0, +129,SPOON,SUM,1,0,1,0,0,6,44,0, +129,,SUM,3,0,3,0,8,26,169,0, +129,,,,,,,,,,, +130,,,,,,,,,,, +130,BOWL,SUM,0,0,0,0,0,0,4,8.6438801289, +130,CUP,SUM,0,0,0,0,0,10,6,5.2915380001, +130,SPOON,SUM,0,0,0,0,0,3,11,13.3512639999, +130,,SUM,0,0,0,0,0,13,21,27.2866821289, +130,,,,,,,,,,, +131,,,,,,,,,,, +131,BOWL,SUM,0,0,0,0,8,5,40,20.4245080948, +131,CUP,SUM,1,0,1,0,0,72,45,0, +131,SPOON,SUM,0,0,0,0,0,2,24,15.6421468258, +131,,SUM,1,0,1,0,8,79,109,36.0666549206, +131,,,,,,,,,,, +132,,,,,,,,,,, +132,BOWL,SUM,0,0,0,0,0,17,26,13.43572402, +132,CUP,SUM,0,0,0,0,16,7,7,14.698168993, +132,SPOON,SUM,1,0,1,0,0,10,44,0, +132,,SUM,1,0,1,0,16,34,77,28.133893013, +132,,,,,,,,,,, +133,,,,,,,,,,, +133,BOWL,,,,,,,,,, +133,CUP,BOWL,SUM,0,0,0,0,0,3,20,11.8010160923 +133,SPOON,CUP,SUM,1,0,1,0,0,7,11,0 +133,,SPOON,SUM,0,0,0,0,16,6,1,24.7989139557 +133,,,SUM,1,0,1,0,16,16,32,36.599930048 +134,,,,,,,,,,, +134,BOWL,SUM,0,0,0,0,0,11,10,9.5188651085, +134,CUP,SUM,0,0,0,0,0,1,7,7.6647639275, +134,SPOON,SUM,0,0,0,0,16,6,4,19.6616859436, +134,,SUM,0,0,0,0,16,18,21,36.8453149796, +134,,,,,,,,,,, +135,,,,,,,,,,, +135,BOWL,SUM,1,0,0,1,8,2,13,0, +135,CUP,SUM,1,0,1,0,8,16,33,0, +135,SPOON,SUM,0,0,0,0,0,0,1,11.9704418182, +135,,SUM,2,0,1,1,16,18,47,11.9704418182, +135,,,,,,,,,,, +136,,,,,,,,,,, +136,BOWL,SUM,1,0,1,0,0,26,44,0, +136,CUP,SUM,0,0,0,0,0,0,3,7.1904070377, +136,SPOON,SUM,1,0,1,0,0,11,44,0, +136,,SUM,2,0,2,0,0,37,91,7.1904070377, +136,,,,,,,,,,, +137,,,,,,,,,,, +137,BOWL,SUM,1,0,1,0,4,8,44,0, +137,CUP,SUM,0,0,0,0,0,2,6,5.923648119, +137,SPOON,SUM,1,0,1,0,16,8,44,0, +137,,SUM,2,0,2,0,20,18,94,5.923648119, +137,,,,,,,,,,, +138,,,,,,,,,,, +138,BOWL,SUM,1,0,1,0,0,10,44,0, +138,CUP,SUM,0,0,0,0,24,4,11,23.4751749039, +138,SPOON,SUM,1,0,1,0,0,15,44,0, +138,,SUM,2,0,2,0,24,29,99,23.4751749039, +138,,,,,,,,,,, +139,,,,,,,,,,, +139,BOWL,SUM,1,0,0,1,0,4,11,0, +139,CUP,SUM,0,0,0,0,8,64,12,36.9832060337, +139,SPOON,SUM,0,0,0,0,0,2,4,12.1681649685, +139,,SUM,1,0,0,1,8,70,27,49.1513710022, +139,,,,,,,,,,, +140,,,,,,,,,,, +140,BOWL,SUM,0,0,0,0,0,3,18,11.8182878494, +140,CUP,SUM,0,0,0,0,16,3,4,16.7213029861, +140,SPOON,SUM,1,1,0,0,8,71,0,0, +140,,SUM,1,1,0,0,24,77,22,28.5395908356, +140,,,,,,,,,,, +141,,,,,,,,,,, +141,BOWL,SUM,0,0,0,0,8,9,13,15.1042940617, +141,CUP,SUM,1,0,1,0,12,13,11,0, +141,SPOON,SUM,0,0,0,0,48,6,12,43.8079309464, +141,,SUM,1,0,1,0,68,28,36,58.912225008, +141,,,,,,,,,,, +142,,,,,,,,,,, +142,BOWL,SUM,1,0,0,1,32,9,11,0, +142,CUP,SUM,0,0,0,0,0,0,4,6.2575290203, +142,SPOON,SUM,1,0,1,0,8,14,44,0, +142,,SUM,2,0,1,1,40,23,59,6.2575290203, +142,,,,,,,,,,, +143,,,,,,,,,,, +143,BOWL,SUM,1,0,1,0,0,12,44,0, +143,CUP,SUM,0,0,0,0,0,0,6,5.9623861313, +143,SPOON,SUM,0,0,0,0,0,17,16,15.0095448494, +143,,SUM,1,0,1,0,0,29,66,20.9719309807, +143,,,,,,,,,,, +144,,,,,,,,,,, +144,BOWL,SUM,1,0,0,1,16,4,11,0, +144,CUP,SUM,0,0,0,0,0,3,9,8.5464868546, +144,SPOON,SUM,1,0,1,0,0,24,44,0, +144,,SUM,2,0,1,1,16,31,64,8.5464868546, +144,,,,,,,,,,, +145,,,,,,,,,,, +145,BOWL,SUM,0,0,0,0,0,0,8,11.432997942, +145,CUP,SUM,0,0,0,0,0,3,4,6.0902090073, +145,SPOON,SUM,1,0,1,0,0,157,24,0, +145,,SUM,1,0,1,0,0,160,36,17.5232069492, +145,,,,,,,,,,, +146,,,,,,,,,,, +146,BOWL,SUM,1,0,0,1,0,2,11,0, +146,CUP,SUM,1,1,0,0,8,71,0,0, +146,SPOON,SUM,1,0,1,0,56,13,44,0, +146,,SUM,3,1,1,1,64,86,55,0, +146,,,,,,,,,,, +147,,,,,,,,,,, +147,BOWL,SUM,1,0,1,0,0,26,44,0, +147,CUP,SUM,1,0,1,0,8,13,43,0, +147,SPOON,SUM,0,0,0,0,0,1,8,13.0368509293, +147,,SUM,2,0,2,0,8,40,95,13.0368509293, +147,,,,,,,,,,, +148,,,,,,,,,,, +148,BOWL,SUM,1,0,1,0,0,4,44,0, +148,CUP,SUM,1,0,1,0,0,10,33,0, +148,SPOON,SUM,1,1,0,0,8,41,0,0, +148,,SUM,3,1,2,0,8,55,77,0, +148,,,,,,,,,,, +149,,,,,,,,,,, +149,BOWL,SUM,0,0,0,0,0,2,14,11.6629359722, +149,CUP,SUM,0,0,0,0,0,3,28,11.6526257992, +149,SPOON,SUM,1,0,1,0,0,18,44,0, +149,,SUM,1,0,1,0,0,23,86,23.3155617714, +149,,,,,,,,,,, +150,,,,,,,,,,, +150,BOWL,SUM,1,0,1,0,8,9,44,0, +150,CUP,SUM,0,0,0,0,0,0,6,6.8687500954, +150,SPOON,SUM,0,0,0,0,0,7,29,17.9745469093, +150,,SUM,1,0,1,0,8,16,79,24.8432970047, +150,,,,,,,,,,, +151,,,,,,,,,,, +151,BOWL,SUM,1,0,1,0,0,11,44,0, +151,CUP,SUM,0,0,0,0,60,11,24,44.5633671284, +151,SPOON,SUM,1,1,0,0,8,71,0,0, +151,,SUM,2,1,1,0,68,93,68,44.5633671284, +151,,,,,,,,,,, +152,,,,,,,,,,, +152,BOWL,SUM,1,0,1,0,0,28,44,0, +152,CUP,SUM,0,0,0,0,0,0,2,5.480312109, +152,SPOON,SUM,0,0,0,0,0,4,20,15.8566520214, +152,,SUM,1,0,1,0,0,32,66,21.3369641304, +152,,,,,,,,,,, +153,,,,,,,,,,, +153,BOWL,SUM,1,0,1,0,0,8,44,0, +153,CUP,SUM,0,0,0,0,16,5,7,17.0104131699, +153,SPOON,SUM,0,0,0,0,0,2,0,10.861438036, +153,,SUM,1,0,1,0,16,15,51,27.8718512058, +153,,,,,,,,,,, +154,,,,,,,,,,, +154,BOWL,SUM,1,0,1,0,0,341,0,0, +154,CUP,SUM,0,0,0,0,0,1,3,6.3119931221, +154,SPOON,SUM,0,0,0,0,0,3,16,15.1821382046, +154,,SUM,1,0,1,0,0,345,19,21.4941313267, +154,,,,,,,,,,, +155,,,,,,,,,,, +155,BOWL,SUM,1,0,1,0,0,24,44,0, +155,CUP,SUM,1,0,1,0,16,11,33,0, +155,SPOON,SUM,0,0,0,0,0,3,2,12.6849770546, +155,,SUM,2,0,2,0,16,38,79,12.6849770546, +155,,,,,,,,,,, +156,,,,,,,,,,, +156,BOWL,SUM,1,0,1,0,0,42,40,0, +156,CUP,SUM,0,0,0,0,0,0,9,6.7622821331, +156,SPOON,SUM,0,0,0,0,0,7,0,11.763199091, +156,,SUM,1,0,1,0,0,49,49,18.5254812241, +156,,,,,,,,,,, +157,,,,,,,,,,, +157,BOWL,SUM,1,0,1,0,0,13,44,0, +157,CUP,SUM,0,0,0,0,8,6,8,13.2593421936, +157,SPOON,SUM,0,0,0,0,0,1,9,14.0687110424, +157,,SUM,1,0,1,0,8,20,61,27.328053236, +157,,,,,,,,,,, +158,,,,,,,,,,, +158,BOWL,SUM,1,0,1,0,8,16,44,0, +158,CUP,SUM,0,0,0,0,32,5,18,31.896447897, +158,SPOON,SUM,0,0,0,0,0,4,22,17.0525698662, +158,,SUM,1,0,1,0,40,25,84,48.9490177631, +158,,,,,,,,,,, +159,,,,,,,,,,, +159,BOWL,SUM,0,0,0,0,0,15,17,11.7529029846, +159,CUP,SUM,1,0,0,1,0,5,36,0, +159,SPOON,SUM,0,0,0,0,14,9,34,27.2936820984, +159,,SUM,1,0,0,1,14,29,87,39.046585083, +159,,,,,,,,,,, +160,,,,,,,,,,, +160,BOWL,SUM,0,0,0,0,8,28,3,16.12439394, +160,CUP,SUM,1,1,0,0,88,7,0,0, +160,SPOON,SUM,1,0,1,0,0,56,40,0, +160,,SUM,2,1,1,0,96,91,43,16.12439394, +160,,,,,,,,,,, +161,,,,,,,,,,, +161,BOWL,SUM,0,0,0,0,0,5,21,12.1083211899, +161,CUP,SUM,0,0,0,0,0,6,14,7.321873188, +161,SPOON,SUM,0,0,0,0,0,2,0,10.8815219402, +161,,SUM,0,0,0,0,0,13,35,30.3117163181, +161,,,,,,,,,,, +162,,,,,,,,,,, +162,BOWL,SUM,1,0,1,0,16,7,44,0, +162,CUP,SUM,1,0,0,1,0,3,11,0, +162,SPOON,SUM,1,0,1,0,0,13,44,0, +162,,SUM,3,0,2,1,16,23,99,0, +162,,,,,,,,,,, +163,,,,,,,,,,, +163,BOWL,SUM,0,0,0,0,0,6,37,15.5653710365, +163,CUP,SUM,1,0,0,1,0,5,17,0, +163,SPOON,SUM,0,0,0,0,0,1,7,13.0041890144, +163,,SUM,1,0,0,1,0,12,61,28.569560051, +163,,,,,,,,,,, +164,,,,,,,,,,, +164,BOWL,SUM,0,0,0,0,0,9,50,18.9871940613, +164,CUP,SUM,0,0,0,0,0,7,14,8.2136371136, +164,SPOON,SUM,0,0,0,0,0,1,0,11.0881400108, +164,,SUM,0,0,0,0,0,17,64,38.2889711857, +164,,,,,,,,,,, +165,,,,,,,,,,, +165,BOWL,SUM,0,0,0,0,0,7,42,18.5211920738, +165,CUP,SUM,1,0,1,0,0,25,33,0, +165,SPOON,SUM,0,0,0,0,8,14,24,21.5657382011, +165,,SUM,1,0,1,0,8,46,99,40.086930275, +165,,,,,,,,,,, +166,,,,,,,,,,, +166,BOWL,SUM,1,0,1,0,16,9,44,0, +166,CUP,SUM,0,0,0,0,0,1,13,8.9795269966, +166,SPOON,SUM,1,0,1,0,0,14,44,0, +166,,SUM,2,0,2,0,16,24,101,8.9795269966, +166,,,,,,,,,,, +167,,,,,,,,,,, +167,BOWL,SUM,0,0,0,0,0,10,14,15.3389379978, +167,CUP,SUM,0,0,0,0,16,6,16,22.1768651009, +167,SPOON,SUM,0,0,0,0,0,11,4,12.492866993, +167,,SUM,0,0,0,0,16,27,34,50.0086700916, +167,,,,,,,,,,, +168,,,,,,,,,,, +168,BOWL,SUM,0,0,0,0,0,0,1,8.3621249199, +168,CUP,SUM,1,0,1,0,0,4,33,0, +168,SPOON,SUM,1,0,1,0,0,13,44,0, +168,,SUM,2,0,2,0,0,17,78,8.3621249199, +168,,,,,,,,,,, +169,,,,,,,,,,, +169,BOWL,SUM,1,0,0,1,8,12,23,0, +169,CUP,SUM,1,0,1,0,24,27,77,0, +169,SPOON,SUM,0,0,0,0,0,2,0,10.2206320763, +169,,SUM,2,0,1,1,32,41,100,10.2206320763, +169,,,,,,,,,,, +170,,,,,,,,,,, +170,BOWL,SUM,0,0,0,0,20,0,6,22.3981318474, +170,CUP,SUM,0,0,0,0,0,7,2,5.4617760181, +170,SPOON,SUM,0,0,0,0,0,0,10,14.7321579456, +170,,SUM,0,0,0,0,20,7,18,42.5920658112, +170,,,,,,,,,,, +171,,,,,,,,,,, +171,BOWL,SUM,1,0,1,0,0,14,44,0, +171,CUP,SUM,0,0,0,0,16,3,12,18.2048490047, +171,SPOON,SUM,0,0,0,0,0,0,0,11.387693882, +171,,SUM,1,0,1,0,16,17,56,29.5925428867, +171,,,,,,,,,,, +172,,,,,,,,,,, +172,BOWL,SUM,0,0,0,0,16,6,1,18.9545619488, +172,CUP,SUM,0,0,0,0,16,2,5,16.498800993, +172,SPOON,SUM,1,0,1,0,0,21,44,0, +172,,SUM,1,0,1,0,32,29,50,35.4533629417, +172,,,,,,,,,,, +173,,,,,,,,,,, +173,BOWL,SUM,0,0,0,0,8,2,6,15.099834919, +173,CUP,SUM,1,0,1,0,0,13,77,0, +173,SPOON,SUM,0,0,0,0,0,3,0,11.2342867851, +173,,SUM,1,0,1,0,8,18,83,26.3341217041, +173,,,,,,,,,,, +174,,,,,,,,,,, +174,BOWL,SUM,1,0,1,0,0,16,44,0, +174,CUP,SUM,0,0,0,0,0,5,10,8.7305181026, +174,SPOON,SUM,0,0,0,0,0,3,10,14.4291517735, +174,,SUM,1,0,1,0,0,24,64,23.1596698761, +174,,,,,,,,,,, +175,,,,,,,,,,, +175,BOWL,SUM,0,0,0,0,8,10,13,18.8611459732, +175,CUP,SUM,1,0,1,0,0,15,39,0, +175,SPOON,SUM,0,0,0,0,8,6,17,19.5398159027, +175,,SUM,1,0,1,0,16,31,69,38.4009618759, +175,,,,,,,,,,, +176,,,,,,,,,,, +176,BOWL,SUM,0,0,0,0,0,0,4,10.1839029789, +176,CUP,SUM,0,0,0,0,0,0,3,7.5769870281, +176,SPOON,SUM,1,0,1,0,8,12,44,0, +176,,SUM,1,0,1,0,8,12,51,17.760890007, +176,,,,,,,,,,, +177,,,,,,,,,,, +177,BOWL,SUM,1,0,1,0,8,10,44,0, +177,CUP,SUM,0,0,0,0,0,3,12,7.454474926, +177,SPOON,SUM,0,0,0,0,0,0,1,10.6336429119, +177,,SUM,1,0,1,0,8,13,57,18.0881178379, +177,,,,,,,,,,, +178,,,,,,,,,,, +178,BOWL,SUM,0,0,0,0,0,0,2,9.6163320541, +178,CUP,SUM,1,0,1,0,8,15,11,0, +178,SPOON,SUM,0,0,0,0,0,13,14,15.2853200436, +178,,SUM,1,0,1,0,8,28,27,24.9016520977, +178,,,,,,,,,,, +179,,,,,,,,,,, +179,BOWL,SUM,1,0,1,0,0,19,44,0, +179,CUP,SUM,0,0,0,0,0,1,7,7.8703119755, +179,SPOON,SUM,0,0,0,0,12,3,10,21.2854120731, +179,,SUM,1,0,1,0,12,23,61,29.1557240486, +179,,,,,,,,,,, +180,,,,,,,,,,, +180,BOWL,SUM,1,0,0,1,40,8,11,0, +180,CUP,SUM,0,0,0,0,0,6,11,10.2074959278, +180,SPOON,SUM,0,0,0,0,16,2,4,21.9615950584, +180,,SUM,1,0,0,1,56,16,26,32.1690909863, +180,,,,,,,,,,, +181,,,,,,,,,,, +181,BOWL,SUM,1,0,1,0,0,19,44,0, +181,CUP,SUM,0,0,0,0,0,6,13,7.9505028725, +181,SPOON,SUM,0,0,0,0,16,1,0,22.5744860172, +181,,SUM,1,0,1,0,16,26,57,30.5249888897, +181,,,,,,,,,,, +182,,,,,,,,,,, +182,BOWL,SUM,0,0,0,0,8,3,21,19.5262699127, +182,CUP,SUM,1,0,1,0,0,10,33,0, +182,SPOON,SUM,1,0,1,0,0,25,44,0, +182,,SUM,2,0,2,0,8,38,98,19.5262699127, +182,,,,,,,,,,, +183,,,,,,,,,,, +183,BOWL,SUM,1,0,0,1,8,0,13,0, +183,CUP,SUM,0,0,0,0,0,1,2,8.4699010849, +183,SPOON,SUM,1,0,1,0,0,28,44,0, +183,,SUM,2,0,1,1,8,29,59,8.4699010849, +183,,,,,,,,,,, +184,,,,,,,,,,, +184,BOWL,SUM,1,0,1,0,0,174,24,0, +184,CUP,SUM,0,0,0,0,0,0,15,8.2353930473, +184,SPOON,SUM,0,0,0,0,0,4,5,14.0056550503, +184,,SUM,1,0,1,0,0,178,44,22.2410480976, +184,,,,,,,,,,, +185,,,,,,,,,,, +185,BOWL,SUM,1,1,0,0,96,6,0,0, +185,CUP,SUM,0,0,0,0,16,13,6,50.9591639042, +185,SPOON,SUM,1,0,1,0,0,15,44,0, +185,,SUM,2,1,1,0,112,34,50,50.9591639042, +185,,,,,,,,,,, +186,,,,,,,,,,, +186,BOWL,SUM,0,0,0,0,0,0,4,9.7632758617, +186,CUP,SUM,1,0,0,1,20,6,13,0, +186,SPOON,SUM,1,0,1,0,0,28,44,0, +186,,SUM,2,0,1,1,20,34,61,9.7632758617, +186,,,,,,,,,,, +187,,,,,,,,,,, +187,BOWL,SUM,1,0,1,0,12,10,44,0, +187,CUP,SUM,0,0,0,0,0,2,2,6.8748562336, +187,SPOON,SUM,0,0,0,0,0,1,0,11.1090378761, +187,,SUM,1,0,1,0,12,13,46,17.9838941097, +187,,,,,,,,,,, +188,,,,,,,,,,, +188,BOWL,SUM,1,0,1,0,16,15,44,0, +188,CUP,SUM,0,0,0,0,0,1,6,6.037142992, +188,SPOON,SUM,0,0,0,0,16,3,1,22.871876955, +188,,SUM,1,0,1,0,32,19,51,28.9090199471, +188,,,,,,,,,,, +189,,,,,,,,,,, +189,BOWL,SUM,0,0,0,0,0,3,0,8.9889361858, +189,CUP,SUM,0,0,0,0,0,2,12,7.1721839905, +189,SPOON,SUM,0,0,0,0,16,9,40,29.7200610638, +189,,SUM,0,0,0,0,16,14,52,45.8811812401, +189,,,,,,,,,,, +190,,,,,,,,,,, +190,BOWL,SUM,0,0,0,0,0,5,15,11.6802399158, +190,CUP,SUM,1,0,1,0,0,55,10,0, +190,SPOON,SUM,0,0,0,0,0,4,5,12.5475389957, +190,,SUM,1,0,1,0,0,64,30,24.2277789116, +190,,,,,,,,,,, +191,,,,,,,,,,, +191,BOWL,SUM,0,0,0,0,8,32,20,19.5476880074, +191,CUP,SUM,0,0,0,0,0,22,8,7.9055600166, +191,SPOON,SUM,0,0,0,0,26,3,4,28.8938138485, +191,,SUM,0,0,0,0,34,57,32,56.3470618725, +191,,,,,,,,,,, +192,,,,,,,,,,, +192,BOWL,SUM,1,0,1,0,0,12,44,0, +192,CUP,SUM,0,0,0,0,0,4,4,7.2315981388, +192,SPOON,SUM,0,0,0,0,0,1,0,11.6747610569, +192,,SUM,1,0,1,0,0,17,48,18.9063591957, +192,,,,,,,,,,, +193,,,,,,,,,,, +193,BOWL,SUM,0,0,0,0,24,4,6,25.858355999, +193,CUP,SUM,1,0,1,0,0,26,33,0, +193,SPOON,SUM,0,0,0,0,0,5,28,17.0169429779, +193,,SUM,1,0,1,0,24,35,67,42.8752989769, +193,,,,,,,,,,, +194,,,,,,,,,,, +194,BOWL,SUM,1,0,1,0,0,7,44,0, +194,CUP,SUM,0,0,0,0,0,0,2,4.9429750443, +194,SPOON,SUM,1,0,1,0,0,341,0,0, +194,,SUM,2,0,2,0,0,348,46,4.9429750443, +194,,,,,,,,,,, +195,,,,,,,,,,, +195,BOWL,SUM,0,0,0,0,0,1,8,10.3405179977, +195,CUP,SUM,1,0,1,0,0,21,33,0, +195,SPOON,SUM,1,0,1,0,0,8,44,0, +195,,SUM,2,0,2,0,0,30,85,10.3405179977, +195,,,,,,,,,,, +196,,,,,,,,,,, +196,BOWL,SUM,1,0,1,0,0,37,40,0, +196,CUP,SUM,0,0,0,0,0,5,13,11.7845001221, +196,SPOON,SUM,0,0,0,0,0,5,17,14.992718935, +196,,SUM,1,0,1,0,0,47,70,26.7772190571, +196,,,,,,,,,,, +197,,,,,,,,,,, +197,BOWL,SUM,1,0,0,1,0,6,13,0, +197,CUP,SUM,1,0,1,0,4,10,11,0, +197,SPOON,SUM,0,0,0,0,8,6,37,25.0864229202, +197,,SUM,2,0,1,1,12,22,61,25.0864229202, +197,,,,,,,,,,, +198,,,,,,,,,,, +198,BOWL,SUM,0,0,0,0,8,8,5,17.2684919834, +198,CUP,SUM,1,1,0,0,8,80,0,0, +198,SPOON,SUM,0,0,0,0,0,2,25,16.5347821712, +198,,SUM,1,1,0,0,16,90,30,33.8032741547, +198,,,,,,,,,,, +199,,,,,,,,,,, +199,BOWL,SUM,1,0,1,0,0,28,44,0, +199,CUP,SUM,0,0,0,0,0,2,5,7.9615008831, +199,SPOON,SUM,0,0,0,0,0,5,36,18.3941440582, +199,,SUM,1,0,1,0,0,35,85,26.3556449413, +199,,,,,,,,,,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/heur_pr2_orig.csv b/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/heur_pr2_orig.csv new file mode 100644 index 0000000000..ac76a60080 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/heur_pr2_orig.csv @@ -0,0 +1,1203 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,16,0,0,16.0908989906 +0,CUP,SUM,1,0,0,1,0,0,11,0 +0,SPOON,SUM,1,0,1,0,0,5,44,0 +0,,SUM,2,0,1,1,16,5,55,16.0908989906 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,8,1,13,13.5569479465 +1,CUP,SUM,0,0,0,0,16,2,14,15.1056079865 +1,SPOON,SUM,0,0,0,0,0,0,0,9.9465920925 +1,,SUM,0,0,0,0,24,3,27,38.6091480255 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,1,0,1,0,0,1,44,0 +2,CUP,SUM,1,0,0,1,0,5,32,0 +2,SPOON,SUM,0,0,0,0,0,0,9,11.9806311131 +2,,SUM,2,0,1,1,0,6,85,11.9806311131 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,0,0,4,7.8048260212 +3,CUP,SUM,0,0,0,0,0,1,11,6.6010439396 +3,SPOON,SUM,0,0,0,0,0,0,0,10.4570579529 +3,,SUM,0,0,0,0,0,1,15,24.8629279137 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,1,4,7.902613163 +4,CUP,SUM,1,0,0,1,16,0,12,0 +4,SPOON,SUM,0,0,0,0,0,2,20,13.772217989 +4,,SUM,1,0,0,1,16,3,36,21.674831152 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,24,4,36,24.1229500771 +5,CUP,SUM,0,0,0,0,0,0,2,4.5270810127 +5,SPOON,SUM,0,0,0,0,0,0,7,12.2756679058 +5,,SUM,0,0,0,0,24,4,45,40.9256989956 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,8,2,13,12.9568269253 +6,CUP,SUM,1,0,0,1,0,0,11,0 +6,SPOON,SUM,0,0,0,0,0,0,5,11.7542731762 +6,,SUM,1,0,0,1,8,2,29,24.7111001015 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,44,2,9,27.55534482 +7,CUP,SUM,0,0,0,0,24,3,10,16.7267870903 +7,SPOON,SUM,1,0,1,0,8,3,44,0 +7,,SUM,1,0,1,0,76,8,63,44.2821319103 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,1,0,1,0,24,4,44,0 +8,CUP,SUM,1,0,0,1,0,1,18,0 +8,SPOON,SUM,0,0,0,0,0,1,8,11.8552091122 +8,,SUM,2,0,1,1,24,6,70,11.8552091122 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,0,5,8.5220751762 +9,CUP,SUM,1,0,0,1,0,2,11,0 +9,SPOON,SUM,0,0,0,0,8,1,1,13.6455879211 +9,,SUM,1,0,0,1,8,3,17,22.1676630974 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,3,32,13.3466501236 +10,CUP,SUM,1,0,0,1,0,0,11,0 +10,SPOON,SUM,0,0,0,0,16,0,5,18.4817039967 +10,,SUM,1,0,0,1,16,3,48,31.8283541203 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,8,7,32,16.2029840946 +11,CUP,SUM,0,0,0,0,0,3,16,10.1003251076 +11,SPOON,SUM,0,0,0,0,0,2,16,13.2082059383 +11,,SUM,0,0,0,0,8,12,64,39.5115151405 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,0,0,8,8.357074976 +12,CUP,SUM,1,0,0,1,0,0,17,0 +12,SPOON,SUM,0,0,0,0,8,5,24,17.9342930317 +12,,SUM,1,0,0,1,8,5,49,26.2913680077 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,0,1,12,9.102337122 +13,CUP,SUM,0,0,0,0,8,0,2,8.3139820099 +13,SPOON,SUM,0,0,0,0,0,5,32,16.4842641354 +13,,SUM,0,0,0,0,8,6,46,33.9005832672 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,16,4,0,14.2003099918 +14,CUP,SUM,1,0,0,1,0,0,17,0 +14,SPOON,SUM,0,0,0,0,8,1,1,14.8334131241 +14,,SUM,1,0,0,1,24,5,18,29.0337231159 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,1,0,1,0,0,5,44,0 +15,CUP,SUM,1,0,0,1,32,0,17,0 +15,SPOON,SUM,0,0,0,0,12,0,12,17.5370099545 +15,,SUM,2,0,1,1,44,5,73,17.5370099545 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,0,1,7.8193941116 +16,CUP,SUM,1,0,0,1,8,4,35,0 +16,SPOON,SUM,0,0,0,0,0,0,9,12.7784059048 +16,,SUM,1,0,0,1,8,4,45,20.5978000164 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,0,0,1,7.7409598827 +17,CUP,SUM,1,0,1,0,0,4,25,0 +17,SPOON,SUM,0,0,0,0,8,3,28,19.6595950127 +17,,SUM,1,0,1,0,8,7,54,27.4005548954 +17,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,0,0,5,7.9468929768 +18,CUP,SUM,0,0,0,0,0,1,6,4.7033939362 +18,SPOON,SUM,0,0,0,0,0,1,13,12.8126540184 +18,,SUM,0,0,0,0,0,2,24,25.4629409313 +18,,,,,,,,,, +18,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,0,21,10.5336260796 +19,CUP,SUM,0,0,0,0,32,1,6,19.4816849232 +19,SPOON,SUM,0,0,0,0,8,2,15,16.6754469872 +19,,SUM,0,0,0,0,40,3,42,46.6907579899 +19,,,,,,,,,, +19,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,8,0,0,10.5921700001 +20,CUP,SUM,1,0,0,1,8,1,17,0 +20,SPOON,SUM,1,0,1,0,0,6,44,0 +20,,SUM,2,0,1,1,16,7,61,10.5921700001 +20,,,,,,,,,, +20,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,0,4,8.0128669739 +21,CUP,SUM,1,0,0,1,0,0,11,0 +21,SPOON,SUM,0,0,0,0,8,1,0,14.2866690159 +21,,SUM,1,0,0,1,8,1,15,22.2995359898 +21,,,,,,,,,, +21,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,0,1,8,9.1596682072 +22,CUP,SUM,1,0,0,1,0,0,11,0 +22,SPOON,SUM,1,0,1,0,0,7,44,0 +22,,SUM,2,0,1,1,0,8,63,9.1596682072 +22,,,,,,,,,, +22,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,0,0,7.5834739208 +23,CUP,SUM,1,0,0,1,8,0,11,0 +23,SPOON,SUM,0,0,0,0,0,1,11,13.3500390053 +23,,SUM,1,0,0,1,8,1,22,20.9335129261 +23,,,,,,,,,, +23,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,0,2,12,9.1711261272 +24,CUP,SUM,1,0,0,1,0,1,11,0 +24,SPOON,SUM,0,0,0,0,0,2,13,12.9868779182 +24,,SUM,1,0,0,1,0,5,36,22.1580040455 +24,,,,,,,,,, +24,,,,,,,,,, +25,BOWL,SUM,1,0,1,0,0,2,44,0 +25,CUP,SUM,1,0,0,1,8,1,12,0 +25,SPOON,SUM,0,0,0,0,0,0,1,10.6138269901 +25,,SUM,2,0,1,1,8,3,57,10.6138269901 +25,,,,,,,,,, +25,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,8,5,14,14.2087850571 +26,CUP,SUM,1,0,0,1,6,1,17,0 +26,SPOON,SUM,0,0,0,0,0,0,20,14.3131599426 +26,,SUM,1,0,0,1,14,6,51,28.5219449997 +26,,,,,,,,,, +26,,,,,,,,,, +27,BOWL,SUM,1,0,1,0,0,4,44,0 +27,CUP,SUM,0,0,0,0,44,5,67,31.4812760353 +27,SPOON,SUM,0,0,0,0,0,1,16,13.5532569885 +27,,SUM,1,0,1,0,44,10,127,45.0345330238 +27,,,,,,,,,, +27,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,16,0,0,14.9937460423 +28,CUP,SUM,1,0,0,1,0,0,15,0 +28,SPOON,SUM,1,0,1,0,0,3,44,0 +28,,SUM,2,0,1,1,16,3,59,14.9937460423 +28,,,,,,,,,, +28,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,0,0,1,8.0499680042 +29,CUP,SUM,1,0,0,1,0,0,11,0 +29,SPOON,SUM,0,0,0,0,0,1,12,12.8911111355 +29,,SUM,1,0,0,1,0,1,24,20.9410791397 +29,,,,,,,,,, +29,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,0,2,0,7.3274409771 +30,CUP,SUM,1,0,0,1,0,0,11,0 +30,SPOON,SUM,0,0,0,0,0,2,20,14.8593699932 +30,,SUM,1,0,0,1,0,4,31,22.1868109703 +30,,,,,,,,,, +30,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,8,5,36,17.2517809868 +31,CUP,SUM,1,0,0,1,0,0,18,0 +31,SPOON,SUM,0,0,0,0,8,0,1,14.5215251446 +31,,SUM,1,0,0,1,16,5,55,31.7733061314 +31,,,,,,,,,, +31,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,8,1,20,14.5430059433 +32,CUP,SUM,0,0,0,0,0,6,16,10.5946850777 +32,SPOON,SUM,0,0,0,0,0,0,4,11.1537828445 +32,,SUM,0,0,0,0,8,7,40,36.2914738655 +32,,,,,,,,,, +32,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,1,8,8.7054278851 +33,CUP,SUM,1,0,0,1,12,0,19,0 +33,SPOON,SUM,0,0,0,0,0,0,4,11.2080450058 +33,,SUM,1,0,0,1,12,1,31,19.9134728909 +33,,,,,,,,,, +33,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,0,1,18,10.2658150196 +34,CUP,SUM,1,0,0,1,0,3,11,0 +34,SPOON,SUM,0,0,0,0,0,3,16,13.5303990841 +34,,SUM,1,0,0,1,0,7,45,23.7962141037 +34,,,,,,,,,, +34,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,12,2,34,18.2723309994 +35,CUP,SUM,0,0,0,0,0,3,8,5.1405959129 +35,SPOON,SUM,0,0,0,0,0,5,4,11.7703728676 +35,,SUM,0,0,0,0,12,10,46,35.1832997799 +35,,,,,,,,,, +35,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,0,0,5,9.213654995 +36,CUP,SUM,0,0,0,0,8,0,15,12.4043228626 +36,SPOON,SUM,0,0,0,0,0,4,17,14.6642260551 +36,,SUM,0,0,0,0,8,4,37,36.2822039127 +36,,,,,,,,,, +36,,,,,,,,,, +37,BOWL,SUM,0,0,0,0,8,1,20,14.9099128246 +37,CUP,SUM,0,0,0,0,8,0,13,11.3325939178 +37,SPOON,SUM,0,0,0,0,0,1,4,11.6810569763 +37,,SUM,0,0,0,0,16,2,37,37.9235637188 +37,,,,,,,,,, +37,,,,,,,,,, +38,BOWL,SUM,0,0,0,0,0,0,1,7.8724060059 +38,CUP,SUM,0,0,0,0,24,0,14,20.1030390263 +38,SPOON,SUM,0,0,0,0,0,0,4,11.067081213 +38,,SUM,0,0,0,0,24,0,19,39.0425262451 +38,,,,,,,,,, +38,,,,,,,,,, +39,BOWL,SUM,0,0,0,0,0,1,0,7.417301178 +39,CUP,SUM,1,0,0,1,0,2,11,0 +39,SPOON,SUM,0,0,0,0,0,1,9,12.2423779964 +39,,SUM,1,0,0,1,0,4,20,19.6596791744 +39,,,,,,,,,, +39,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,16,1,0,14.2166690826 +40,CUP,SUM,1,0,0,1,16,0,11,0 +40,SPOON,SUM,0,0,0,0,8,0,1,13.9622790813 +40,,SUM,1,0,0,1,40,1,12,28.178948164 +40,,,,,,,,,, +40,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,0,0,6,8.3873791695 +41,CUP,SUM,0,0,0,0,0,0,6,4.7343769073 +41,SPOON,SUM,0,0,0,0,24,3,21,25.7377250195 +41,,SUM,0,0,0,0,24,3,33,38.8594810963 +41,,,,,,,,,, +41,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,0,1,16,10.0478510857 +42,CUP,SUM,1,0,0,1,0,1,11,0 +42,SPOON,SUM,0,0,0,0,16,0,4,18.7537460327 +42,,SUM,1,0,0,1,16,2,31,28.8015971184 +42,,,,,,,,,, +42,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,0,1,12,9.0865368843 +43,CUP,SUM,0,0,0,0,12,4,19,15.5288248062 +43,SPOON,SUM,0,0,0,0,0,0,3,11.1328909397 +43,,SUM,0,0,0,0,12,5,34,35.7482526302 +43,,,,,,,,,, +43,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,8,0,2,11.315237999 +44,CUP,SUM,0,0,0,0,0,1,4,4.651941061 +44,SPOON,SUM,0,0,0,0,0,1,13,12.8725280762 +44,,SUM,0,0,0,0,8,2,19,28.8397071362 +44,,,,,,,,,, +44,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,0,1,13,9.5758650303 +45,CUP,SUM,0,0,0,0,0,0,4,5.0230879784 +45,SPOON,SUM,0,0,0,0,0,2,18,14.3156619072 +45,,SUM,0,0,0,0,0,3,35,28.9146149158 +45,,,,,,,,,, +45,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,0,0,0,7.5921308994 +46,CUP,SUM,1,0,0,1,0,0,12,0 +46,SPOON,SUM,0,0,0,0,0,3,32,16.3581438065 +46,,SUM,1,0,0,1,0,3,44,23.9502747059 +46,,,,,,,,,, +46,,,,,,,,,, +47,BOWL,SUM,0,0,0,0,48,0,4,29.631978035 +47,CUP,SUM,1,0,0,1,0,0,19,0 +47,SPOON,SUM,0,0,0,0,0,3,9,12.4314539433 +47,,SUM,1,0,0,1,48,3,32,42.0634319782 +47,,,,,,,,,, +47,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,0,0,0,7.4364180565 +48,CUP,SUM,1,0,0,1,0,1,11,0 +48,SPOON,SUM,0,0,0,0,16,1,5,18.74137187 +48,,SUM,1,0,0,1,16,2,16,26.1777899265 +48,,,,,,,,,, +48,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,0,0,1,7.7798500061 +49,CUP,SUM,0,0,0,0,8,0,8,8.7965669632 +49,SPOON,SUM,0,0,0,0,0,0,0,10.2725379467 +49,,SUM,0,0,0,0,8,0,9,26.848954916 +49,,,,,,,,,, +49,,,,,,,,,, +50,BOWL,SUM,0,0,0,0,16,0,0,14.5628221035 +50,CUP,SUM,1,0,0,1,0,6,47,0 +50,SPOON,SUM,0,0,0,0,0,2,24,14.5269141197 +50,,SUM,1,0,0,1,16,8,71,29.0897362232 +50,,,,,,,,,, +50,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,0,2,12,9.6157450676 +51,CUP,SUM,1,0,0,1,0,1,11,0 +51,SPOON,SUM,0,0,0,0,0,2,33,16.8213160038 +51,,SUM,1,0,0,1,0,5,56,26.4370610714 +51,,,,,,,,,, +51,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,8,0,0,11.4475929737 +52,CUP,SUM,1,0,0,1,0,0,11,0 +52,SPOON,SUM,0,0,0,0,8,0,1,14.8031470776 +52,,SUM,1,0,0,1,16,0,12,26.2507400513 +52,,,,,,,,,, +52,,,,,,,,,, +53,BOWL,SUM,0,0,0,0,0,0,1,7.6924679279 +53,CUP,SUM,0,0,0,0,0,0,14,9.8666980267 +53,SPOON,SUM,0,0,0,0,8,0,8,16.4037489891 +53,,SUM,0,0,0,0,8,0,23,33.9629149437 +53,,,,,,,,,, +53,,,,,,,,,, +54,BOWL,SUM,1,0,1,0,0,1,44,0 +54,CUP,SUM,0,0,0,0,0,1,8,6.5134541988 +54,SPOON,SUM,0,0,0,0,8,0,7,18.5083880425 +54,,SUM,1,0,1,0,8,2,59,25.0218422413 +54,,,,,,,,,, +54,,,,,,,,,, +55,BOWL,SUM,0,0,0,0,0,1,3,8.4696469307 +55,CUP,SUM,0,0,0,0,0,0,2,4.7757558823 +55,SPOON,SUM,0,0,0,0,8,2,22,19.5132780075 +55,,SUM,0,0,0,0,8,3,27,32.7586808205 +55,,,,,,,,,, +55,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,0,3,20,10.9438450336 +56,CUP,SUM,0,0,0,0,0,1,10,7.2538809776 +56,SPOON,SUM,0,0,0,0,0,0,8,12.7890999317 +56,,SUM,0,0,0,0,0,4,38,30.986825943 +56,,,,,,,,,, +56,,,,,,,,,, +57,BOWL,SUM,1,0,1,0,0,7,44,0 +57,CUP,SUM,1,0,0,1,0,1,26,0 +57,SPOON,SUM,0,0,0,0,8,3,28,18.829777956 +57,,SUM,2,0,1,1,8,11,98,18.829777956 +57,,,,,,,,,, +57,,,,,,,,,, +58,BOWL,SUM,0,0,0,0,0,1,12,8.9016320705 +58,CUP,SUM,0,0,0,0,0,0,14,8.6314549446 +58,SPOON,SUM,0,0,0,0,0,0,2,10.6147549152 +58,,SUM,0,0,0,0,0,1,28,28.1478419304 +58,,,,,,,,,, +58,,,,,,,,,, +59,BOWL,SUM,0,0,0,0,0,0,5,7.9928691387 +59,CUP,SUM,0,0,0,0,0,1,6,4.5234599113 +59,SPOON,SUM,0,0,0,0,0,1,13,13.0547270775 +59,,SUM,0,0,0,0,0,2,24,25.5710561275 +59,,,,,,,,,, +59,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,0,0,21,10.8251240253 +60,CUP,SUM,0,0,0,0,32,1,6,20.2537519932 +60,SPOON,SUM,0,0,0,0,8,2,15,17.7351200581 +60,,SUM,0,0,0,0,40,3,42,48.8139960766 +60,,,,,,,,,, +60,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,8,0,0,11.1574389935 +61,CUP,SUM,1,0,0,1,8,1,17,0 +61,SPOON,SUM,1,0,1,0,0,6,44,0 +61,,SUM,2,0,1,1,16,7,61,11.1574389935 +61,,,,,,,,,, +61,,,,,,,,,, +62,BOWL,SUM,0,0,0,0,0,0,4,7.7585761547 +62,CUP,SUM,1,0,0,1,0,0,11,0 +62,SPOON,SUM,0,0,0,0,8,1,0,14.4823701382 +62,,SUM,1,0,0,1,8,1,15,22.2409462929 +62,,,,,,,,,, +62,,,,,,,,,, +63,BOWL,SUM,0,0,0,0,0,1,8,8.6061930656 +63,CUP,SUM,1,0,0,1,0,0,11,0 +63,SPOON,SUM,1,0,1,0,0,7,44,0 +63,,SUM,2,0,1,1,0,8,63,8.6061930656 +63,,,,,,,,,, +63,,,,,,,,,, +64,BOWL,SUM,0,0,0,0,0,0,0,7.1587569714 +64,CUP,SUM,1,0,0,1,8,0,11,0 +64,SPOON,SUM,0,0,0,0,0,1,11,13.0544710159 +64,,SUM,1,0,0,1,8,1,22,20.2132279873 +64,,,,,,,,,, +64,,,,,,,,,, +65,BOWL,SUM,0,0,0,0,0,2,12,9.0194160938 +65,CUP,SUM,1,0,0,1,0,1,11,0 +65,SPOON,SUM,0,0,0,0,0,2,13,12.6173911095 +65,,SUM,1,0,0,1,0,5,36,21.6368072033 +65,,,,,,,,,, +65,,,,,,,,,, +66,BOWL,SUM,1,0,1,0,0,2,44,0 +66,CUP,SUM,1,0,0,1,8,1,12,0 +66,SPOON,SUM,0,0,0,0,0,0,1,10.6649329662 +66,,SUM,2,0,1,1,8,3,57,10.6649329662 +66,,,,,,,,,, +66,,,,,,,,,, +67,BOWL,SUM,0,0,0,0,8,5,14,14.4327719212 +67,CUP,SUM,1,0,0,1,6,1,17,0 +67,SPOON,SUM,0,0,0,0,0,0,20,14.5419318676 +67,,SUM,1,0,0,1,14,6,51,28.9747037888 +67,,,,,,,,,, +67,,,,,,,,,, +68,BOWL,SUM,1,0,1,0,0,4,44,0 +68,CUP,SUM,0,0,0,0,44,5,67,31.5919189453 +68,SPOON,SUM,0,0,0,0,0,1,16,13.8390939236 +68,,SUM,1,0,1,0,44,10,127,45.4310128689 +68,,,,,,,,,, +68,,,,,,,,,, +69,BOWL,SUM,0,0,0,0,16,0,0,14.7661738396 +69,CUP,SUM,1,0,0,1,0,0,15,0 +69,SPOON,SUM,1,0,1,0,0,3,44,0 +69,,SUM,2,0,1,1,16,3,59,14.7661738396 +69,,,,,,,,,, +69,,,,,,,,,, +70,BOWL,SUM,0,0,0,0,0,0,1,7.9913580418 +70,CUP,SUM,1,0,0,1,0,0,11,0 +70,SPOON,SUM,0,0,0,0,0,1,12,12.9608240128 +70,,SUM,1,0,0,1,0,1,24,20.9521820545 +70,,,,,,,,,, +70,,,,,,,,,, +71,BOWL,SUM,0,0,0,0,0,2,0,7.4578588009 +71,CUP,SUM,1,0,0,1,0,0,11,0 +71,SPOON,SUM,0,0,0,0,0,2,20,15.147400856 +71,,SUM,1,0,0,1,0,4,31,22.6052596569 +71,,,,,,,,,, +71,,,,,,,,,, +72,BOWL,SUM,0,0,0,0,8,5,36,17.5651929379 +72,CUP,SUM,1,0,0,1,0,0,18,0 +72,SPOON,SUM,0,0,0,0,8,0,1,15.0042300224 +72,,SUM,1,0,0,1,16,5,55,32.5694229603 +72,,,,,,,,,, +72,,,,,,,,,, +73,BOWL,SUM,0,0,0,0,8,1,20,14.6955227852 +73,CUP,SUM,0,0,0,0,0,6,16,11.0188179016 +73,SPOON,SUM,0,0,0,0,0,0,4,10.9840619564 +73,,SUM,0,0,0,0,8,7,40,36.6984026432 +73,,,,,,,,,, +73,,,,,,,,,, +74,BOWL,SUM,0,0,0,0,0,1,8,8.9963769913 +74,CUP,SUM,1,0,0,1,12,0,19,0 +74,SPOON,SUM,0,0,0,0,0,0,4,11.5707349777 +74,,SUM,1,0,0,1,12,1,31,20.567111969 +74,,,,,,,,,, +74,,,,,,,,,, +75,BOWL,SUM,0,0,0,0,0,1,18,10.482558012 +75,CUP,SUM,1,0,0,1,0,3,11,0 +75,SPOON,SUM,0,0,0,0,0,3,16,13.9246089458 +75,,SUM,1,0,0,1,0,7,45,24.4071669579 +75,,,,,,,,,, +75,,,,,,,,,, +76,BOWL,SUM,0,0,0,0,12,2,34,18.7302060127 +76,CUP,SUM,0,0,0,0,0,3,8,6.0940549374 +76,SPOON,SUM,0,0,0,0,0,5,4,12.4039719105 +76,,SUM,0,0,0,0,12,10,46,37.2282328606 +76,,,,,,,,,, +76,,,,,,,,,, +77,BOWL,SUM,0,0,0,0,0,0,5,9.1319749355 +77,CUP,SUM,0,0,0,0,8,0,15,13.1134939194 +77,SPOON,SUM,0,0,0,0,0,4,17,14.9392821789 +77,,SUM,0,0,0,0,8,4,37,37.1847510338 +77,,,,,,,,,, +77,,,,,,,,,, +78,BOWL,SUM,0,0,0,0,8,1,20,14.8515188694 +78,CUP,SUM,0,0,0,0,8,0,13,12.3796949387 +78,SPOON,SUM,0,0,0,0,0,1,4,11.7136240005 +78,,SUM,0,0,0,0,16,2,37,38.9448378086 +78,,,,,,,,,, +78,,,,,,,,,, +79,BOWL,SUM,0,0,0,0,0,0,1,8.2394759655 +79,CUP,SUM,0,0,0,0,24,0,14,21.2455749512 +79,SPOON,SUM,0,0,0,0,0,0,4,12.1253681183 +79,,SUM,0,0,0,0,24,0,19,41.610419035 +79,,,,,,,,,, +79,,,,,,,,,, +80,BOWL,SUM,1,0,1,0,0,7,44,0 +80,CUP,SUM,1,0,0,1,0,1,26,0 +80,SPOON,SUM,0,0,0,0,8,3,28,18.4933261871 +80,,SUM,2,0,1,1,8,11,98,18.4933261871 +80,,,,,,,,,, +80,,,,,,,,,, +81,BOWL,SUM,0,0,0,0,0,1,12,8.8889400959 +81,CUP,SUM,0,0,0,0,0,0,14,8.5484919548 +81,SPOON,SUM,0,0,0,0,0,0,2,10.6539101601 +81,,SUM,0,0,0,0,0,1,28,28.0913422108 +81,,,,,,,,,, +81,,,,,,,,,, +82,BOWL,SUM,0,0,0,0,0,0,5,8.0698261261 +82,CUP,SUM,0,0,0,0,0,1,6,4.6353368759 +82,SPOON,SUM,0,0,0,0,0,1,13,12.4650518894 +82,,SUM,0,0,0,0,0,2,24,25.1702148914 +82,,,,,,,,,, +82,,,,,,,,,, +83,BOWL,SUM,0,0,0,0,0,0,21,10.7793281078 +83,CUP,SUM,0,0,0,0,32,1,6,19.9651010036 +83,SPOON,SUM,0,0,0,0,8,2,15,17.3216769695 +83,,SUM,0,0,0,0,40,3,42,48.066106081 +83,,,,,,,,,, +83,,,,,,,,,, +84,BOWL,SUM,0,0,0,0,8,0,0,10.5563240051 +84,CUP,SUM,1,0,0,1,8,1,17,0 +84,SPOON,SUM,1,0,1,0,0,6,44,0 +84,,SUM,2,0,1,1,16,7,61,10.5563240051 +84,,,,,,,,,, +84,,,,,,,,,, +85,BOWL,SUM,0,0,0,0,0,0,4,8.1229388714 +85,CUP,SUM,1,0,0,1,0,0,11,0 +85,SPOON,SUM,0,0,0,0,8,1,0,14.2496099472 +85,,SUM,1,0,0,1,8,1,15,22.3725488186 +85,,,,,,,,,, +85,,,,,,,,,, +86,BOWL,SUM,0,0,0,0,0,1,8,8.5583598614 +86,CUP,SUM,1,0,0,1,0,0,11,0 +86,SPOON,SUM,1,0,1,0,0,7,44,0 +86,,SUM,2,0,1,1,0,8,63,8.5583598614 +86,,,,,,,,,, +86,,,,,,,,,, +87,BOWL,SUM,0,0,0,0,0,0,0,6.9523279667 +87,CUP,SUM,1,0,0,1,8,0,11,0 +87,SPOON,SUM,0,0,0,0,0,1,11,12.9354829788 +87,,SUM,1,0,0,1,8,1,22,19.8878109455 +87,,,,,,,,,, +87,,,,,,,,,, +88,BOWL,SUM,0,0,0,0,0,2,12,9.1349301338 +88,CUP,SUM,1,0,0,1,0,1,11,0 +88,SPOON,SUM,0,0,0,0,0,2,13,12.8090589046 +88,,SUM,1,0,0,1,0,5,36,21.9439890385 +88,,,,,,,,,, +88,,,,,,,,,, +89,BOWL,SUM,1,0,1,0,0,2,44,0 +89,CUP,SUM,1,0,0,1,8,1,12,0 +89,SPOON,SUM,0,0,0,0,0,0,1,10.7945160866 +89,,SUM,2,0,1,1,8,3,57,10.7945160866 +89,,,,,,,,,, +89,,,,,,,,,, +90,BOWL,SUM,0,0,0,0,8,5,14,14.5862650871 +90,CUP,SUM,1,0,0,1,6,1,17,0 +90,SPOON,SUM,0,0,0,0,0,0,20,13.5365991592 +90,,SUM,1,0,0,1,14,6,51,28.1228642464 +90,,,,,,,,,, +90,,,,,,,,,, +91,BOWL,SUM,1,0,1,0,0,4,44,0 +91,CUP,SUM,0,0,0,0,44,5,67,32.2395730019 +91,SPOON,SUM,0,0,0,0,0,1,16,13.6120769978 +91,,SUM,1,0,1,0,44,10,127,45.8516499996 +91,,,,,,,,,, +91,,,,,,,,,, +92,BOWL,SUM,0,0,0,0,16,0,0,14.298358202 +92,CUP,SUM,1,0,0,1,0,0,15,0 +92,SPOON,SUM,1,0,1,0,0,3,44,0 +92,,SUM,2,0,1,1,16,3,59,14.298358202 +92,,,,,,,,,, +92,,,,,,,,,, +93,BOWL,SUM,0,0,0,0,0,0,1,7.8226950169 +93,CUP,SUM,1,0,0,1,0,0,11,0 +93,SPOON,SUM,0,0,0,0,0,1,12,13.0035178661 +93,,SUM,1,0,0,1,0,1,24,20.826212883 +93,,,,,,,,,, +93,,,,,,,,,, +94,BOWL,SUM,0,0,0,0,0,2,0,7.5843029022 +94,CUP,SUM,1,0,0,1,0,0,11,0 +94,SPOON,SUM,0,0,0,0,0,2,20,14.9923319817 +94,,SUM,1,0,0,1,0,4,31,22.5766348839 +94,,,,,,,,,, +94,,,,,,,,,, +95,BOWL,SUM,0,0,0,0,8,5,36,16.9351811409 +95,CUP,SUM,1,0,0,1,0,0,18,0 +95,SPOON,SUM,0,0,0,0,8,0,1,14.2875897884 +95,,SUM,1,0,0,1,16,5,55,31.2227709293 +95,,,,,,,,,, +95,,,,,,,,,, +96,BOWL,SUM,0,0,0,0,8,1,20,14.1860098839 +96,CUP,SUM,0,0,0,0,0,6,16,10.7020220757 +96,SPOON,SUM,0,0,0,0,0,0,4,11.0964319706 +96,,SUM,0,0,0,0,8,7,40,35.9844639301 +96,,,,,,,,,, +96,,,,,,,,,, +97,BOWL,SUM,0,0,0,0,0,1,8,8.6147010326 +97,CUP,SUM,1,0,0,1,12,0,19,0 +97,SPOON,SUM,0,0,0,0,0,0,4,10.9142560959 +97,,SUM,1,0,0,1,12,1,31,19.5289571285 +97,,,,,,,,,, +97,,,,,,,,,, +98,BOWL,SUM,0,0,0,0,0,1,18,10.3255479336 +98,CUP,SUM,1,0,0,1,0,3,11,0 +98,SPOON,SUM,0,0,0,0,0,3,16,13.8381330967 +98,,SUM,1,0,0,1,0,7,45,24.1636810303 +98,,,,,,,,,, +98,,,,,,,,,, +99,BOWL,SUM,0,0,0,0,12,2,34,18.161044836 +99,CUP,SUM,0,0,0,0,0,3,8,5.0742509365 +99,SPOON,SUM,0,0,0,0,0,5,4,11.8395738602 +99,,SUM,0,0,0,0,12,10,46,35.0748696327 +99,,,,,,,,,, +99,,,,,,,,,, +100,BOWL,SUM,0,0,0,0,0,0,5,8.7887191772 +100,CUP,SUM,0,0,0,0,8,0,15,12.7108709812 +100,SPOON,SUM,0,0,0,0,0,4,17,14.5642330647 +100,,SUM,0,0,0,0,8,4,37,36.0638232231 +100,,,,,,,,,, +100,,,,,,,,,, +101,BOWL,SUM,0,0,0,0,8,1,20,15.477241993 +101,CUP,SUM,0,0,0,0,8,0,13,11.5720140934 +101,SPOON,SUM,0,0,0,0,0,1,4,11.5963890553 +101,,SUM,0,0,0,0,16,2,37,38.6456451416 +101,,,,,,,,,, +101,,,,,,,,,, +102,BOWL,SUM,0,0,0,0,0,0,1,7.4590368271 +102,CUP,SUM,0,0,0,0,24,0,14,19.8688409328 +102,SPOON,SUM,0,0,0,0,0,0,4,11.0847461224 +102,,SUM,0,0,0,0,24,0,19,38.4126238823 +102,,,,,,,,,, +102,,,,,,,,,, +103,BOWL,SUM,1,0,1,0,0,7,44,0 +103,CUP,SUM,1,0,0,1,0,1,26,0 +103,SPOON,SUM,0,0,0,0,8,3,28,18.3595449924 +103,,SUM,2,0,1,1,8,11,98,18.3595449924 +103,,,,,,,,,, +103,,,,,,,,,, +104,BOWL,SUM,0,0,0,0,0,1,12,8.926763773 +104,CUP,SUM,0,0,0,0,0,0,14,8.9727039337 +104,SPOON,SUM,0,0,0,0,0,0,2,10.5587990284 +104,,SUM,0,0,0,0,0,1,28,28.4582667351 +104,,,,,,,,,, +104,,,,,,,,,, +105,BOWL,SUM,0,0,0,0,0,0,5,8.1286921501 +105,CUP,SUM,0,0,0,0,0,1,6,4.9638950825 +105,SPOON,SUM,0,0,0,0,0,1,13,12.9461500645 +105,,SUM,0,0,0,0,0,2,24,26.0387372971 +105,,,,,,,,,, +105,,,,,,,,,, +106,BOWL,SUM,0,0,0,0,0,0,21,10.974132061 +106,CUP,SUM,0,0,0,0,32,1,6,19.7350780964 +106,SPOON,SUM,0,0,0,0,8,2,15,17.5787100792 +106,,SUM,0,0,0,0,40,3,42,48.2879202366 +106,,,,,,,,,, +106,,,,,,,,,, +107,BOWL,SUM,0,0,0,0,8,0,0,10.2387311459 +107,CUP,SUM,1,0,0,1,8,1,17,0 +107,SPOON,SUM,1,0,1,0,0,6,44,0 +107,,SUM,2,0,1,1,16,7,61,10.2387311459 +107,,,,,,,,,, +107,,,,,,,,,, +108,BOWL,SUM,0,0,0,0,0,0,4,7.4951879978 +108,CUP,SUM,1,0,0,1,0,0,11,0 +108,SPOON,SUM,0,0,0,0,8,1,0,14.4823901653 +108,,SUM,1,0,0,1,8,1,15,21.9775781631 +108,,,,,,,,,, +108,,,,,,,,,, +109,BOWL,SUM,0,0,0,0,0,1,8,8.4347259998 +109,CUP,SUM,1,0,0,1,0,0,11,0 +109,SPOON,SUM,1,0,1,0,0,7,44,0 +109,,SUM,2,0,1,1,0,8,63,8.4347259998 +109,,,,,,,,,, +109,,,,,,,,,, +110,BOWL,SUM,0,0,0,0,0,0,0,7.2712070942 +110,CUP,SUM,1,0,0,1,8,0,11,0 +110,SPOON,SUM,0,0,0,0,0,1,11,13.2354009151 +110,,SUM,1,0,0,1,8,1,22,20.5066080093 +110,,,,,,,,,, +110,,,,,,,,,, +111,BOWL,SUM,0,0,0,0,0,2,12,9.0649001598 +111,CUP,SUM,1,0,0,1,0,1,11,0 +111,SPOON,SUM,0,0,0,0,0,2,13,12.5656249523 +111,,SUM,1,0,0,1,0,5,36,21.6305251122 +111,,,,,,,,,, +111,,,,,,,,,, +112,BOWL,SUM,1,0,1,0,0,2,44,0 +112,CUP,SUM,1,0,0,1,8,1,12,0 +112,SPOON,SUM,0,0,0,0,0,0,1,10.7807719707 +112,,SUM,2,0,1,1,8,3,57,10.7807719707 +112,,,,,,,,,, +112,,,,,,,,,, +113,BOWL,SUM,0,0,0,0,8,5,14,14.4060008526 +113,CUP,SUM,1,0,0,1,6,1,17,0 +113,SPOON,SUM,0,0,0,0,0,0,20,14.0462949276 +113,,SUM,1,0,0,1,14,6,51,28.4522957802 +113,,,,,,,,,, +113,,,,,,,,,, +114,BOWL,SUM,1,0,1,0,0,4,44,0 +114,CUP,SUM,0,0,0,0,44,5,67,31.2239041328 +114,SPOON,SUM,0,0,0,0,0,1,16,14.1713171005 +114,,SUM,1,0,1,0,44,10,127,45.3952212334 +114,,,,,,,,,, +114,,,,,,,,,, +115,BOWL,SUM,0,0,0,0,16,0,0,14.7992508411 +115,CUP,SUM,1,0,0,1,0,0,15,0 +115,SPOON,SUM,1,0,1,0,0,3,44,0 +115,,SUM,2,0,1,1,16,3,59,14.7992508411 +115,,,,,,,,,, +115,,,,,,,,,, +116,BOWL,SUM,0,0,0,0,0,0,1,7.1466989517 +116,CUP,SUM,1,0,0,1,0,0,11,0 +116,SPOON,SUM,0,0,0,0,0,1,12,12.6712698936 +116,,SUM,1,0,0,1,0,1,24,19.8179688454 +116,,,,,,,,,, +116,,,,,,,,,, +117,BOWL,SUM,0,0,0,0,0,2,0,7.7306358814 +117,CUP,SUM,1,0,0,1,0,0,11,0 +117,SPOON,SUM,0,0,0,0,0,2,20,14.7489509583 +117,,SUM,1,0,0,1,0,4,31,22.4795868397 +117,,,,,,,,,, +117,,,,,,,,,, +118,BOWL,SUM,0,0,0,0,8,5,36,16.975028038 +118,CUP,SUM,1,0,0,1,0,0,18,0 +118,SPOON,SUM,0,0,0,0,8,0,1,14.734418869 +118,,SUM,1,0,0,1,16,5,55,31.709446907 +118,,,,,,,,,, +118,,,,,,,,,, +119,BOWL,SUM,0,0,0,0,8,1,20,14.1540560722 +119,CUP,SUM,0,0,0,0,0,6,16,10.4268729687 +119,SPOON,SUM,0,0,0,0,0,0,4,11.0964810848 +119,,SUM,0,0,0,0,8,7,40,35.6774101257 +119,,,,,,,,,, +119,,,,,,,,,, +120,BOWL,SUM,0,0,0,0,0,1,8,8.6448290348 +120,CUP,SUM,1,0,0,1,12,0,19,0 +120,SPOON,SUM,0,0,0,0,0,0,4,11.055560112 +120,,SUM,1,0,0,1,12,1,31,19.7003891468 +120,,,,,,,,,, +120,,,,,,,,,, +121,BOWL,SUM,0,0,0,0,0,1,18,10.1801950932 +121,CUP,SUM,1,0,0,1,0,3,11,0 +121,SPOON,SUM,0,0,0,0,0,3,16,13.3143351078 +121,,SUM,1,0,0,1,0,7,45,23.494530201 +121,,,,,,,,,, +121,,,,,,,,,, +122,BOWL,SUM,0,0,0,0,12,2,34,17.7745249271 +122,CUP,SUM,0,0,0,0,0,3,8,5.4758520126 +122,SPOON,SUM,0,0,0,0,0,5,4,12.2872438431 +122,,SUM,0,0,0,0,12,10,46,35.5376207829 +122,,,,,,,,,, +122,,,,,,,,,, +123,BOWL,SUM,0,0,0,0,0,0,5,8.6141700745 +123,CUP,SUM,0,0,0,0,8,0,15,12.3336091042 +123,SPOON,SUM,0,0,0,0,0,4,17,14.4455640316 +123,,SUM,0,0,0,0,8,4,37,35.3933432102 +123,,,,,,,,,, +123,,,,,,,,,, +124,BOWL,SUM,0,0,0,0,8,1,20,14.8594589233 +124,CUP,SUM,0,0,0,0,8,0,13,11.2695820332 +124,SPOON,SUM,0,0,0,0,0,1,4,11.7643070221 +124,,SUM,0,0,0,0,16,2,37,37.8933479786 +124,,,,,,,,,, +124,,,,,,,,,, +125,BOWL,SUM,0,0,0,0,0,0,1,8.0197639465 +125,CUP,SUM,0,0,0,0,24,0,14,19.7506270409 +125,SPOON,SUM,0,0,0,0,0,0,4,11.5545239449 +125,,SUM,0,0,0,0,24,0,19,39.3249149323 +125,,,,,,,,,, +125,,,,,,,,,, +126,BOWL,SUM,1,0,1,0,0,2,44,0 +126,CUP,SUM,0,0,0,0,0,1,4,5.1721148491 +126,SPOON,SUM,0,0,0,0,8,0,0,13.0090479851 +126,,SUM,1,0,1,0,8,3,48,18.1811628342 +126,,,,,,,,,, +126,,,,,,,,,, +127,BOWL,SUM,0,0,0,0,16,0,8,15.2236778736 +127,CUP,SUM,0,0,0,0,0,0,2,4.36302495 +127,SPOON,SUM,1,0,1,0,0,5,44,0 +127,,SUM,1,0,1,0,16,5,54,19.5867028236 +127,,,,,,,,,, +127,,,,,,,,,, +128,BOWL,SUM,0,0,0,0,12,0,4,12.8249340057 +128,CUP,SUM,1,0,0,1,0,1,11,0 +128,SPOON,SUM,0,0,0,0,8,2,0,13.8053541183 +128,,SUM,1,0,0,1,20,3,15,26.6302881241 +128,,,,,,,,,, +128,,,,,,,,,, +129,BOWL,SUM,0,0,0,0,0,4,20,10.4737799168 +129,CUP,SUM,0,0,0,0,0,0,7,5.3390471935 +129,SPOON,SUM,0,0,0,0,0,0,4,11.3812401295 +129,,SUM,0,0,0,0,0,4,31,27.1940672398 +129,,,,,,,,,, +129,,,,,,,,,, +130,BOWL,SUM,0,0,0,0,0,0,0,6.9132730961 +130,CUP,SUM,0,0,0,0,0,0,5,5.2021479607 +130,SPOON,SUM,0,0,0,0,24,2,16,24.9408280849 +130,,SUM,0,0,0,0,24,2,21,37.0562491417 +130,,,,,,,,,, +130,,,,,,,,,, +131,BOWL,SUM,0,0,0,0,0,0,0,7.442841053 +131,CUP,SUM,1,0,0,1,0,0,20,0 +131,SPOON,SUM,0,0,0,0,0,1,7,12.2038750648 +131,,SUM,1,0,0,1,0,1,27,19.6467161179 +131,,,,,,,,,, +131,,,,,,,,,, +132,BOWL,SUM,0,0,0,0,8,0,0,10.5709779263 +132,CUP,SUM,1,0,0,1,0,0,11,0 +132,SPOON,SUM,0,0,0,0,0,0,0,9.6507899761 +132,,SUM,1,0,0,1,8,0,11,20.2217679024 +132,,,,,,,,,, +132,,,,,,,,,, +133,BOWL,SUM,0,0,0,0,0,0,4,7.9626989365 +133,CUP,SUM,0,0,0,0,0,2,12,8.0945000648 +133,SPOON,SUM,0,0,0,0,0,1,9,12.1706328392 +133,,SUM,0,0,0,0,0,3,25,28.2278318405 +133,,,,,,,,,, +133,,,,,,,,,, +134,BOWL,SUM,0,0,0,0,0,3,41,14.8263459206 +134,CUP,SUM,0,0,0,0,0,6,124,16.8453440666 +134,SPOON,SUM,0,0,0,0,0,0,3,11.400769949 +134,,SUM,0,0,0,0,0,9,168,43.0724599361 +134,,,,,,,,,, +134,,,,,,,,,, +135,BOWL,SUM,0,0,0,0,0,0,16,9.7629320621 +135,CUP,SUM,1,0,0,1,0,1,11,0 +135,SPOON,SUM,0,0,0,0,0,2,13,13.1192479134 +135,,SUM,1,0,0,1,0,3,40,22.8821799755 +135,,,,,,,,,, +135,,,,,,,,,, +136,BOWL,SUM,1,0,1,0,0,2,44,0 +136,CUP,SUM,1,0,0,1,8,1,11,0 +136,SPOON,SUM,0,0,0,0,0,0,6,11.6380388737 +136,,SUM,2,0,1,1,8,3,61,11.6380388737 +136,,,,,,,,,, +136,,,,,,,,,, +137,BOWL,SUM,1,0,1,0,0,5,44,0 +137,CUP,SUM,1,0,0,1,0,2,26,0 +137,SPOON,SUM,0,0,0,0,0,1,29,15.474766016 +137,,SUM,2,0,1,1,0,8,99,15.474766016 +137,,,,,,,,,, +137,,,,,,,,,, +138,BOWL,SUM,0,0,0,0,0,1,24,11.4029591084 +138,CUP,SUM,0,0,0,0,0,0,9,6.1637639999 +138,SPOON,SUM,0,0,0,0,0,0,5,11.5713129044 +138,,SUM,0,0,0,0,0,1,38,29.1380360126 +138,,,,,,,,,, +138,,,,,,,,,, +139,BOWL,SUM,0,0,0,0,0,1,8,8.4199180603 +139,CUP,SUM,1,0,0,1,0,0,11,0 +139,SPOON,SUM,0,0,0,0,0,1,12,12.3391251564 +139,,SUM,1,0,0,1,0,2,31,20.7590432167 +139,,,,,,,,,, +139,,,,,,,,,, +140,BOWL,SUM,0,0,0,0,0,0,0,7.1711521149 +140,CUP,SUM,1,0,0,1,8,0,21,0 +140,SPOON,SUM,0,0,0,0,0,0,4,10.7804808617 +140,,SUM,1,0,0,1,8,0,25,17.9516329765 +140,,,,,,,,,, +140,,,,,,,,,, +141,BOWL,SUM,0,0,0,0,8,0,8,11.9394841194 +141,CUP,SUM,0,0,0,0,0,0,8,6.0983099937 +141,SPOON,SUM,1,0,1,0,0,8,44,0 +141,,SUM,1,0,1,0,8,8,60,18.0377941132 +141,,,,,,,,,, +141,,,,,,,,,, +142,BOWL,SUM,0,0,0,0,0,0,0,7.3077399731 +142,CUP,SUM,0,0,0,0,0,0,28,9.5341868401 +142,SPOON,SUM,0,0,0,0,0,2,12,13.3187139034 +142,,SUM,0,0,0,0,0,2,40,30.1606407166 +142,,,,,,,,,, +142,,,,,,,,,, +143,BOWL,SUM,0,0,0,0,8,4,41,18.2916350365 +143,CUP,SUM,1,0,0,1,0,0,11,0 +143,SPOON,SUM,0,0,0,0,16,3,33,24.3468780518 +143,,SUM,1,0,0,1,24,7,85,42.6385130882 +143,,,,,,,,,, +143,,,,,,,,,, +144,BOWL,SUM,0,0,0,0,16,2,28,19.8660678864 +144,CUP,SUM,1,0,0,1,0,0,11,0 +144,SPOON,SUM,0,0,0,0,0,3,36,16.9746391773 +144,,SUM,1,0,0,1,16,5,75,36.8407070637 +144,,,,,,,,,, +144,,,,,,,,,, +145,BOWL,SUM,1,0,1,0,8,4,44,0 +145,CUP,SUM,0,0,0,0,0,0,4,5.1251649857 +145,SPOON,SUM,0,0,0,0,8,0,11,16.9526100159 +145,,SUM,1,0,1,0,16,4,59,22.0777750015 +145,,,,,,,,,, +145,,,,,,,,,, +146,BOWL,SUM,0,0,0,0,0,1,7,8.3415880203 +146,CUP,SUM,0,0,0,0,0,4,2,4.9271879196 +146,SPOON,SUM,0,0,0,0,8,5,40,20.7019460201 +146,,SUM,0,0,0,0,8,10,49,33.9707219601 +146,,,,,,,,,, +146,,,,,,,,,, +147,BOWL,SUM,0,0,0,0,8,0,0,10.2560710907 +147,CUP,SUM,1,0,0,1,0,1,11,0 +147,SPOON,SUM,0,0,0,0,0,1,8,11.237719059 +147,,SUM,1,0,0,1,8,2,19,21.4937901497 +147,,,,,,,,,, +147,,,,,,,,,, +148,BOWL,SUM,1,0,1,0,16,3,44,0 +148,CUP,SUM,0,0,0,0,0,0,2,4.7666490078 +148,SPOON,SUM,1,0,1,0,16,6,44,0 +148,,SUM,2,0,2,0,32,9,90,4.7666490078 +148,,,,,,,,,, +148,,,,,,,,,, +149,BOWL,SUM,0,0,0,0,0,0,20,10.5354180336 +149,CUP,SUM,1,0,0,1,16,1,11,0 +149,SPOON,SUM,0,0,0,0,0,0,0,9.8192908764 +149,,SUM,1,0,0,1,16,1,31,20.35470891 +149,,,,,,,,,, +149,,,,,,,,,, +150,BOWL,SUM,1,0,1,0,8,5,44,0 +150,CUP,SUM,0,0,0,0,0,0,2,5.0044779778 +150,SPOON,SUM,0,0,0,0,0,0,8,11.6593260765 +150,,SUM,1,0,1,0,8,5,54,16.6638040543 +150,,,,,,,,,, +150,,,,,,,,,, +151,BOWL,SUM,1,0,1,0,8,3,44,0 +151,CUP,SUM,1,0,0,1,0,1,11,0 +151,SPOON,SUM,0,0,0,0,0,1,8,11.6332850456 +151,,SUM,2,0,1,1,8,5,63,11.6332850456 +151,,,,,,,,,, +151,,,,,,,,,, +152,BOWL,SUM,1,0,1,0,12,3,44,0 +152,CUP,SUM,0,0,0,0,0,0,14,7.9376020432 +152,SPOON,SUM,0,0,0,0,0,0,14,12.8907330036 +152,,SUM,1,0,1,0,12,3,72,20.8283350468 +152,,,,,,,,,, +152,,,,,,,,,, +153,BOWL,SUM,0,0,0,0,0,0,4,7.6115350723 +153,CUP,SUM,1,0,0,1,0,1,21,0 +153,SPOON,SUM,0,0,0,0,12,1,13,17.1059019566 +153,,SUM,1,0,0,1,12,2,38,24.7174370289 +153,,,,,,,,,, +153,,,,,,,,,, +154,BOWL,SUM,0,0,0,0,0,2,8,8.3896691799 +154,CUP,SUM,1,0,0,1,0,0,12,0 +154,SPOON,SUM,0,0,0,0,0,0,9,12.2362229824 +154,,SUM,1,0,0,1,0,2,29,20.6258921623 +154,,,,,,,,,, +154,,,,,,,,,, +155,BOWL,SUM,0,0,0,0,12,1,4,12.4635798931 +155,CUP,SUM,0,0,0,0,0,1,3,5.3243360519 +155,SPOON,SUM,0,0,0,0,0,1,7,12.2293059826 +155,,SUM,0,0,0,0,12,3,14,30.0172219276 +155,,,,,,,,,, +155,,,,,,,,,, +156,BOWL,SUM,1,0,1,0,0,5,44,0 +156,CUP,SUM,0,0,0,0,0,4,3,5.9744930267 +156,SPOON,SUM,0,0,0,0,0,0,6,11.7150859833 +156,,SUM,1,0,1,0,0,9,53,17.68957901 +156,,,,,,,,,, +156,,,,,,,,,, +157,BOWL,SUM,0,0,0,0,0,0,0,6.9688739777 +157,CUP,SUM,1,0,0,1,6,1,11,0 +157,SPOON,SUM,0,0,0,0,0,1,3,11.3017289639 +157,,SUM,1,0,0,1,6,2,14,18.2706029415 +157,,,,,,,,,, +157,,,,,,,,,, +158,BOWL,SUM,0,0,0,0,0,0,0,7.3001179695 +158,CUP,SUM,1,0,0,1,56,0,11,0 +158,SPOON,SUM,0,0,0,0,0,2,24,14.1748700142 +158,,SUM,1,0,0,1,56,2,35,21.4749879837 +158,,,,,,,,,, +158,,,,,,,,,, +159,BOWL,SUM,1,0,1,0,0,3,44,0 +159,CUP,SUM,1,0,0,1,0,4,32,0 +159,SPOON,SUM,0,0,0,0,0,0,0,10.8226408958 +159,,SUM,2,0,1,1,0,7,76,10.8226408958 +159,,,,,,,,,, +159,,,,,,,,,, +160,BOWL,SUM,0,0,0,0,8,1,2,11.5318090916 +160,CUP,SUM,1,0,0,1,8,1,11,0 +160,SPOON,SUM,0,0,0,0,8,0,2,14.8526570797 +160,,SUM,1,0,0,1,24,2,15,26.3844661713 +160,,,,,,,,,, +160,,,,,,,,,, +81,BOWL,SUM,0,0,0,0,0,0,4,8.0874228477 +161,CUP,SUM,1,0,1,0,0,1,37,0 +161,SPOON,SUM,0,0,0,0,12,0,2,16.7071819305 +161,,SUM,1,0,1,0,12,1,43,24.7946047783 +161,,,,,,,,,, +161,,,,,,,,,, +162,BOWL,SUM,0,0,0,0,0,1,12,10.2416059971 +162,CUP,SUM,0,0,0,0,0,1,2,5.6675229073 +162,SPOON,SUM,0,0,0,0,0,0,4,11.6093459129 +162,,SUM,0,0,0,0,0,2,18,27.5184748173 +162,,,,,,,,,, +162,,,,,,,,,, +163,BOWL,SUM,0,0,0,0,0,1,8,9.4575190544 +163,CUP,SUM,0,0,0,0,0,0,2,4.9495830536 +163,SPOON,SUM,0,0,0,0,0,0,0,11.0135099888 +163,,SUM,0,0,0,0,0,1,10,25.4206120968 +163,,,,,,,,,, +163,,,,,,,,,, +164,BOWL,SUM,1,0,1,0,0,3,44,0 +164,CUP,SUM,0,0,0,0,0,0,2,5.3534588814 +164,SPOON,SUM,0,0,0,0,12,1,13,19.4031159878 +164,,SUM,1,0,1,0,12,4,59,24.7565748692 +164,,,,,,,,,, +164,,,,,,,,,, +165,BOWL,SUM,0,0,0,0,0,0,18,10.1564729214 +165,CUP,SUM,1,0,0,1,16,0,28,0 +165,SPOON,SUM,0,0,0,0,0,3,22,14.9861021042 +165,,SUM,1,0,0,1,16,3,68,25.1425750256 +165,,,,,,,,,, +165,,,,,,,,,, +166,BOWL,SUM,1,0,1,0,0,7,44,0 +166,CUP,SUM,1,0,0,1,0,1,26,0 +166,SPOON,SUM,0,0,0,0,8,3,28,17.9515199661 +166,,SUM,2,0,1,1,8,11,98,17.9515199661 +166,,,,,,,,,, +166,,,,,,,,,, +167,BOWL,SUM,0,0,0,0,0,1,12,8.9237859249 +167,CUP,SUM,0,0,0,0,0,2,14,8.6281139851 +167,SPOON,SUM,0,0,0,0,0,0,2,10.656594038 +167,,SUM,0,0,0,0,0,3,28,28.208493948 +167,,,,,,,,,, +167,,,,,,,,,, +168,BOWL,SUM,0,0,0,0,0,1,5,7.8352839947 +168,CUP,SUM,0,0,0,0,0,1,6,4.5605678558 +168,SPOON,SUM,0,0,0,0,0,1,13,12.0963790417 +168,,SUM,0,0,0,0,0,3,24,24.4922308922 +168,,,,,,,,,, +168,,,,,,,,,, +169,BOWL,SUM,0,0,0,0,0,2,21,10.4310359955 +169,CUP,SUM,0,0,0,0,24,0,2,14.3583450317 +169,SPOON,SUM,0,0,0,0,0,2,27,16.2586390972 +169,,SUM,0,0,0,0,24,4,50,41.0480201244 +169,,,,,,,,,, +169,,,,,,,,,, +170,BOWL,SUM,0,0,0,0,0,0,0,6.6946909428 +170,CUP,SUM,0,0,0,0,0,0,5,5.1819331646 +170,SPOON,SUM,0,0,0,0,8,3,16,16.5373730659 +170,,SUM,0,0,0,0,8,3,21,28.4139971733 +170,,,,,,,,,, +170,,,,,,,,,, +171,BOWL,SUM,0,0,0,0,8,0,3,10.5527451038 +171,CUP,SUM,0,0,0,0,0,1,11,6.3168690205 +171,SPOON,SUM,0,0,0,0,0,1,13,13.1939871311 +171,,SUM,0,0,0,0,8,2,27,30.0636012554 +171,,,,,,,,,, +171,,,,,,,,,, +172,BOWL,SUM,0,0,0,0,8,1,0,10.0606548786 +172,CUP,SUM,0,0,0,0,20,3,21,17.4721519947 +172,SPOON,SUM,1,0,1,0,0,11,44,0 +172,,SUM,1,0,1,0,28,15,65,27.5328068733 +172,,,,,,,,,, +172,,,,,,,,,, +173,BOWL,SUM,0,0,0,0,0,6,32,12.4122409821 +173,CUP,SUM,1,0,0,1,16,1,11,0 +173,SPOON,SUM,0,0,0,0,0,1,10,11.7601418495 +173,,SUM,1,0,0,1,16,8,53,24.1723828316 +173,,,,,,,,,, +173,,,,,,,,,, +174,BOWL,SUM,1,0,1,0,8,4,44,0 +174,CUP,SUM,1,0,0,1,0,0,11,0 +174,SPOON,SUM,0,0,0,0,0,0,0,10.3760700226 +174,,SUM,2,0,1,1,8,4,55,10.3760700226 +174,,,,,,,,,, +174,,,,,,,,,, +175,BOWL,SUM,1,0,1,0,0,7,44,0 +175,CUP,SUM,0,0,0,0,0,1,2,4.8846178055 +175,SPOON,SUM,0,0,0,0,0,2,13,14.1282269955 +175,,SUM,1,0,1,0,0,10,59,19.0128448009 +175,,,,,,,,,, +175,,,,,,,,,, +176,BOWL,SUM,0,0,0,0,24,0,4,18.3240609169 +176,CUP,SUM,0,0,0,0,0,2,2,5.001157999 +176,SPOON,SUM,0,0,0,0,0,2,0,10.2332849503 +176,,SUM,0,0,0,0,24,4,6,33.5585038662 +176,,,,,,,,,, +176,,,,,,,,,, +177,BOWL,SUM,0,0,0,0,0,2,12,9.2105891705 +177,CUP,SUM,0,0,0,0,0,2,2,5.1137299538 +177,SPOON,SUM,0,0,0,0,24,4,0,21.7804300785 +177,,SUM,0,0,0,0,24,8,14,36.1047492027 +177,,,,,,,,,, +177,,,,,,,,,, +178,BOWL,SUM,1,0,1,0,8,6,44,0 +178,CUP,SUM,1,0,1,0,12,2,11,0 +178,SPOON,SUM,0,0,0,0,0,4,0,10.5202789307 +178,,SUM,2,0,2,0,20,12,55,10.5202789307 +178,,,,,,,,,, +178,,,,,,,,,, +179,BOWL,SUM,0,0,0,0,0,0,0,6.770236969 +179,CUP,SUM,1,0,0,1,8,0,17,0 +179,SPOON,SUM,0,0,0,0,0,1,4,10.974011898 +179,,SUM,1,0,0,1,8,1,21,17.744248867 +179,,,,,,,,,, +179,,,,,,,,,, +180,BOWL,SUM,1,0,1,0,8,4,44,0 +180,CUP,SUM,0,0,0,0,0,5,37,11.6026470661 +180,SPOON,SUM,1,0,1,0,8,10,44,0 +180,,SUM,2,0,2,0,16,19,125,11.6026470661 +180,,,,,,,,,, +180,,,,,,,,,, +181,BOWL,SUM,0,0,0,0,0,0,0,7.0572290421 +181,CUP,SUM,0,0,0,0,24,3,2,15.5493228436 +181,SPOON,SUM,0,0,0,0,0,0,0,10.1831591129 +181,,SUM,0,0,0,0,24,3,2,32.7897109985 +181,,,,,,,,,, +181,,,,,,,,,, +182,BOWL,SUM,1,0,1,0,0,3,44,0 +182,CUP,SUM,0,0,0,0,8,1,2,8.7766821384 +182,SPOON,SUM,0,0,0,0,0,2,0,10.6251888275 +182,,SUM,1,0,1,0,8,6,46,19.401870966 +182,,,,,,,,,, +182,,,,,,,,,, +183,BOWL,SUM,0,0,0,0,0,0,4,8.3425798416 +183,CUP,SUM,1,0,0,1,8,2,11,0 +183,SPOON,SUM,0,0,0,0,16,0,0,17.0707039833 +183,,SUM,1,0,0,1,24,2,15,25.4132838249 +183,,,,,,,,,, +183,,,,,,,,,, +184,BOWL,SUM,0,0,0,0,0,0,1,8.2794508934 +184,CUP,SUM,1,0,0,1,0,1,11,0 +184,SPOON,SUM,0,0,0,0,40,3,12,31.8623631001 +184,,SUM,1,0,0,1,40,4,24,40.1418139935 +184,,,,,,,,,, +184,,,,,,,,,, +185,BOWL,SUM,0,0,0,0,8,3,1,12.1664590836 +185,CUP,SUM,1,0,0,1,0,2,11,0 +185,SPOON,SUM,0,0,0,0,0,0,1,10.4260070324 +185,,SUM,1,0,0,1,8,5,13,22.592466116 +185,,,,,,,,,, +185,,,,,,,,,, +186,BOWL,SUM,1,0,1,0,0,4,44,0 +186,CUP,SUM,1,0,0,1,0,1,11,0 +186,SPOON,SUM,0,0,0,0,0,2,36,16.7238230705 +186,,SUM,2,0,1,1,0,7,91,16.7238230705 +186,,,,,,,,,, +186,,,,,,,,,, +187,BOWL,SUM,0,0,0,0,0,3,16,10.2425920963 +187,CUP,SUM,1,0,0,1,0,0,17,0 +187,SPOON,SUM,0,0,0,0,0,3,34,16.6521868706 +187,,SUM,1,0,0,1,0,6,67,26.8947789669 +187,,,,,,,,,, +187,,,,,,,,,, +188,BOWL,SUM,1,0,1,0,0,4,44,0 +188,CUP,SUM,1,0,0,1,8,3,11,0 +188,SPOON,SUM,0,0,0,0,0,3,24,14.6588668823 +188,,SUM,2,0,1,1,8,10,79,14.6588668823 +188,,,,,,,,,, +188,,,,,,,,,, +189,BOWL,SUM,0,0,0,0,0,0,0,7.3959648609 +189,CUP,SUM,1,0,0,1,0,0,11,0 +189,SPOON,SUM,0,0,0,0,0,2,9,13.0320661068 +189,,SUM,1,0,0,1,0,2,20,20.4280309677 +189,,,,,,,,,, +189,,,,,,,,,, +190,BOWL,SUM,0,0,0,0,0,1,0,7.3283028603 +190,CUP,SUM,0,0,0,0,0,0,2,4.8656790257 +190,SPOON,SUM,0,0,0,0,0,5,36,16.3442611694 +190,,SUM,0,0,0,0,0,6,38,28.5382430553 +190,,,,,,,,,, +190,,,,,,,,,, +191,BOWL,SUM,0,0,0,0,0,0,0,7.2763221264 +191,CUP,SUM,1,0,0,1,0,0,11,0 +191,SPOON,SUM,1,0,1,0,0,5,44,0 +191,,SUM,2,0,1,1,0,5,55,7.2763221264 +191,,,,,,,,,, +191,,,,,,,,,, +192,BOWL,SUM,0,0,0,0,0,4,1,7.3278541565 +192,CUP,SUM,0,0,0,0,0,1,17,9.0630099773 +192,SPOON,SUM,0,0,0,0,8,6,21,17.8689110279 +192,,SUM,0,0,0,0,8,11,39,34.2597751617 +192,,,,,,,,,, +192,,,,,,,,,, +193,BOWL,SUM,1,0,1,0,24,7,44,0 +193,CUP,SUM,0,0,0,0,0,1,2,4.870541811 +193,SPOON,SUM,0,0,0,0,0,0,0,10.3970658779 +193,,SUM,1,0,1,0,24,8,46,15.2676076889 +193,,,,,,,,,, +193,,,,,,,,,, +194,BOWL,SUM,1,0,1,0,0,4,44,0 +194,CUP,SUM,0,0,0,0,0,3,11,7.6614909172 +194,SPOON,SUM,0,0,0,0,0,0,1,10.7214860916 +194,,SUM,1,0,1,0,0,7,56,18.3829770088 +194,,,,,,,,,, +194,,,,,,,,,, +195,BOWL,SUM,0,0,0,0,0,0,0,7.0351099968 +195,CUP,SUM,1,0,0,1,40,6,46,0 +195,SPOON,SUM,0,0,0,0,0,1,4,11.2242088318 +195,,SUM,1,0,0,1,40,7,50,18.2593188286 +195,,,,,,,,,, +195,,,,,,,,,, +196,BOWL,SUM,0,0,0,0,0,1,8,8.4781200886 +196,CUP,SUM,0,0,0,0,8,1,2,8.3474159241 +196,SPOON,SUM,0,0,0,0,0,1,3,11.5721290112 +196,,SUM,0,0,0,0,8,3,13,28.3976650238 +196,,,,,,,,,, +196,,,,,,,,,, +197,BOWL,SUM,0,0,0,0,0,1,4,7.9306440353 +197,CUP,SUM,1,0,0,1,8,0,11,0 +197,SPOON,SUM,0,0,0,0,0,3,40,17.6018869877 +197,,SUM,1,0,0,1,8,4,55,25.532531023 +197,,,,,,,,,, +197,,,,,,,,,, +198,BOWL,SUM,0,0,0,0,8,5,19,15.9665050507 +198,CUP,SUM,0,0,0,0,0,1,11,7.9614930153 +198,SPOON,SUM,0,0,0,0,0,1,0,10.6570780277 +198,,SUM,0,0,0,0,8,7,30,34.5850760937 +198,,,,,,,,,, +198,,,,,,,,,, +199,BOWL,SUM,1,0,1,0,0,3,44,0 +199,CUP,SUM,0,0,0,0,8,0,2,8.7669808865 +199,SPOON,SUM,0,0,0,0,0,6,27,16.0432140827 +199,,SUM,1,0,1,0,8,9,73,24.8101949692 +199,,,,,,,,,, +199,,,,,,,,,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/kvr_boxy_3var_best.csv b/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/kvr_boxy_3var_best.csv new file mode 100644 index 0000000000..855226b495 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/kvr_boxy_3var_best.csv @@ -0,0 +1,303 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,2,45,14,35.26452302932739 +0,CUP,SUM,1,0,0,1,0,469,58,0.0 +0,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +0,,SUM,2,0,1,1,2,2095,72,35.26452302932739 +0,, +1,, +1,BOWL,SUM,0,0,0,0,6,28,6,25.85601305961609 +1,CUP,SUM,0,0,0,0,0,13,2,12.409448146820068 +1,SPOON,SUM,0,0,0,0,0,1,14,29.9533531665802 +1,,SUM,0,0,0,0,6,42,22,68.21881437301636 +1,, +2,, +2,BOWL,SUM,1,0,1,0,0,1404,18,0.0 +2,CUP,SUM,0,0,0,0,0,14,10,18.43154788017273 +2,SPOON,SUM,1,0,1,0,0,1564,8,0.0 +2,,SUM,2,0,2,0,0,2982,36,18.43154788017273 +2,, +3,, +3,BOWL,SUM,0,0,0,0,0,35,0,15.790754079818726 +3,CUP,SUM,0,0,0,0,0,10,0,11.57533597946167 +3,SPOON,SUM,0,0,0,0,0,36,2,18.805893898010254 +3,,SUM,0,0,0,0,0,81,2,46.17198395729065 +3,, +4,, +4,BOWL,SUM,0,0,0,0,6,45,16,38.230873107910156 +4,CUP,SUM,0,0,0,0,0,92,0,16.134905099868774 +4,SPOON,SUM,0,0,0,0,0,216,0,29.674817085266113 +4,,SUM,0,0,0,0,6,353,16,84.04059529304504 +4,, +5,, +5,BOWL,SUM,0,0,0,0,0,387,2,41.53441596031189 +5,CUP,SUM,0,0,0,0,0,31,2,13.482014179229736 +5,SPOON,SUM,0,0,0,0,0,26,4,17.79829502105713 +5,,SUM,0,0,0,0,0,444,8,72.81472516059875 +5,, +6,, +6,BOWL,SUM,0,0,0,0,0,38,13,25.44232702255249 +6,CUP,SUM,0,0,0,0,2,53,7,18.7336528301239 +6,SPOON,SUM,1,0,1,0,2,1581,5,0.0 +6,,SUM,1,0,1,0,4,1672,25,44.17597985267639 +6,, +7,, +7,BOWL,SUM,0,0,0,0,0,23,8,20.340171813964844 +7,CUP,SUM,1,0,1,0,2,524,107,0.0 +7,SPOON,SUM,0,0,0,0,0,46,9,36.318702936172485 +7,,SUM,1,0,1,0,2,593,124,56.65887475013733 +7,, +8,, +8,BOWL,SUM,0,0,0,0,0,15,5,16.030744791030884 +8,CUP,SUM,0,0,0,0,6,73,0,16.65789484977722 +8,SPOON,SUM,0,0,0,0,0,161,1,29.691219091415405 +8,,SUM,0,0,0,0,6,249,6,62.37985873222351 +8,, +9,, +9,BOWL,SUM,0,0,0,0,0,167,8,33.539669036865234 +9,CUP,SUM,0,0,0,0,0,9,4,12.90775179862976 +9,SPOON,SUM,0,0,0,0,4,567,4,52.225929975509644 +9,,SUM,0,0,0,0,4,743,16,98.67335081100464 +9,, +10,, +10,BOWL,SUM,0,0,0,0,6,29,5,23.604433059692383 +10,CUP,SUM,0,0,0,0,8,12,8,18.779245138168335 +10,SPOON,SUM,0,0,0,0,0,35,0,17.461730003356934 +10,,SUM,0,0,0,0,14,76,13,59.84540820121765 +10,, +11,, +11,BOWL,SUM,0,0,0,0,0,64,7,21.09502100944519 +11,CUP,SUM,0,0,0,0,2,6,6,14.86521601676941 +11,SPOON,SUM,0,0,0,0,0,130,0,25.152591943740845 +11,,SUM,0,0,0,0,2,200,13,61.112828969955444 +11,, +12,, +12,BOWL,SUM,0,0,0,0,0,100,3,24.63730812072754 +12,CUP,SUM,1,0,1,0,0,438,115,0.0 +12,SPOON,SUM,0,0,0,0,0,14,0,16.512137174606323 +12,,SUM,1,0,1,0,0,552,118,41.14944529533386 +12,, +13,, +13,BOWL,SUM,0,0,0,0,0,28,6,17.39031481742859 +13,CUP,SUM,0,0,0,0,2,44,9,20.80741310119629 +13,SPOON,SUM,0,0,0,0,2,12,4,18.434448957443237 +13,,SUM,0,0,0,0,4,84,19,56.632176876068115 +13,, +14,, +14,BOWL,SUM,0,0,0,0,6,11,5,25.677917957305908 +14,CUP,SUM,1,0,1,0,6,382,108,0.0 +14,SPOON,SUM,0,0,0,0,0,17,9,33.09389805793762 +14,,SUM,1,0,1,0,12,410,122,58.77181601524353 +14,, +15,, +15,BOWL,SUM,0,0,0,0,0,182,0,24.333861827850342 +15,CUP,SUM,0,0,0,0,0,26,7,14.393471002578735 +15,SPOON,SUM,0,0,0,0,0,15,2,18.83298110961914 +15,,SUM,0,0,0,0,0,223,9,57.56031394004822 +15,, +16,, +16,BOWL,SUM,0,0,0,0,0,45,1,16.495805025100708 +16,CUP,SUM,0,0,0,0,16,24,6,24.350743055343628 +16,SPOON,SUM,0,0,0,0,0,907,4,78.50611186027527 +16,,SUM,0,0,0,0,16,976,11,119.3526599407196 +16,, +17,, +17,BOWL,SUM,0,0,0,0,0,53,6,27.511013984680176 +17,CUP,SUM,1,0,1,0,2,855,90,0.0 +17,SPOON,SUM,0,0,0,0,0,87,7,30.62739896774292 +17,,SUM,1,0,1,0,2,995,103,58.138412952423096 +17,, +18,, +18,BOWL,SUM,0,0,0,0,0,24,0,13.885917901992798 +18,CUP,SUM,0,0,0,0,6,56,4,18.6828670501709 +18,SPOON,SUM,0,0,0,0,4,6,1,18.861089944839478 +18,,SUM,0,0,0,0,10,86,5,51.429874897003174 +18,, +19,, +19,BOWL,SUM,0,0,0,0,0,55,4,17.536975145339966 +19,CUP,SUM,0,0,0,0,0,22,2,12.047250986099243 +19,SPOON,SUM,0,0,0,0,8,3,0,21.359088897705078 +19,,SUM,0,0,0,0,8,80,6,50.94331502914429 +19,, +20,, +20,BOWL,SUM,0,0,0,0,0,82,7,25.10892605781555 +20,CUP,SUM,1,0,1,0,0,465,110,0.0 +20,SPOON,SUM,0,0,0,0,0,7,10,32.079673051834106 +20,,SUM,1,0,1,0,0,554,127,57.18859910964966 +20,, +21,, +21,BOWL,SUM,1,0,1,0,2,1587,13,0.0 +21,CUP,SUM,1,0,1,0,0,610,104,0.0 +21,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +21,,SUM,3,0,3,0,2,3778,117,0.0 +21,, +22,, +22,BOWL,SUM,0,0,0,0,0,75,6,26.107800006866455 +22,CUP,SUM,0,0,0,0,0,12,10,16.855175971984863 +22,SPOON,SUM,0,0,0,0,8,101,0,27.97274684906006 +22,,SUM,0,0,0,0,8,188,16,70.93572282791138 +22,, +23,, +23,BOWL,SUM,0,0,0,0,0,14,7,21.378226041793823 +23,CUP,SUM,1,0,0,1,8,574,114,0.0 +23,SPOON,SUM,0,0,0,0,0,241,7,47.047467947006226 +23,,SUM,1,0,0,1,8,829,128,68.42569398880005 +23,, +24,, +24,BOWL,SUM,0,0,0,0,6,44,0,18.01453399658203 +24,CUP,SUM,0,0,0,0,0,44,2,12.958813905715942 +24,SPOON,SUM,1,0,1,0,6,1568,5,0.0 +24,,SUM,1,0,1,0,12,1656,7,30.973347902297974 +24,, +25,, +25,BOWL,SUM,0,0,0,0,0,119,4,21.42752504348755 +25,CUP,SUM,0,0,0,0,6,23,5,16.091768980026245 +25,SPOON,SUM,0,0,0,0,0,1,3,22.663936853408813 +25,,SUM,0,0,0,0,6,143,12,60.18323087692261 +25,, +26,, +26,BOWL,SUM,0,0,0,0,0,151,3,24.114493131637573 +26,CUP,SUM,0,0,0,0,0,54,9,16.781694173812866 +26,SPOON,SUM,0,0,0,0,0,5,1,17.97213387489319 +26,,SUM,0,0,0,0,0,210,13,58.86832118034363 +26,, +27,, +27,BOWL,SUM,0,0,0,0,0,30,4,21.774598121643066 +27,CUP,SUM,0,0,0,0,0,17,2,13.456995010375977 +27,SPOON,SUM,0,0,0,0,0,13,0,16.910961151123047 +27,,SUM,0,0,0,0,0,60,6,52.14255428314209 +27,, +28,, +28,BOWL,SUM,0,0,0,0,4,214,12,35.60226106643677 +28,CUP,SUM,0,0,0,0,0,21,4,13.346338033676147 +28,SPOON,SUM,0,0,0,0,0,175,0,27.523408889770508 +28,,SUM,0,0,0,0,4,410,16,76.47200798988342 +28,, +29,, +29,BOWL,SUM,0,0,0,0,6,37,4,17.56292486190796 +29,CUP,SUM,0,0,0,0,0,75,11,24.25345206260681 +29,SPOON,SUM,0,0,0,0,0,11,0,16.537650108337402 +29,,SUM,0,0,0,0,6,123,15,58.35402703285217 +29,, +30,, +30,BOWL,SUM,1,0,1,0,0,1500,22,0.0 +30,CUP,SUM,0,0,0,0,0,13,6,12.961507797241211 +30,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +30,,SUM,2,0,2,0,0,3094,28,12.961507797241211 +30,, +31,, +31,BOWL,SUM,0,0,0,0,0,42,18,26.60525608062744 +31,CUP,SUM,1,0,1,0,8,1123,63,0.0 +31,SPOON,SUM,0,0,0,0,0,25,1,19.352105140686035 +31,,SUM,1,0,1,0,8,1190,82,45.95736122131348 +31,, +32,, +32,BOWL,SUM,0,0,0,0,0,208,24,54.39823794364929 +32,CUP,SUM,0,0,0,0,0,26,4,12.791224002838135 +32,SPOON,SUM,0,0,0,0,0,391,1,41.84676504135132 +32,,SUM,0,0,0,0,0,625,29,109.03622698783875 +32,, +33,, +33,BOWL,SUM,0,0,0,0,0,77,7,25.586490869522095 +33,CUP,SUM,1,0,1,0,26,129,109,0.0 +33,SPOON,SUM,0,0,0,0,8,0,0,22.6729838848114 +33,,SUM,1,0,1,0,34,206,116,48.259474754333496 +33,, +34,, +34,BOWL,SUM,1,0,1,0,10,1247,53,0.0 +34,CUP,SUM,1,0,1,0,2,221,112,0.0 +34,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +34,,SUM,3,0,3,0,12,3049,165,0.0 +34,, +35,, +35,BOWL,SUM,1,0,1,0,0,1241,28,0.0 +35,CUP,SUM,0,0,0,0,0,5,4,12.96828579902649 +35,SPOON,SUM,0,0,0,0,4,78,0,23.940156936645508 +35,,SUM,1,0,1,0,4,1324,32,36.908442735672 +35,, +36,, +36,BOWL,SUM,0,0,0,0,0,6,2,14.210785865783691 +36,CUP,SUM,0,0,0,0,18,40,2,28.262330055236816 +36,SPOON,SUM,0,0,0,0,0,58,5,29.730287075042725 +36,,SUM,0,0,0,0,18,104,9,72.20340299606323 +36,, +37,, +37,BOWL,SUM,0,0,0,0,0,323,2,40.30579400062561 +37,CUP,SUM,0,0,0,0,0,38,4,12.771619081497192 +37,SPOON,SUM,0,0,0,0,0,33,11,41.81716799736023 +37,,SUM,0,0,0,0,0,394,17,94.89458107948303 +37,, +38,, +38,BOWL,SUM,0,0,0,0,0,114,2,23.842216968536377 +38,CUP,SUM,0,0,0,0,0,77,28,39.54249405860901 +38,SPOON,SUM,1,0,1,0,2,1567,5,0.0 +38,,SUM,1,0,1,0,2,1758,35,63.384711027145386 +38,, +39,, +39,BOWL,SUM,1,0,1,0,8,1517,13,0.0 +39,CUP,SUM,0,0,0,0,0,26,0,12.114723920822144 +39,SPOON,SUM,0,0,0,0,8,243,4,37.027223110198975 +39,,SUM,1,0,1,0,16,1786,17,49.14194703102112 +39,, +40,, +40,BOWL,SUM,1,0,1,0,0,933,70,0.0 +40,CUP,SUM,0,0,0,0,0,13,4,13.071056127548218 +40,SPOON,SUM,0,0,0,0,30,173,0,39.960164070129395 +40,,SUM,1,0,1,0,30,1119,74,53.03122019767761 +40,, +41,, +41,BOWL,SUM,1,0,1,0,0,1549,6,0.0 +41,CUP,SUM,0,0,0,0,10,13,6,23.908283948898315 +41,SPOON,SUM,0,0,0,0,0,76,4,21.21236801147461 +41,,SUM,1,0,1,0,10,1638,16,45.120651960372925 +41,, +42,, +42,BOWL,SUM,0,0,0,0,14,177,16,43.287765979766846 +42,CUP,SUM,1,0,1,0,0,374,106,0.0 +42,SPOON,SUM,0,0,0,0,34,131,2,46.55565309524536 +42,,SUM,1,0,1,0,48,682,124,89.8434190750122 +42,, +43,, +43,BOWL,SUM,0,0,0,0,0,39,4,19.90210795402527 +43,CUP,SUM,0,0,0,0,2,41,4,14.28514289855957 +43,SPOON,SUM,0,0,0,0,0,120,1,25.053864002227783 +43,,SUM,0,0,0,0,2,200,9,59.24111485481262 +43,, +44,, +44,BOWL,SUM,0,0,0,0,0,192,6,30.820032835006714 +44,CUP,SUM,1,0,1,0,0,775,53,0.0 +44,SPOON,SUM,0,0,0,0,0,22,0,16.17891001701355 +44,,SUM,1,0,1,0,0,989,59,46.998942852020264 +44,, +45,, +45,BOWL,SUM,0,0,0,0,0,46,6,25.13912296295166 +45,CUP,SUM,1,0,1,0,6,225,112,0.0 +45,SPOON,SUM,0,0,0,0,0,114,9,44.78759503364563 +45,,SUM,1,0,1,0,6,385,127,69.92671799659729 +45,, +46,, +46,BOWL,SUM,0,0,0,0,0,49,5,20.763957023620605 +46,CUP,SUM,1,0,1,0,2,206,111,0.0 +46,SPOON,SUM,0,0,0,0,0,118,0,23.122469186782837 +46,,SUM,1,0,1,0,2,373,116,43.88642621040344 +46,, +47,, +47,BOWL,SUM,0,0,0,0,0,26,0,14.366594076156616 +47,CUP,SUM,1,0,1,0,4,521,99,0.0 +47,SPOON,SUM,0,0,0,0,0,13,2,17.05501699447632 +47,,SUM,1,0,1,0,4,560,101,31.421611070632935 +47,, +48,, +48,BOWL,SUM,0,0,0,0,2,415,8,46.314335107803345 +48,CUP,SUM,0,0,0,0,0,17,11,17.968498945236206 +48,SPOON,SUM,0,0,0,0,0,37,0,18.874425172805786 +48,,SUM,0,0,0,0,2,469,19,83.15725922584534 +48,, +49,, +49,BOWL,SUM,0,0,0,0,14,662,11,75.74930500984192 +49,CUP,SUM,1,0,1,0,0,223,81,0.0 +49,SPOON,SUM,0,0,0,0,0,98,7,38.095966815948486 +49,,SUM,1,0,1,0,14,983,99,113.8452718257904 +49,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/kvr_last_run.csv b/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/kvr_last_run.csv new file mode 100644 index 0000000000..872d531eff --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/kvr_last_run.csv @@ -0,0 +1,144 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,0,90,5,26.146669149398804 +0,CUP,SUM,0,0,0,0,0,3,2,9.97815203666687 +0,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +0,,SUM,1,1,0,0,0,1612,7,36.124821186065674 +0,, +1,, +1,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +1,CUP,SUM,0,0,0,0,2,106,12,20.07645893096924 +1,SPOON,SUM,0,0,0,0,0,95,4,26.837361812591553 +1,,SUM,1,1,0,0,2,1720,16,46.91382074356079 +1,, +2,, +2,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +2,CUP,SUM,1,1,0,0,0,1519,0,0.0 +2,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +2,,SUM,3,3,0,0,0,4557,0,0.0 +2,, +3,, +3,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +3,CUP,SUM,0,0,0,0,0,48,6,15.514100790023804 +3,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +3,,SUM,2,2,0,0,0,3086,6,15.514100790023804 +3,, +4,, +4,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +4,CUP,SUM,1,1,0,0,0,1519,0,0.0 +4,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +4,,SUM,3,3,0,0,0,4557,0,0.0 +4,, +5,, +5,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +5,CUP,SUM,1,1,0,0,0,1519,0,0.0 +5,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +5,,SUM,3,3,0,0,0,4557,0,0.0 +5,, +6,, +6,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +6,CUP,SUM,1,1,0,0,0,1519,0,0.0 +6,SPOON,SUM,0,0,0,0,0,431,0,40.24056816101074 +6,,SUM,2,2,0,0,0,3469,0,40.24056816101074 +6,, +7,, +7,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +7,CUP,SUM,1,1,0,0,0,1519,0,0.0 +7,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +7,,SUM,3,3,0,0,0,4557,0,0.0 +7,, +8,, +8,BOWL,SUM,1,0,1,0,0,1589,0,0.0 +8,CUP,SUM,1,1,0,0,0,1519,0,0.0 +8,SPOON,SUM,0,0,0,0,0,0,0,15.104079961776733 +8,,SUM,2,1,1,0,0,3108,0,15.104079961776733 +8,, +9,, +9,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +9,CUP,SUM,1,1,0,0,0,1519,0,0.0 +9,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +9,,SUM,3,3,0,0,0,4557,0,0.0 +9,, +10,, +10,BOWL,SUM,0,0,0,0,32,23,0,28.552817821502686 +10,CUP,SUM,1,1,0,0,0,1519,0,0.0 +10,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +10,,SUM,2,2,0,0,32,3061,0,28.552817821502686 +10,, +11,, +11,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +11,CUP,SUM,1,1,0,0,0,1519,0,0.0 +11,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +11,,SUM,3,3,0,0,0,4557,0,0.0 +11,, +12,, +12,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +12,CUP,SUM,1,1,0,0,0,1519,0,0.0 +12,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +12,,SUM,3,3,0,0,0,4557,0,0.0 +12,, +13,, +13,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +13,CUP,SUM,0,0,0,0,0,4,1,11.309921979904175 +13,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +13,,SUM,2,2,0,0,0,3042,1,11.309921979904175 +13,, +14,, +14,BOWL,SUM,0,0,0,0,0,56,4,19.901787042617798 +14,CUP,SUM,1,1,0,0,0,1519,0,0.0 +14,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +14,,SUM,2,2,0,0,0,3094,4,19.901787042617798 +14,, +15,, +15,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +15,CUP,SUM,0,0,0,0,0,80,19,35.60285711288452 +15,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +15,,SUM,2,2,0,0,0,3118,19,35.60285711288452 +15,, +16,, +16,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +16,CUP,SUM,1,1,0,0,0,1519,0,0.0 +16,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +16,,SUM,3,3,0,0,0,4557,0,0.0 +16,, +17,, +17,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +17,CUP,SUM,1,1,0,0,0,1519,0,0.0 +17,SPOON,SUM,0,0,0,0,0,14,0,15.217566013336182 +17,,SUM,2,2,0,0,0,3052,0,15.217566013336182 +17,, +18,, +18,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +18,CUP,SUM,1,0,1,0,0,1658,0,0.0 +18,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +18,,SUM,3,2,1,0,0,4696,0,0.0 +18,, +19,, +19,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +19,CUP,SUM,1,0,1,0,0,1638,0,0.0 +19,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +19,,SUM,3,2,1,0,0,4676,0,0.0 +19,, +20,, +20,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +20,CUP,SUM,1,1,0,0,0,1519,0,0.0 +20,SPOON,SUM,1,0,1,0,8,1582,0,0.0 +20,,SUM,3,2,1,0,8,4620,0,0.0 +20,, +21,, +21,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +21,CUP,SUM,1,1,0,0,0,1519,0,0.0 +21,SPOON,SUM,0,0,0,0,6,103,10,27.39035391807556 +21,,SUM,2,2,0,0,6,3141,10,27.39035391807556 +21,, +22,, +22,BOWL,SUM,0,0,0,0,0,62,8,19.67384910583496 +22,CUP,SUM,0,0,0,0,0,12,10,15.023195028305054 +22,SPOON,SUM,1,0,1,0,0,1405,28,0.0 +22,,SUM,1,0,1,0,0,1479,46,34.697044134140015 +22,, +23,, +23,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +23,CUP,SUM,0,0,0,0,0,10,10,12.614169836044312 diff --git a/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/kvr_pr2_new_best.csv b/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/kvr_pr2_new_best.csv new file mode 100644 index 0000000000..872d531eff --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/kvr_pr2_new_best.csv @@ -0,0 +1,144 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,0,90,5,26.146669149398804 +0,CUP,SUM,0,0,0,0,0,3,2,9.97815203666687 +0,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +0,,SUM,1,1,0,0,0,1612,7,36.124821186065674 +0,, +1,, +1,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +1,CUP,SUM,0,0,0,0,2,106,12,20.07645893096924 +1,SPOON,SUM,0,0,0,0,0,95,4,26.837361812591553 +1,,SUM,1,1,0,0,2,1720,16,46.91382074356079 +1,, +2,, +2,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +2,CUP,SUM,1,1,0,0,0,1519,0,0.0 +2,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +2,,SUM,3,3,0,0,0,4557,0,0.0 +2,, +3,, +3,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +3,CUP,SUM,0,0,0,0,0,48,6,15.514100790023804 +3,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +3,,SUM,2,2,0,0,0,3086,6,15.514100790023804 +3,, +4,, +4,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +4,CUP,SUM,1,1,0,0,0,1519,0,0.0 +4,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +4,,SUM,3,3,0,0,0,4557,0,0.0 +4,, +5,, +5,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +5,CUP,SUM,1,1,0,0,0,1519,0,0.0 +5,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +5,,SUM,3,3,0,0,0,4557,0,0.0 +5,, +6,, +6,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +6,CUP,SUM,1,1,0,0,0,1519,0,0.0 +6,SPOON,SUM,0,0,0,0,0,431,0,40.24056816101074 +6,,SUM,2,2,0,0,0,3469,0,40.24056816101074 +6,, +7,, +7,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +7,CUP,SUM,1,1,0,0,0,1519,0,0.0 +7,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +7,,SUM,3,3,0,0,0,4557,0,0.0 +7,, +8,, +8,BOWL,SUM,1,0,1,0,0,1589,0,0.0 +8,CUP,SUM,1,1,0,0,0,1519,0,0.0 +8,SPOON,SUM,0,0,0,0,0,0,0,15.104079961776733 +8,,SUM,2,1,1,0,0,3108,0,15.104079961776733 +8,, +9,, +9,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +9,CUP,SUM,1,1,0,0,0,1519,0,0.0 +9,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +9,,SUM,3,3,0,0,0,4557,0,0.0 +9,, +10,, +10,BOWL,SUM,0,0,0,0,32,23,0,28.552817821502686 +10,CUP,SUM,1,1,0,0,0,1519,0,0.0 +10,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +10,,SUM,2,2,0,0,32,3061,0,28.552817821502686 +10,, +11,, +11,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +11,CUP,SUM,1,1,0,0,0,1519,0,0.0 +11,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +11,,SUM,3,3,0,0,0,4557,0,0.0 +11,, +12,, +12,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +12,CUP,SUM,1,1,0,0,0,1519,0,0.0 +12,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +12,,SUM,3,3,0,0,0,4557,0,0.0 +12,, +13,, +13,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +13,CUP,SUM,0,0,0,0,0,4,1,11.309921979904175 +13,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +13,,SUM,2,2,0,0,0,3042,1,11.309921979904175 +13,, +14,, +14,BOWL,SUM,0,0,0,0,0,56,4,19.901787042617798 +14,CUP,SUM,1,1,0,0,0,1519,0,0.0 +14,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +14,,SUM,2,2,0,0,0,3094,4,19.901787042617798 +14,, +15,, +15,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +15,CUP,SUM,0,0,0,0,0,80,19,35.60285711288452 +15,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +15,,SUM,2,2,0,0,0,3118,19,35.60285711288452 +15,, +16,, +16,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +16,CUP,SUM,1,1,0,0,0,1519,0,0.0 +16,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +16,,SUM,3,3,0,0,0,4557,0,0.0 +16,, +17,, +17,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +17,CUP,SUM,1,1,0,0,0,1519,0,0.0 +17,SPOON,SUM,0,0,0,0,0,14,0,15.217566013336182 +17,,SUM,2,2,0,0,0,3052,0,15.217566013336182 +17,, +18,, +18,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +18,CUP,SUM,1,0,1,0,0,1658,0,0.0 +18,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +18,,SUM,3,2,1,0,0,4696,0,0.0 +18,, +19,, +19,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +19,CUP,SUM,1,0,1,0,0,1638,0,0.0 +19,SPOON,SUM,1,1,0,0,0,1519,0,0.0 +19,,SUM,3,2,1,0,0,4676,0,0.0 +19,, +20,, +20,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +20,CUP,SUM,1,1,0,0,0,1519,0,0.0 +20,SPOON,SUM,1,0,1,0,8,1582,0,0.0 +20,,SUM,3,2,1,0,8,4620,0,0.0 +20,, +21,, +21,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +21,CUP,SUM,1,1,0,0,0,1519,0,0.0 +21,SPOON,SUM,0,0,0,0,6,103,10,27.39035391807556 +21,,SUM,2,2,0,0,6,3141,10,27.39035391807556 +21,, +22,, +22,BOWL,SUM,0,0,0,0,0,62,8,19.67384910583496 +22,CUP,SUM,0,0,0,0,0,12,10,15.023195028305054 +22,SPOON,SUM,1,0,1,0,0,1405,28,0.0 +22,,SUM,1,0,1,0,0,1479,46,34.697044134140015 +22,, +23,, +23,BOWL,SUM,1,1,0,0,0,1519,0,0.0 +23,CUP,SUM,0,0,0,0,0,10,10,12.614169836044312 diff --git a/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/kvr_pr2_orig_orig_best.csv b/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/kvr_pr2_orig_orig_best.csv new file mode 100644 index 0000000000..99afcf48a8 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/kvr_pr2_orig_orig_best.csv @@ -0,0 +1,63 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +20,, +20,BOWL,SUM,0,0,0,0,2,47,0,13.78581714630127 +20,CUP,SUM,1,0,0,1,2,188,58,0.0 +20,SPOON,SUM,0,0,0,0,0,125,0,20.95003318786621 +20,,SUM,1,0,0,1,4,360,58,34.73585033416748 +20,, +21,, +21,BOWL,SUM,0,0,0,0,0,53,0,13.247747898101807 +21,CUP,SUM,0,0,0,0,0,27,14,24.23551607131958 +21,SPOON,SUM,0,0,0,0,0,80,2,18.07046103477478 +21,,SUM,0,0,0,0,0,160,16,55.55372500419617 +21,, +22,, +22,BOWL,SUM,0,0,0,0,0,15,0,11.859118938446045 +22,CUP,SUM,0,0,0,0,0,33,13,19.584190845489502 +22,SPOON,SUM,0,0,0,0,16,63,2,24.22484803199768 +22,,SUM,0,0,0,0,16,111,15,55.66815781593323 +22,, +23,, +23,BOWL,SUM,0,0,0,0,0,13,0,10.66537094116211 +23,CUP,SUM,1,0,1,0,0,280,81,0.0 +23,SPOON,SUM,0,0,0,0,0,0,0,13.794100999832153 +23,,SUM,1,0,1,0,0,293,81,24.459471940994263 +23,, +24,, +24,BOWL,SUM,0,0,0,0,2,5,0,10.852939128875732 +24,CUP,SUM,1,0,0,1,0,185,51,0.0 +24,SPOON,SUM,0,0,0,0,0,35,0,15.279842853546143 +24,,SUM,1,0,0,1,2,225,51,26.132781982421875 +24,, +25,, +25,BOWL,SUM,0,0,0,0,0,17,0,10.735448837280273 +25,CUP,SUM,0,0,0,0,0,10,5,11.906934022903442 +25,SPOON,SUM,0,0,0,0,2,17,3,16.28773283958435 +25,,SUM,0,0,0,0,2,44,8,38.930115699768066 +25,, +26,, +26,BOWL,SUM,0,0,0,0,0,9,0,10.646228075027466 +26,CUP,SUM,1,0,0,1,0,228,54,0.0 +26,SPOON,SUM,0,0,0,0,0,29,0,14.428622961044312 +26,,SUM,1,0,0,1,0,266,54,25.074851036071777 +26,, +27,, +27,BOWL,SUM,0,0,0,0,0,0,0,10.294739961624146 +27,CUP,SUM,0,0,0,0,0,37,9,15.870995044708252 +27,SPOON,SUM,0,0,0,0,0,1,2,13.735243082046509 +27,,SUM,0,0,0,0,0,38,11,39.900978088378906 +27,, +28,, +28,BOWL,SUM,0,0,0,0,0,11,0,10.87513017654419 +28,CUP,SUM,0,0,0,0,0,22,1,10.793434143066406 +28,SPOON,SUM,0,0,0,0,0,49,0,15.872761011123657 +28,,SUM,0,0,0,0,0,82,1,37.54132533073425 +28,, +29,, +29,BOWL,SUM,0,0,0,0,2,11,0,11.241461992263794 +29,CUP,SUM,0,0,0,0,2,16,10,18.71555995941162 +29,SPOON,SUM,0,0,0,0,0,2,3,15.333929061889648 +29,,SUM,0,0,0,0,4,29,13,45.29095101356506 +29,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/kvr_pr2_orig_var_best.csv b/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/kvr_pr2_orig_var_best.csv new file mode 100644 index 0000000000..bb3024d8ba --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/kvr_pr2_orig_var_best.csv @@ -0,0 +1,123 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +30,, +30,BOWL,SUM,0,0,0,0,2,25,3,15.176192998886108 +30,CUP,SUM,1,0,0,1,0,311,72,0.0 +30,SPOON,SUM,0,0,0,0,0,82,3,21.904402017593384 +30,,SUM,1,0,0,1,2,418,78,37.08059501647949 +30,, +31,, +31,BOWL,SUM,0,0,0,0,2,17,1,14.191196918487549 +31,CUP,SUM,0,0,0,0,0,33,5,11.319457054138184 +31,SPOON,SUM,0,0,0,0,0,108,6,30.83554196357727 +31,,SUM,0,0,0,0,2,158,12,56.346195936203 +31,, +32,, +32,BOWL,SUM,0,0,0,0,0,29,2,12.624501943588257 +32,CUP,SUM,1,0,0,1,0,322,74,0.0 +32,SPOON,SUM,0,0,0,0,0,1,1,15.137447118759155 +32,,SUM,1,0,0,1,0,352,77,27.761949062347412 +32,, +33,, +33,BOWL,SUM,0,0,0,0,8,72,5,21.26604413986206 +33,CUP,SUM,0,0,0,0,2,37,2,15.092926025390625 +33,SPOON,SUM,0,0,0,0,0,52,0,17.986762046813965 +33,,SUM,0,0,0,0,10,161,7,54.34573221206665 +33,, +34,, +34,BOWL,SUM,0,0,0,0,0,58,0,14.654443979263306 +34,CUP,SUM,0,0,0,0,0,33,0,11.376353025436401 +34,SPOON,SUM,0,0,0,0,6,90,0,22.241242170333862 +34,,SUM,0,0,0,0,6,181,0,48.27203917503357 +34,, +35,, +35,BOWL,SUM,0,0,0,0,0,33,3,14.326218128204346 +35,CUP,SUM,0,0,0,0,0,9,6,10.497527122497559 +35,SPOON,SUM,0,0,0,0,4,114,0,22.181149005889893 +35,,SUM,0,0,0,0,4,156,9,47.0048942565918 +35,, +36,, +36,BOWL,SUM,1,0,1,0,56,709,92,0.0 +36,CUP,SUM,0,0,0,0,6,24,0,13.171665906906128 +36,SPOON,SUM,0,0,0,0,0,5,0,14.967988014221191 +36,,SUM,1,0,1,0,62,738,92,28.13965392112732 +36,, +37,, +37,BOWL,SUM,0,0,0,0,0,21,4,14.213629007339478 +37,CUP,SUM,0,0,0,0,0,10,2,10.409108877182007 +37,SPOON,SUM,0,0,0,0,4,9,11,27.090785026550293 +37,,SUM,0,0,0,0,4,40,17,51.71352291107178 +37,, +38,, +38,BOWL,SUM,0,0,0,0,0,23,4,14.445498943328857 +38,CUP,SUM,0,0,0,0,0,79,14,21.001418113708496 +38,SPOON,SUM,0,0,0,0,0,16,8,23.722058057785034 +38,,SUM,0,0,0,0,0,118,26,59.16897511482239 +38,, +39,, +39,BOWL,SUM,0,0,0,0,0,40,4,16.103780031204224 +39,CUP,SUM,0,0,0,0,2,11,0,11.215667009353638 +39,SPOON,SUM,0,0,0,0,0,1,1,16.523443937301636 +39,,SUM,0,0,0,0,2,52,5,43.8428909778595 +39,, +40,, +40,BOWL,SUM,0,0,0,0,0,12,0,12.185853958129883 +40,CUP,SUM,0,0,0,0,2,32,4,11.859659910202026 +40,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +40,,SUM,1,0,1,0,2,1625,4,24.04551386833191 +40,, +41,, +41,BOWL,SUM,0,0,0,0,0,55,0,14.7917799949646 +41,CUP,SUM,1,0,0,1,0,312,50,0.0 +41,SPOON,SUM,0,0,0,0,2,355,2,39.10470986366272 +41,,SUM,1,0,0,1,2,722,52,53.89648985862732 +41,, +42,, +42,BOWL,SUM,0,0,0,0,26,159,16,43.63910412788391 +42,CUP,SUM,0,0,0,0,0,37,5,19.566689014434814 +42,SPOON,SUM,0,0,0,0,0,78,5,25.31734800338745 +42,,SUM,0,0,0,0,26,274,26,88.52314114570618 +42,, +43,, +43,BOWL,SUM,0,0,0,0,0,41,3,16.09066605567932 +43,CUP,SUM,0,0,0,0,0,8,10,12.512807130813599 +43,SPOON,SUM,0,0,0,0,0,114,0,22.12491202354431 +43,,SUM,0,0,0,0,0,163,13,50.72838521003723 +43,, +44,, +44,BOWL,SUM,0,0,0,0,0,9,0,11.853585958480835 +44,CUP,SUM,0,0,0,0,0,4,6,10.589781999588013 +44,SPOON,SUM,0,0,0,0,0,25,1,17.042464017868042 +44,,SUM,0,0,0,0,0,38,7,39.48583197593689 +44,, +45,, +45,BOWL,SUM,0,0,0,0,2,10,2,13.216369867324829 +45,CUP,SUM,0,0,0,0,0,11,5,10.870016098022461 +45,SPOON,SUM,0,0,0,0,0,475,2,48.28839898109436 +45,,SUM,0,0,0,0,2,496,9,72.37478494644165 +45,, +46,, +46,BOWL,SUM,0,0,0,0,0,64,8,19.686548948287964 +46,CUP,SUM,0,0,0,0,0,9,0,10.32280707359314 +46,SPOON,SUM,0,0,0,0,0,1,1,16.505611896514893 +46,,SUM,0,0,0,0,0,74,9,46.514967918395996 +46,, +47,, +47,BOWL,SUM,0,0,0,0,0,55,3,15.032520771026611 +47,CUP,SUM,0,0,0,0,0,20,2,10.923398971557617 +47,SPOON,SUM,0,0,0,0,0,80,2,19.789910078048706 +47,,SUM,0,0,0,0,0,155,7,45.745829820632935 +47,, +48,, +48,BOWL,SUM,0,0,0,0,0,9,0,12.139205932617188 +48,CUP,SUM,0,0,0,0,0,58,15,30.707082986831665 +48,SPOON,SUM,0,0,0,0,0,23,6,19.366377115249634 +48,,SUM,0,0,0,0,0,90,21,62.212666034698486 +48,, +49,, +49,BOWL,SUM,0,0,0,0,0,8,0,12.491016149520874 +49,CUP,SUM,0,0,0,0,0,18,5,11.428593873977661 +49,SPOON,SUM,0,0,0,0,6,61,6,23.46119499206543 +49,,SUM,0,0,0,0,6,87,11,47.380805015563965 +49,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/kvr_pr2_orig_varhalf_best.csv b/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/kvr_pr2_orig_varhalf_best.csv new file mode 100644 index 0000000000..e856c5c9cc --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/old_deadline_10.12.2019/kvr_pr2_orig_varhalf_best.csv @@ -0,0 +1,291 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +50,, +50,BOWL,SUM,0,0,0,0,0,14,4,10.599961042404175 +50,CUP,SUM,0,0,0,0,0,5,0,6.82976508140564 +50,SPOON,SUM,1,0,1,0,2,1581,0,0.0 +50,,SUM,1,0,1,0,2,1600,4,17.429726123809814 +50,, +51,, +51,BOWL,SUM,0,0,0,0,0,12,0,8.819735050201416 +51,CUP,SUM,0,0,0,0,2,50,5,13.62477707862854 +51,SPOON,SUM,0,0,0,0,0,0,0,11.77640700340271 +51,,SUM,0,0,0,0,2,62,5,34.220919132232666 +51,, +52,, +52,BOWL,SUM,0,0,0,0,0,43,0,10.358792066574097 +52,CUP,SUM,0,0,0,0,2,12,4,7.626431941986084 +52,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +52,,SUM,1,0,1,0,2,1636,4,17.98522400856018 +52,, +53,, +53,BOWL,SUM,0,0,0,0,0,30,12,15.279633045196533 +53,CUP,SUM,0,0,0,0,0,16,7,8.061570882797241 +53,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +53,,SUM,1,0,1,0,0,1627,19,23.341203927993774 +53,, +54,, +54,BOWL,SUM,0,0,0,0,0,20,0,8.824887990951538 +54,CUP,SUM,0,0,0,0,0,46,2,7.7838640213012695 +54,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +54,,SUM,1,0,1,0,0,1647,2,16.608752012252808 +54,, +55,, +55,BOWL,SUM,0,0,0,0,0,22,2,9.265057802200317 +55,CUP,SUM,1,0,1,0,0,261,111,0.0 +55,SPOON,SUM,0,0,0,0,0,0,6,14.802527904510498 +55,,SUM,1,0,1,0,0,283,119,24.067585706710815 +55,, +56,, +56,BOWL,SUM,0,0,0,0,0,11,4,10.86034893989563 +56,CUP,SUM,0,0,0,0,0,32,1,9.013726949691772 +56,SPOON,SUM,0,0,0,0,0,0,7,16.014787197113037 +56,,SUM,0,0,0,0,0,43,12,35.88886308670044 +56,, +57,, +57,BOWL,SUM,0,0,0,0,0,12,0,8.734523057937622 +57,CUP,SUM,0,0,0,0,42,59,86,71.68465900421143 +57,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +57,,SUM,1,0,1,0,42,1652,86,80.41918206214905 +57,, +58,, +58,BOWL,SUM,0,0,0,0,0,18,3,10.268955945968628 +58,CUP,SUM,0,0,0,0,2,197,38,42.9977490901947 +58,SPOON,SUM,1,0,1,0,2,1326,42,0.0 +58,,SUM,1,0,1,0,4,1541,83,53.26670503616333 +58,, +59,, +59,BOWL,SUM,0,0,0,0,2,31,0,9.98353886604309 +59,CUP,SUM,0,0,0,0,0,30,14,18.098119020462036 +59,SPOON,SUM,0,0,0,0,6,6,3,15.140197038650513 +59,,SUM,0,0,0,0,8,67,17,43.22185492515564 +59,, +60,, +60,BOWL,SUM,0,0,0,0,0,37,0,10.481428861618042 +60,CUP,SUM,0,0,0,0,0,61,13,17.97027897834778 +60,SPOON,SUM,0,0,0,0,0,0,0,12.089012861251831 +60,,SUM,0,0,0,0,0,98,13,40.54072070121765 +60,, +61,, +61,BOWL,SUM,0,0,0,0,0,23,4,10.518329858779907 +61,CUP,SUM,0,0,0,0,2,10,8,8.249943971633911 +61,SPOON,SUM,0,0,0,0,0,33,5,15.682204961776733 +61,,SUM,0,0,0,0,2,66,17,34.45047879219055 +61,, +62,, +62,BOWL,SUM,0,0,0,0,2,3,0,9.43644905090332 +62,CUP,SUM,0,0,0,0,0,83,13,18.08749008178711 +62,SPOON,SUM,0,0,0,0,0,367,2,29.182981967926025 +62,,SUM,0,0,0,0,2,453,15,56.706921100616455 +62,, +63,, +63,BOWL,SUM,0,0,0,0,6,2,0,10.693027973175049 +63,CUP,SUM,0,0,0,0,0,104,22,19.450329065322876 +63,SPOON,SUM,1,0,1,0,2,1581,0,0.0 +63,,SUM,1,0,1,0,8,1687,22,30.143357038497925 +63,, +64,, +64,BOWL,SUM,1,0,1,0,0,1285,40,0.0 +64,CUP,SUM,0,0,0,0,0,35,0,7.634438991546631 +64,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +64,,SUM,2,0,2,0,0,2901,40,7.634438991546631 +64,, +65,, +65,BOWL,SUM,1,0,1,0,0,549,102,0.0 +65,CUP,SUM,0,0,0,0,0,26,1,7.4246909618377686 +65,SPOON,SUM,0,0,0,0,0,0,1,12.8157958984375 +65,,SUM,1,0,1,0,0,575,104,20.24048686027527 +65,, +66,, +66,BOWL,SUM,0,0,0,0,0,10,2,9.116393089294434 +66,CUP,SUM,0,0,0,0,38,52,13,29.734323978424072 +66,SPOON,SUM,0,0,0,0,0,34,29,28.66660189628601 +66,,SUM,0,0,0,0,38,96,44,67.51731896400452 +66,, +67,, +67,BOWL,SUM,1,1,0,0,160,78,0,0.0 +67,CUP,SUM,0,0,0,0,0,14,7,8.952981948852539 +67,SPOON,SUM,1,0,1,0,0,1582,0,0.0 +67,,SUM,2,1,1,0,160,1674,7,8.952981948852539 +67,, +68,, +68,BOWL,SUM,0,0,0,0,0,16,0,9.423910140991211 +68,CUP,SUM,0,0,0,0,0,26,10,12.244262933731079 +68,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +68,,SUM,1,0,1,0,0,1623,10,21.66817307472229 +68,, +69,, +69,BOWL,SUM,0,0,0,0,0,10,0,8.93390703201294 +69,CUP,SUM,1,0,0,1,0,285,51,0.0 +69,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +69,,SUM,2,0,1,1,0,1876,51,8.93390703201294 +69,, +70,, +70,BOWL,SUM,0,0,0,0,0,8,0,9.032894134521484 +70,CUP,SUM,1,0,1,0,4,244,71,0.0 +70,SPOON,SUM,0,0,0,0,0,176,4,23.54850196838379 +70,,SUM,1,0,1,0,4,428,75,32.58139610290527 +70,, +71,, +71,BOWL,SUM,0,0,0,0,0,13,0,9.875010013580322 +71,CUP,SUM,0,0,0,0,0,28,0,7.775708913803101 +71,SPOON,SUM,1,0,1,0,0,592,102,0.0 +71,,SUM,1,0,1,0,0,633,102,17.650718927383423 +71,, +72,, +72,BOWL,SUM,0,0,0,0,0,14,0,9.158792972564697 +72,CUP,SUM,1,0,0,1,0,242,53,0.0 +72,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +72,,SUM,2,0,1,1,0,1837,53,9.158792972564697 +72,, +73,, +73,BOWL,SUM,0,0,0,0,0,8,4,10.863928079605103 +73,CUP,SUM,0,0,0,0,0,14,7,9.10171389579773 +73,SPOON,SUM,0,0,0,0,0,0,1,13.112598180770874 +73,,SUM,0,0,0,0,0,22,12,33.078240156173706 +73,, +74,, +74,BOWL,SUM,1,0,1,0,0,1581,0,0.0 +74,CUP,SUM,0,0,0,0,0,298,40,46.43463110923767 +74,SPOON,SUM,0,0,0,0,0,11,2,14.50262999534607 +74,,SUM,1,0,1,0,0,1890,42,60.93726110458374 +74,, +75,, +75,BOWL,SUM,0,0,0,0,0,10,2,9.391451835632324 +75,CUP,SUM,0,0,0,0,2,5,8,8.284360885620117 +75,SPOON,SUM,0,0,0,0,0,27,0,12.70317792892456 +75,,SUM,0,0,0,0,2,42,10,30.378990650177002 +75,, +76,, +76,BOWL,SUM,0,0,0,0,2,17,8,13.663438081741333 +76,CUP,SUM,0,0,0,0,0,162,47,42.28623414039612 +76,SPOON,SUM,1,0,1,0,54,1062,0,0.0 +76,,SUM,1,0,1,0,56,1241,55,55.94967222213745 +76,, +77,, +77,BOWL,SUM,0,0,0,0,0,31,6,11.966325998306274 +77,CUP,SUM,1,0,0,1,0,305,51,0.0 +77,SPOON,SUM,0,0,0,0,0,77,1,16.68572688102722 +77,,SUM,1,0,0,1,0,413,58,28.652052879333496 +77,, +78,, +78,BOWL,SUM,0,0,0,0,0,7,0,9.105072021484375 +78,CUP,SUM,0,0,0,0,0,51,10,14.868062019348145 +78,SPOON,SUM,0,0,0,0,0,0,2,12.604153871536255 +78,,SUM,0,0,0,0,0,58,12,36.577287912368774 +78,, +79,, +79,BOWL,SUM,0,0,0,0,0,19,1,9.620437860488892 +79,CUP,SUM,1,0,1,0,0,143,112,0.0 +79,SPOON,SUM,1,0,1,0,0,899,78,0.0 +79,,SUM,2,0,2,0,0,1061,191,9.620437860488892 +79,, +80,, +80,BOWL,SUM,0,0,0,0,0,12,8,12.730754137039185 +80,CUP,SUM,0,0,0,0,0,18,5,10.660567045211792 +80,SPOON,SUM,0,0,0,0,0,6,13,20.492497205734253 +80,,SUM,0,0,0,0,0,36,26,43.88381838798523 +80,, +81,, +81,BOWL,SUM,0,0,0,0,0,14,8,13.050469160079956 +81,CUP,SUM,0,0,0,0,0,148,32,36.885241985321045 +81,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +81,,SUM,1,0,1,0,0,1743,40,49.935711145401 +81,, +82,, +82,BOWL,SUM,0,0,0,0,0,271,2,22.20917582511902 +82,CUP,SUM,0,0,0,0,0,85,30,29.510241985321045 +82,SPOON,SUM,1,0,1,0,10,1587,0,0.0 +82,,SUM,1,0,1,0,10,1943,32,51.71941781044006 +82,, +83,, +83,BOWL,SUM,0,0,0,0,0,14,0,9.251063823699951 +83,CUP,SUM,0,0,0,0,0,41,5,9.406798839569092 +83,SPOON,SUM,1,0,1,0,2,1581,0,0.0 +83,,SUM,1,0,1,0,2,1636,5,18.657862663269043 +83,, +84,, +84,BOWL,SUM,0,0,0,0,0,35,6,12.497748136520386 +84,CUP,SUM,1,0,1,0,4,320,110,0.0 +84,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +84,,SUM,2,0,2,0,4,1936,116,12.497748136520386 +84,, +85,, +85,BOWL,SUM,0,0,0,0,0,120,2,14.380787134170532 +85,CUP,SUM,0,0,0,0,6,93,31,36.29663109779358 +85,SPOON,SUM,0,0,0,0,0,38,0,14.628196001052856 +85,,SUM,0,0,0,0,6,251,33,65.30561423301697 +85,, +86,, +86,BOWL,SUM,1,0,1,0,0,1013,64,0.0 +86,CUP,SUM,0,0,0,0,0,20,4,8.184858083724976 +86,SPOON,SUM,0,0,0,0,0,0,2,12.805813074111938 +86,,SUM,1,0,1,0,0,1033,70,20.990671157836914 +86,, +87,, +87,BOWL,SUM,0,0,0,0,0,17,1,10.491102933883667 +87,CUP,SUM,0,0,0,0,2,106,30,27.989120960235596 +87,SPOON,SUM,0,0,0,0,0,2,7,17.713347911834717 +87,,SUM,0,0,0,0,2,125,38,56.19357180595398 +87,, +88,, +88,BOWL,SUM,1,0,1,0,0,491,102,0.0 +88,CUP,SUM,0,0,0,0,0,23,9,9.6980140209198 +88,SPOON,SUM,0,0,0,0,0,0,4,13.845911979675293 +88,,SUM,1,0,1,0,0,514,115,23.543926000595093 +88,, +89,, +89,BOWL,SUM,0,0,0,0,72,112,4,48.080251932144165 +89,CUP,SUM,0,0,0,0,0,17,2,9.52760910987854 +89,SPOON,SUM,0,0,0,0,0,4,2,12.896147966384888 +89,,SUM,0,0,0,0,72,133,8,70.50400900840759 +89,, +90,, +90,BOWL,SUM,1,0,1,0,0,714,88,0.0 +90,CUP,SUM,0,0,0,0,6,6,9,13.423007011413574 +90,SPOON,SUM,1,0,1,0,0,1590,0,0.0 +90,,SUM,2,0,2,0,6,2310,97,13.423007011413574 +90,, +91,, +91,BOWL,SUM,0,0,0,0,6,201,12,24.63028907775879 +91,CUP,SUM,1,0,0,1,0,357,58,0.0 +91,SPOON,SUM,0,0,0,0,0,0,14,19.229068994522095 +91,,SUM,1,0,0,1,6,558,84,43.859358072280884 +91,, +92,, +92,BOWL,SUM,0,0,0,0,0,11,0,9.569445133209229 +92,CUP,SUM,1,0,0,1,2,288,57,0.0 +92,SPOON,SUM,1,0,1,0,16,1452,0,0.0 +92,,SUM,2,0,1,1,18,1751,57,9.569445133209229 +92,, +93,, +93,BOWL,SUM,0,0,0,0,0,2,0,9.265429973602295 +93,CUP,SUM,0,0,0,0,0,5,0,7.2139599323272705 +93,SPOON,SUM,0,0,0,0,4,9,4,15.813823938369751 +93,,SUM,0,0,0,0,4,16,4,32.293213844299316 +93,, +94,, +94,BOWL,SUM,0,0,0,0,0,85,19,22.648711919784546 +94,CUP,SUM,0,0,0,0,0,22,2,8.69812798500061 +94,SPOON,SUM,0,0,0,0,4,4,10,19.86899209022522 +94,,SUM,0,0,0,0,4,111,31,51.215831995010376 +94,, +95,, +95,BOWL,SUM,0,0,0,0,0,32,0,10.771960020065308 +95,CUP,SUM,1,0,0,1,0,338,54,0.0 +95,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +95,,SUM,2,0,1,1,0,1951,54,10.771960020065308 +95,, +96,, +96,BOWL,SUM,0,0,0,0,0,39,6,13.384937047958374 +96,CUP,SUM,0,0,0,0,0,27,4,8.436053037643433 +96,SPOON,SUM,1,0,1,0,0,1582,0,0.0 +96,,SUM,1,0,1,0,0,1648,10,21.820990085601807 +96,, +97,, +97,BOWL,SUM,1,0,1,0,0,933,76,0.0 +97,CUP,SUM,1,0,0,1,0,251,55,0.0 +97,SPOON,SUM,0,0,0,0,4,311,0,28.879663944244385 +97,,SUM,2,0,1,1,4,1495,131,28.879663944244385 +97,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/paper/1.Pr2HrSim.csv b/cram_knowrob/cram_knowrob_vr/experiments/paper/1.Pr2HrSim.csv new file mode 100644 index 0000000000..d99696fbb6 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/paper/1.Pr2HrSim.csv @@ -0,0 +1,1203 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,1,18,12.8868250847 +0,CUP,SUM,0,0,0,0,0,0,17,9.2035570145 +0,SPOON,SUM,0,0,0,0,20,0,0,17.2296690941 +0,,SUM,0,0,0,0,20,1,35,39.3200511932 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,0,1,4,6.8639597893 +1,CUP,SUM,0,0,0,0,20,2,6,13.6228618622 +1,SPOON,SUM,0,0,0,0,12,8,27,20.7887630463 +1,,SUM,0,0,0,0,32,11,37,41.2755846977 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,0,1,16,9.6965088844 +2,CUP,SUM,0,0,0,0,0,0,2,4.244836092 +2,SPOON,SUM,0,0,0,0,16,2,3,17.2406001091 +2,,SUM,0,0,0,0,16,3,21,31.1819450855 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,8,0,8,10.5855000019 +3,CUP,SUM,0,0,0,0,0,3,18,6.4490301609 +3,SPOON,SUM,0,0,0,0,0,0,4,9.9857809544 +3,,SUM,0,0,0,0,8,3,30,27.0203111172 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,8,2,32,15.4768509865 +4,CUP,SUM,0,0,0,0,0,0,22,9.6204090118 +4,SPOON,SUM,0,0,0,0,0,4,17,12.9086449146 +4,,SUM,0,0,0,0,8,6,71,38.0059049129 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,0,4,3,7.1034610271 +5,CUP,SUM,0,0,0,0,8,1,10,10.270373106 +5,SPOON,SUM,0,0,0,0,32,2,28,30.3356311321 +5,,SUM,0,0,0,0,40,7,41,47.7094652653 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,0,1,8,7.9186930656 +6,CUP,SUM,0,0,0,0,0,0,4,4.2926778793 +6,SPOON,SUM,0,0,0,0,16,0,0,15.946710825 +6,,SUM,0,0,0,0,16,1,12,28.1580817699 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,0,1,1,6.7906441689 +7,CUP,SUM,0,0,0,0,48,3,2,25.1059589386 +7,SPOON,SUM,0,0,0,0,8,0,2,13.7524030209 +7,,SUM,0,0,0,0,56,4,5,45.6490061283 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,0,1,18,12.3100121021 +8,CUP,SUM,0,0,0,0,0,0,17,9.0084381104 +8,SPOON,SUM,0,0,0,0,20,0,0,17.4890048504 +8,,SUM,0,0,0,0,20,1,35,38.8074550629 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,1,4,6.8408610821 +9,CUP,SUM,0,0,0,0,20,2,6,13.4904181957 +9,SPOON,SUM,0,0,0,0,12,8,27,20.478000164 +9,,SUM,0,0,0,0,32,11,37,40.8092794418 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,1,16,9.6217720509 +10,CUP,SUM,0,0,0,0,0,0,2,4.0521671772 +10,SPOON,SUM,0,0,0,0,16,2,3,17.4971330166 +10,,SUM,0,0,0,0,16,3,21,31.1710722446 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,8,0,8,10.9636209011 +11,CUP,SUM,0,0,0,0,0,3,18,6.2743570805 +11,SPOON,SUM,0,0,0,0,0,0,4,10.1082618237 +11,,SUM,0,0,0,0,8,3,30,27.3462398052 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,8,2,32,15.3894898891 +12,CUP,SUM,0,0,0,0,0,0,22,9.6602289677 +12,SPOON,SUM,0,0,0,0,0,4,17,13.0366840363 +12,,SUM,0,0,0,0,8,6,71,38.0864028931 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,0,4,3,6.8435721397 +13,CUP,SUM,0,0,0,0,8,1,10,9.9836978912 +13,SPOON,SUM,0,0,0,0,32,2,28,29.9146649837 +13,,SUM,0,0,0,0,40,7,41,46.7419350147 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,0,1,8,7.85947299 +14,CUP,SUM,0,0,0,0,0,0,4,4.1716580391 +14,SPOON,SUM,0,0,0,0,16,0,0,16.08466506 +14,,SUM,0,0,0,0,16,1,12,28.1157960892 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,0,1,1,6.5900440216 +15,CUP,SUM,0,0,0,0,48,3,2,25.1881930828 +15,SPOON,SUM,0,0,0,0,8,0,2,13.6236560345 +15,,SUM,0,0,0,0,56,4,5,45.4018931389 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,0,0,6.1940560341 +16,CUP,SUM,0,0,0,0,8,0,41,24.6789951324 +16,SPOON,SUM,0,0,0,0,0,2,16,12.6928331852 +16,,SUM,0,0,0,0,8,2,57,43.5658843517 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,0,2,2,6.2126150131 +17,CUP,SUM,0,0,0,0,0,3,44,22.9514181614 +17,SPOON,SUM,0,0,0,0,0,0,5,10.3252391815 +17,,SUM,0,0,0,0,0,5,51,39.489272356 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,0,0,0,6.0750510693 +18,CUP,SUM,0,0,0,0,0,2,2,4.0837421417 +18,SPOON,SUM,0,0,0,0,0,0,6,10.7504999638 +18,,SUM,0,0,0,0,0,2,8,20.9092931747 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,2,13,9.0930099487 +19,CUP,SUM,0,0,0,0,0,1,12,7.0760650635 +19,SPOON,SUM,0,0,0,0,0,0,2,10.2661738396 +19,,SUM,0,0,0,0,0,3,27,26.4352488518 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,0,12,21,10.9524009228 +20,CUP,SUM,1,0,0,1,24,1,67,0 +20,SPOON,SUM,0,0,0,0,0,2,4,10.2108559608 +20,,SUM,1,0,0,1,24,15,92,21.1632568836 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,0,4,6.7599239349 +21,CUP,SUM,0,0,0,0,12,3,11,11.4421658516 +21,SPOON,SUM,0,0,0,0,8,1,0,12.6718318462 +21,,SUM,0,0,0,0,20,4,15,30.8739216328 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,8,32,184,46.5364570618 +22,CUP,SUM,0,0,0,0,0,1,7,4.8348150253 +22,SPOON,SUM,0,0,0,0,0,2,0,9.5352180004 +22,,SUM,0,0,0,0,8,35,191,60.9064900875 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,3,48,16.2012979984 +23,CUP,SUM,0,0,0,0,0,0,2,4.2232899666 +23,SPOON,SUM,0,0,0,0,0,0,0,9.6906650066 +23,,SUM,0,0,0,0,0,3,50,30.1152529716 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,0,2,11,8.9214689732 +24,CUP,SUM,0,0,0,0,0,9,29,17.936727047 +24,SPOON,SUM,0,0,0,0,0,6,32,16.6180520058 +24,,SUM,0,0,0,0,0,17,72,43.4762480259 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,0,1,22,10.6977190971 +25,CUP,SUM,0,0,0,0,12,2,24,18.6047210693 +25,SPOON,SUM,0,0,0,0,8,0,5,14.220635891 +25,,SUM,0,0,0,0,20,3,51,43.5230760574 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,0,1,5,7.5495531559 +26,CUP,SUM,0,0,0,0,0,0,18,8.5182650089 +26,SPOON,SUM,0,0,0,0,0,0,9,11.5531489849 +26,,SUM,0,0,0,0,0,1,32,27.6209671497 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,0,17,60,18.723747015 +27,CUP,SUM,1,0,0,1,0,0,51,0 +27,SPOON,SUM,0,0,0,0,10,4,16,18.2132298946 +27,,SUM,1,0,0,1,10,21,127,36.9369769096 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,0,0,4,7.2506151199 +28,CUP,SUM,0,0,0,0,16,2,7,14.5965850353 +28,SPOON,SUM,0,0,0,0,0,2,18,13.1354808807 +28,,SUM,0,0,0,0,16,4,29,34.982681036 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,0,0,0,6.2490329742 +29,CUP,SUM,0,0,0,0,0,0,15,9.4839229584 +29,SPOON,SUM,0,0,0,0,0,1,4,10.6826291084 +29,,SUM,0,0,0,0,0,1,19,26.415585041 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,8,9,28,15.6901190281 +30,CUP,SUM,1,0,0,1,0,2,59,0 +30,SPOON,SUM,0,0,0,0,24,15,33,28.4713468552 +30,,SUM,1,0,0,1,32,26,120,44.1614658833 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,0,3,36,13.9809160233 +31,CUP,SUM,0,0,0,0,8,1,11,9.8417890072 +31,SPOON,SUM,0,0,0,0,0,2,9,12.6882638931 +31,,SUM,0,0,0,0,8,6,56,36.5109689236 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,0,6,8,9.2241950035 +32,CUP,SUM,0,0,0,0,0,1,2,4.9750339985 +32,SPOON,SUM,0,0,0,0,2,2,4,12.3001558781 +32,,SUM,0,0,0,0,2,9,14,26.4993848801 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,0,1,7.4829289913 +33,CUP,SUM,0,0,0,0,16,0,13,14.7805190086 +33,SPOON,SUM,0,0,0,0,8,0,13,17.9933419228 +33,,SUM,0,0,0,0,24,0,27,40.2567899227 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,0,1,0,7.2762839794 +34,CUP,SUM,1,0,0,1,0,0,66,0 +34,SPOON,SUM,0,0,0,0,0,0,5,12.9847791195 +34,,SUM,1,0,0,1,0,1,71,20.2610630989 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,8,2,10,13.1548578739 +35,CUP,SUM,0,0,0,0,6,0,5,8.30519104 +35,SPOON,SUM,0,0,0,0,8,0,0,15.1683578491 +35,,SUM,0,0,0,0,22,2,15,36.6284067631 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,0,1,20,11.2426829338 +36,CUP,SUM,0,0,0,0,0,2,18,9.8954041004 +36,SPOON,SUM,0,0,0,0,0,2,0,11.3789019585 +36,,SUM,0,0,0,0,0,5,38,32.5169889927 +36,,,,,,,,,, +37,,,,,,,,,, +37,BOWL,SUM,0,0,0,0,0,0,0,7.4002969265 +37,CUP,SUM,0,0,0,0,8,0,42,27.474957943 +37,SPOON,SUM,0,0,0,0,0,2,4,12.578772068 +37,,SUM,0,0,0,0,8,2,46,47.4540269375 +37,,,,,,,,,, +38,,,,,,,,,, +38,BOWL,SUM,0,0,0,0,0,18,176,43.6697130203 +38,CUP,SUM,0,0,0,0,12,1,6,12.0623941422 +38,SPOON,SUM,0,0,0,0,0,4,8,13.7960588932 +38,,SUM,0,0,0,0,12,23,190,69.5281660557 +38,,,,,,,,,, +39,,,,,,,,,, +39,BOWL,SUM,0,0,0,0,0,0,0,7.875357151 +39,CUP,SUM,0,0,0,0,0,0,43,23.2071499825 +39,SPOON,SUM,0,0,0,0,0,0,0,10.6997258663 +39,,SUM,0,0,0,0,0,0,43,41.7822329998 +39,,,,,,,,,, +40,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,0,1,0,7.9824428558 +40,CUP,SUM,0,0,0,0,0,0,7,6.7208909988 +40,SPOON,SUM,0,0,0,0,0,12,47,22.6448988914 +40,,SUM,0,0,0,0,0,13,54,37.3482327461 +40,,,,,,,,,, +41,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,0,0,3,8.5203299522 +41,CUP,SUM,0,0,0,0,14,1,6,13.8611290455 +41,SPOON,SUM,0,0,0,0,0,0,5,13.102104187 +41,,SUM,0,0,0,0,14,1,14,35.4835631847 +41,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,0,0,4,8.4169311523 +42,CUP,SUM,0,0,0,0,16,0,15,19.3218491077 +42,SPOON,SUM,0,0,0,0,0,4,11,14.0356647968 +42,,SUM,0,0,0,0,16,4,30,41.7744450569 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,12,0,0,14.6747610569 +43,CUP,SUM,0,0,0,0,8,2,21,16.2153348923 +43,SPOON,SUM,0,0,0,0,0,0,0,11.859197855 +43,,SUM,0,0,0,0,20,2,21,42.7492938042 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,0,6,84,25.3971431255 +44,CUP,SUM,0,0,0,0,0,2,17,13.0895380974 +44,SPOON,SUM,0,0,0,0,0,1,4,11.9813818932 +44,,SUM,0,0,0,0,0,9,105,50.4680631161 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,0,5,30,14.9458658695 +45,CUP,SUM,0,0,0,0,8,3,33,24.0518400669 +45,SPOON,SUM,0,0,0,0,8,5,4,18.1331820488 +45,,SUM,0,0,0,0,16,13,67,57.1308879852 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,0,0,1,9.0187418461 +46,CUP,SUM,0,0,0,0,0,0,7,7.3258450031 +46,SPOON,SUM,0,0,0,0,0,1,13,14.2071149349 +46,,SUM,0,0,0,0,0,1,21,30.5517017841 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,0,0,0,0,12,0,5,15.9248719215 +47,CUP,SUM,1,0,0,1,8,0,51,0 +47,SPOON,SUM,0,0,0,0,16,3,4,22.8173220158 +47,,SUM,1,0,0,1,36,3,60,38.7421939373 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,0,6,41,16.0754420757 +48,CUP,SUM,0,0,0,0,0,0,6,5.3779389858 +48,SPOON,SUM,0,0,0,0,0,2,0,12.1025829315 +48,,SUM,0,0,0,0,0,8,47,33.5559639931 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,0,4,18,11.9138839245 +49,CUP,SUM,0,0,0,0,8,5,54,37.5192821026 +49,SPOON,SUM,0,0,0,0,28,4,0,26.1263279915 +49,,SUM,0,0,0,0,36,13,72,75.5594940186 +49,,,,,,,,,, +50,,,,,,,,,, +50,BOWL,SUM,1,0,1,0,4,22,196,0 +50,CUP,SUM,1,0,0,1,24,2,51,0 +50,SPOON,SUM,0,0,0,0,24,7,1,28.0768549442 +50,,SUM,2,0,1,1,52,31,248,28.0768549442 +50,,,,,,,,,, +51,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,0,0,0,8.3131949902 +51,CUP,SUM,0,0,0,0,0,0,2,6.1342489719 +51,SPOON,SUM,0,0,0,0,0,0,2,12.7308900356 +51,,SUM,0,0,0,0,0,0,4,27.1783339977 +51,,,,,,,,,, +52,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,16,0,0,18.3324708939 +52,CUP,SUM,0,0,0,0,12,0,2,13.3191359043 +52,SPOON,SUM,0,0,0,0,0,1,0,11.3959951401 +52,,SUM,0,0,0,0,28,1,2,43.0476019382 +52,,,,,,,,,, +53,,,,,,,,,, +53,BOWL,SUM,0,0,0,0,8,3,21,17.7842929363 +53,CUP,SUM,0,0,0,0,0,3,21,12.0741188526 +53,SPOON,SUM,0,0,0,0,0,2,13,14.5062360764 +53,,SUM,0,0,0,0,8,8,55,44.3646478653 +53,,,,,,,,,, +54,,,,,,,,,, +54,BOWL,SUM,0,0,0,0,0,0,8,8.9383840561 +54,CUP,SUM,0,0,0,0,0,2,23,13.6544439793 +54,SPOON,SUM,0,0,0,0,0,1,0,12.0926930904 +54,,SUM,0,0,0,0,0,3,31,34.6855211258 +54,,,,,,,,,, +55,,,,,,,,,, +55,BOWL,SUM,0,0,0,0,0,4,10,10.1304860115 +55,CUP,SUM,0,0,0,0,0,2,7,6.3867139816 +55,SPOON,SUM,0,0,0,0,0,1,10,12.9298710823 +55,,SUM,0,0,0,0,0,7,27,29.4470710754 +55,,,,,,,,,, +56,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,0,2,5,9.7557339668 +56,CUP,SUM,0,0,0,0,0,1,2,5.9185678959 +56,SPOON,SUM,0,0,0,0,0,1,4,12.5263831615 +56,,SUM,0,0,0,0,0,4,11,28.2006850243 +56,,,,,,,,,, +57,,,,,,,,,, +57,BOWL,SUM,0,0,0,0,0,3,8,10.7106730938 +57,CUP,SUM,0,0,0,0,0,1,3,6.6652328968 +57,SPOON,SUM,0,0,0,0,0,10,36,20.0421209335 +57,,SUM,0,0,0,0,0,14,47,37.4180269241 +57,,,,,,,,,, +58,,,,,,,,,, +58,BOWL,SUM,0,0,0,0,0,2,16,9.6682059765 +58,CUP,SUM,0,0,0,0,0,2,6,4.4126329422 +58,SPOON,SUM,0,0,0,0,0,1,16,12.9875209332 +58,,SUM,0,0,0,0,0,5,38,27.0683598518 +58,,,,,,,,,, +59,,,,,,,,,, +59,BOWL,SUM,0,0,0,0,0,11,60,18.8260300159 +59,CUP,SUM,0,0,0,0,16,1,33,21.8232059479 +59,SPOON,SUM,0,0,0,0,0,1,0,9.1085929871 +59,,SUM,0,0,0,0,16,13,93,49.7578289509 +59,,,,,,,,,, +60,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,8,2,5,10.4012200832 +60,CUP,SUM,0,0,0,0,0,1,8,4.545427084 +60,SPOON,SUM,0,0,0,0,0,0,3,10.4259700775 +60,,SUM,0,0,0,0,8,3,16,25.3726172447 +60,,,,,,,,,, +61,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,0,0,5,7.3087821007 +61,CUP,SUM,0,0,0,0,8,10,65,38.4326338768 +61,SPOON,SUM,0,0,0,0,0,2,33,16.0271379948 +61,,SUM,0,0,0,0,8,12,103,61.7685539722 +61,,,,,,,,,, +62,,,,,,,,,, +62,BOWL,SUM,0,0,0,0,0,0,0,6.1273419857 +62,CUP,SUM,0,0,0,0,0,1,18,9.1771271229 +62,SPOON,SUM,0,0,0,0,0,2,5,10.6948068142 +62,,SUM,0,0,0,0,0,3,23,25.9992759228 +62,,,,,,,,,, +63,,,,,,,,,, +63,BOWL,SUM,0,0,0,0,0,0,12,8.4758760929 +63,CUP,SUM,0,0,0,0,0,0,26,14.4389801025 +63,SPOON,SUM,0,0,0,0,0,0,2,10.2660491467 +63,,SUM,0,0,0,0,0,0,40,33.1809053421 +63,,,,,,,,,, +64,,,,,,,,,, +64,BOWL,SUM,0,0,0,0,8,0,0,9.5460531712 +64,CUP,SUM,0,0,0,0,0,4,8,5.5689270496 +64,SPOON,SUM,0,0,0,0,0,0,0,9.5279388428 +64,,SUM,0,0,0,0,8,4,8,24.6429190636 +64,,,,,,,,,, +65,,,,,,,,,, +65,BOWL,SUM,0,0,0,0,32,1,0,20.4473941326 +65,CUP,SUM,0,0,0,0,16,0,2,10.4875361919 +65,SPOON,SUM,0,0,0,0,0,0,1,9.8783550262 +65,,SUM,0,0,0,0,48,1,3,40.8132853508 +65,,,,,,,,,, +66,,,,,,,,,, +66,BOWL,SUM,0,0,0,0,0,1,24,10.8991589546 +66,CUP,SUM,0,0,0,0,0,2,47,24.1746790409 +66,SPOON,SUM,0,0,0,0,0,4,10,12.3862469196 +66,,SUM,0,0,0,0,0,7,81,47.4600849152 +66,,,,,,,,,, +67,,,,,,,,,, +67,BOWL,SUM,0,0,0,0,8,0,8,11.515761137 +67,CUP,SUM,1,0,0,1,8,0,57,0 +67,SPOON,SUM,0,0,0,0,0,0,9,12.0420877934 +67,,SUM,1,0,0,1,16,0,74,23.5578489304 +67,,,,,,,,,, +68,,,,,,,,,, +68,BOWL,SUM,0,0,0,0,0,3,6,8.307336092 +68,CUP,SUM,0,0,0,0,0,1,5,4.94607687 +68,SPOON,SUM,0,0,0,0,8,0,5,14.2884299755 +68,,SUM,0,0,0,0,8,4,16,27.5418429375 +68,,,,,,,,,, +69,,,,,,,,,, +69,BOWL,SUM,0,0,0,0,8,10,66,22.4142298698 +69,CUP,SUM,0,0,0,0,0,1,44,19.1177401543 +69,SPOON,SUM,0,0,0,0,0,0,16,13.3245418072 +69,,SUM,0,0,0,0,8,11,126,54.8565118313 +69,,,,,,,,,, +70,,,,,,,,,, +70,BOWL,SUM,0,0,0,0,0,1,4,7.6118881702 +70,CUP,SUM,0,0,0,0,0,0,3,5.4900989532 +70,SPOON,SUM,0,0,0,0,8,9,44,24.5959160328 +70,,SUM,0,0,0,0,8,10,51,37.6979031563 +70,,,,,,,,,, +71,,,,,,,,,, +71,BOWL,SUM,0,0,0,0,0,0,24,11.3888509274 +71,CUP,SUM,0,0,0,0,8,6,72,36.8825199604 +71,SPOON,SUM,0,0,0,0,0,3,6,13.2844769955 +71,,SUM,0,0,0,0,8,9,102,61.5558478832 +71,,,,,,,,,, +72,,,,,,,,,, +72,BOWL,SUM,0,0,0,0,0,1,14,10.4121859074 +72,CUP,SUM,1,0,0,1,56,4,61,0 +72,SPOON,SUM,0,0,0,0,8,0,0,15.0754439831 +72,,SUM,1,0,0,1,64,5,75,25.4876298904 +72,,,,,,,,,, +73,,,,,,,,,, +73,BOWL,SUM,0,0,0,0,0,5,29,14.3728370667 +73,CUP,SUM,0,0,0,0,0,0,6,6.3985991478 +73,SPOON,SUM,0,0,0,0,8,0,4,15.9090890884 +73,,SUM,0,0,0,0,8,5,39,36.6805253029 +73,,,,,,,,,, +74,,,,,,,,,, +74,BOWL,SUM,0,0,0,0,12,1,8,14.9388189316 +74,CUP,SUM,0,0,0,0,0,0,12,9.2944719791 +74,SPOON,SUM,0,0,0,0,36,0,5,32.0581109524 +74,,SUM,0,0,0,0,48,1,25,56.2914018631 +74,,,,,,,,,, +75,,,,,,,,,, +75,BOWL,SUM,0,0,0,0,8,0,0,12.1203420162 +75,CUP,SUM,0,0,0,0,0,0,20,11.7941319942 +75,SPOON,SUM,0,0,0,0,0,1,0,11.0267679691 +75,,SUM,0,0,0,0,8,1,20,34.9412419796 +75,,,,,,,,,, +76,,,,,,,,,, +76,BOWL,SUM,0,0,0,0,0,0,1,8.1389110088 +76,CUP,SUM,0,0,0,0,0,0,4,6.4923481941 +76,SPOON,SUM,0,0,0,0,28,3,9,30.3912341595 +76,,SUM,0,0,0,0,28,3,14,45.0224933624 +76,,,,,,,,,, +77,,,,,,,,,, +77,BOWL,SUM,0,0,0,0,0,6,4,8.3913090229 +77,CUP,SUM,0,0,0,0,8,1,2,11.5134909153 +77,SPOON,SUM,0,0,0,0,0,2,4,12.4963438511 +77,,SUM,0,0,0,0,8,9,10,32.4011437893 +77,,,,,,,,,, +78,,,,,,,,,, +78,BOWL,SUM,0,0,0,0,8,1,4,13.8900771141 +78,CUP,SUM,0,0,0,0,0,0,10,6.7872481346 +78,SPOON,SUM,0,0,0,0,0,2,9,14.3729419708 +78,,SUM,0,0,0,0,8,3,23,35.0502672195 +78,,,,,,,,,, +79,,,,,,,,,, +79,BOWL,SUM,0,0,0,0,0,0,8,10.1590471268 +79,CUP,SUM,0,0,0,0,0,1,8,7.7371120453 +79,SPOON,SUM,0,0,0,0,0,0,4,13.0731239319 +79,,SUM,0,0,0,0,0,1,20,30.9692831039 +79,,,,,,,,,, +80,,,,,,,,,, +80,BOWL,SUM,0,0,0,0,0,0,0,9.0746631622 +80,CUP,SUM,0,0,0,0,0,1,14,9.6896378994 +80,SPOON,SUM,0,0,0,0,0,0,5,13.2256140709 +80,,SUM,0,0,0,0,0,1,19,31.9899151325 +80,,,,,,,,,, +81,,,,,,,,,, +81,BOWL,SUM,0,0,0,0,16,0,0,17.2518389225 +81,CUP,SUM,1,0,0,1,0,0,51,0 +81,SPOON,SUM,0,0,0,0,4,7,36,19.7306330204 +81,,SUM,1,0,0,1,20,7,87,36.9824719429 +81,,,,,,,,,, +82,,,,,,,,,, +82,BOWL,SUM,0,0,0,0,0,3,4,9.1886980534 +82,CUP,SUM,0,0,0,0,0,2,4,6.7278599739 +82,SPOON,SUM,0,0,0,0,0,0,0,11.8397378922 +82,,SUM,0,0,0,0,0,5,8,27.7562959194 +82,,,,,,,,,, +83,,,,,,,,,, +83,BOWL,SUM,0,0,0,0,0,2,8,10.1684780121 +83,CUP,SUM,0,0,0,0,8,2,39,25.5376429558 +83,SPOON,SUM,0,0,0,0,0,1,8,13.0391850471 +83,,SUM,0,0,0,0,8,5,55,48.745306015 +83,,,,,,,,,, +84,,,,,,,,,, +84,BOWL,SUM,0,0,0,0,0,1,0,8.1100280285 +84,CUP,SUM,0,0,0,0,0,0,23,15.5192451477 +84,SPOON,SUM,0,0,0,0,10,5,28,22.8591759205 +84,,SUM,0,0,0,0,10,6,51,46.4884490967 +84,,,,,,,,,, +85,,,,,,,,,, +85,BOWL,SUM,0,0,0,0,8,8,20,18.5176510811 +85,CUP,SUM,0,0,0,0,0,0,2,5.8213839531 +85,SPOON,SUM,0,0,0,0,0,2,9,12.9672119617 +85,,SUM,0,0,0,0,8,10,31,37.3062469959 +85,,,,,,,,,, +86,,,,,,,,,, +86,BOWL,SUM,0,0,0,0,0,1,43,17.2407739162 +86,CUP,SUM,0,0,0,0,0,2,25,10.7536950111 +86,SPOON,SUM,0,0,0,0,2,8,4,14.8476498127 +86,,SUM,0,0,0,0,2,11,72,42.8421187401 +86,,,,,,,,,, +87,,,,,,,,,, +87,BOWL,SUM,0,0,0,0,8,1,20,17.003360033 +87,CUP,SUM,0,0,0,0,0,1,11,9.058161974 +87,SPOON,SUM,0,0,0,0,0,2,4,12.9930310249 +87,,SUM,0,0,0,0,8,4,35,39.0545530319 +87,,,,,,,,,, +88,,,,,,,,,, +88,BOWL,SUM,0,0,0,0,0,0,4,8.7637939453 +88,CUP,SUM,0,0,0,0,0,0,10,8.2956438065 +88,SPOON,SUM,0,0,0,0,8,4,21,22.1916399002 +88,,SUM,0,0,0,0,8,4,35,39.251077652 +88,,,,,,,,,, +89,,,,,,,,,, +89,BOWL,SUM,0,0,0,0,0,1,5,10.2421908379 +89,CUP,SUM,0,0,0,0,0,0,35,21.5128278732 +89,SPOON,SUM,0,0,0,0,0,1,9,13.2498879433 +89,,SUM,0,0,0,0,0,2,49,45.0049066544 +89,,,,,,,,,, +90,,,,,,,,,, +90,BOWL,SUM,0,0,0,0,0,3,0,7.7414979935 +90,CUP,SUM,0,0,0,0,0,0,2,6.3719689846 +90,SPOON,SUM,0,0,0,0,0,8,40,19.277338028 +90,,SUM,0,0,0,0,0,11,42,33.390805006 +90,,,,,,,,,, +91,,,,,,,,,, +91,BOWL,SUM,0,0,0,0,0,0,0,8.55316782 +91,CUP,SUM,0,0,0,0,8,4,6,13.5152390003 +91,SPOON,SUM,0,0,0,0,0,2,4,11.0995769501 +91,,SUM,0,0,0,0,8,6,10,33.1679837704 +91,,,,,,,,,, +92,,,,,,,,,, +92,BOWL,SUM,0,0,0,0,0,3,8,10.5328698158 +92,CUP,SUM,1,0,0,1,0,1,51,0 +92,SPOON,SUM,0,0,0,0,0,1,2,12.5029761791 +92,,SUM,1,0,0,1,0,5,61,23.0358459949 +92,,,,,,,,,, +93,,,,,,,,,, +93,BOWL,SUM,0,0,0,0,8,3,0,15.2488288879 +93,CUP,SUM,0,0,0,0,0,0,8,8.2403371334 +93,SPOON,SUM,0,0,0,0,8,2,4,19.1321129799 +93,,SUM,0,0,0,0,16,5,12,42.6212790012 +93,,,,,,,,,, +94,,,,,,,,,, +94,BOWL,SUM,0,0,0,0,8,1,4,12.220995903 +94,CUP,SUM,0,0,0,0,8,0,24,17.9365642071 +94,SPOON,SUM,0,0,0,0,8,0,0,16.4863669872 +94,,SUM,0,0,0,0,24,1,28,46.6439270973 +94,,,,,,,,,, +95,,,,,,,,,, +95,BOWL,SUM,1,0,1,0,2,33,200,0 +95,CUP,SUM,1,0,0,1,0,1,51,0 +95,SPOON,SUM,0,0,0,0,0,0,5,13.3435490131 +95,,SUM,2,0,1,1,2,34,256,13.3435490131 +95,,,,,,,,,, +96,,,,,,,,,, +96,BOWL,SUM,0,0,0,0,8,3,4,15.5968999863 +96,CUP,SUM,1,0,0,1,0,0,51,0 +96,SPOON,SUM,0,0,0,0,8,2,4,17.4821028709 +96,,SUM,1,0,0,1,16,5,59,33.0790028572 +96,,,,,,,,,, +97,,,,,,,,,, +97,BOWL,SUM,0,0,0,0,0,9,20,13.0357921124 +97,CUP,SUM,0,0,0,0,0,0,6,7.1944391727 +97,SPOON,SUM,0,0,0,0,0,1,0,11.7848310471 +97,,SUM,0,0,0,0,0,10,26,32.0150623322 +97,,,,,,,,,, +98,,,,,,,,,, +98,BOWL,SUM,0,0,0,0,0,4,16,11.0560541153 +98,CUP,SUM,0,0,0,0,8,1,14,14.4293959141 +98,SPOON,SUM,0,0,0,0,12,0,4,17.3383479118 +98,,SUM,0,0,0,0,20,5,34,42.8237979412 +98,,,,,,,,,, +99,,,,,,,,,, +99,BOWL,SUM,0,0,0,0,24,12,60,36.6914620399 +99,CUP,SUM,0,0,0,0,0,1,2,6.1274399757 +99,SPOON,SUM,0,0,0,0,0,1,0,11.5757060051 +99,,SUM,0,0,0,0,24,14,62,54.3946080208 +99,,,,,,,,,, +100,,,,,,,,,, +100,BOWL,SUM,0,0,0,0,0,1,22,12.0083909035 +100,CUP,SUM,0,0,0,0,0,0,23,14.5507588387 +100,SPOON,SUM,0,0,0,0,0,3,12,14.1430220604 +100,,SUM,0,0,0,0,0,4,57,40.7021718025 +100,,,,,,,,,, +101,,,,,,,,,, +101,BOWL,SUM,0,0,0,0,8,9,64,24.7273309231 +101,CUP,SUM,0,0,0,0,0,0,7,8.2402009964 +101,SPOON,SUM,0,0,0,0,0,1,12,14.5651919842 +101,,SUM,0,0,0,0,8,10,83,47.5327239037 +101,,,,,,,,,, +102,,,,,,,,,, +102,BOWL,SUM,0,0,0,0,0,2,16,11.9253380299 +102,CUP,SUM,0,0,0,0,8,2,10,13.8237080574 +102,SPOON,SUM,0,0,0,0,0,2,13,14.07980299 +102,,SUM,0,0,0,0,8,6,39,39.8288490772 +102,,,,,,,,,, +103,,,,,,,,,, +103,BOWL,SUM,0,0,0,0,8,0,8,14.3617329597 +103,CUP,SUM,0,0,0,0,0,0,6,6.8497700691 +103,SPOON,SUM,0,0,0,0,0,3,6,13.0906131268 +103,,SUM,0,0,0,0,8,3,20,34.3021161556 +103,,,,,,,,,, +104,,,,,,,,,, +104,BOWL,SUM,0,0,0,0,0,2,18,11.7847719193 +104,CUP,SUM,0,0,0,0,8,0,12,13.5458579063 +104,SPOON,SUM,0,0,0,0,8,0,7,18.5574350357 +104,,SUM,0,0,0,0,16,2,37,43.8880648613 +104,,,,,,,,,, +105,,,,,,,,,, +105,BOWL,SUM,0,0,0,0,0,0,4,8.9500148296 +105,CUP,SUM,0,0,0,0,0,0,14,9.5944209099 +105,SPOON,SUM,0,0,0,0,0,1,4,12.2550759315 +105,,SUM,0,0,0,0,0,1,22,30.7995116711 +105,,,,,,,,,, +106,,,,,,,,,, +106,BOWL,SUM,0,0,0,0,0,1,8,10.411711216 +106,CUP,SUM,1,0,0,1,0,2,51,0 +106,SPOON,SUM,0,0,0,0,0,0,3,13.0440971851 +106,,SUM,1,0,0,1,0,3,62,23.4558084011 +106,,,,,,,,,, +107,,,,,,,,,, +107,BOWL,SUM,0,0,0,0,0,1,0,8.0925650597 +107,CUP,SUM,0,0,0,0,16,1,9,18.0357670784 +107,SPOON,SUM,0,0,0,0,0,1,4,10.9184751511 +107,,SUM,0,0,0,0,16,3,13,37.0468072891 +107,,,,,,,,,, +108,,,,,,,,,, +108,BOWL,SUM,0,0,0,0,0,7,17,12.3746919632 +108,CUP,SUM,0,0,0,0,0,0,2,5.2872600555 +108,SPOON,SUM,0,0,0,0,16,1,2,23.4880230427 +108,,SUM,0,0,0,0,16,8,21,41.1499750614 +108,,,,,,,,,, +109,,,,,,,,,, +109,BOWL,SUM,0,0,0,0,16,6,0,20.8347079754 +109,CUP,SUM,0,0,0,0,12,0,20,19.8371601105 +109,SPOON,SUM,0,0,0,0,0,3,0,12.4667270184 +109,,SUM,0,0,0,0,28,9,20,53.1385951042 +109,,,,,,,,,, +110,,,,,,,,,, +110,BOWL,SUM,0,0,0,0,8,2,4,14.1782639027 +110,CUP,SUM,0,0,0,0,12,0,33,25.2274668217 +110,SPOON,SUM,0,0,0,0,0,2,4,14.3193778992 +110,,SUM,0,0,0,0,20,4,41,53.7251086235 +110,,,,,,,,,, +111,,,,,,,,,, +111,BOWL,SUM,0,0,0,0,0,0,12,11.3112809658 +111,CUP,SUM,0,0,0,0,0,1,23,13.6705889702 +111,SPOON,SUM,0,0,0,0,4,2,12,15.8655180931 +111,,SUM,0,0,0,0,4,3,47,40.8473880291 +111,,,,,,,,,, +112,,,,,,,,,, +112,BOWL,SUM,0,0,0,0,0,1,8,10.693434 +112,CUP,SUM,0,0,0,0,0,0,8,5.8392679691 +112,SPOON,SUM,0,0,0,0,8,0,4,16.6769771576 +112,,SUM,0,0,0,0,8,1,20,33.2096791267 +112,,,,,,,,,, +113,,,,,,,,,, +113,BOWL,SUM,0,0,0,0,0,0,4,9.2254889011 +113,CUP,SUM,0,0,0,0,0,0,2,6.421859026 +113,SPOON,SUM,0,0,0,0,0,0,3,12.5002179146 +113,,SUM,0,0,0,0,0,0,9,28.1475658417 +113,,,,,,,,,, +114,,,,,,,,,, +114,BOWL,SUM,0,0,0,0,0,3,5,10.2243359089 +114,CUP,SUM,0,0,0,0,0,0,24,13.9054808617 +114,SPOON,SUM,0,0,0,0,0,0,4,13.4303679466 +114,,SUM,0,0,0,0,0,3,33,37.5601847172 +114,,,,,,,,,, +115,,,,,,,,,, +115,BOWL,SUM,0,0,0,0,8,3,4,15.6738481522 +115,CUP,SUM,0,0,0,0,0,2,8,7.4693028927 +115,SPOON,SUM,0,0,0,0,0,4,10,14.2961120605 +115,,SUM,0,0,0,0,8,9,22,37.4392631054 +115,,,,,,,,,, +116,,,,,,,,,, +116,BOWL,SUM,0,0,0,0,8,1,0,12.5245850086 +116,CUP,SUM,0,0,0,0,0,0,2,6.3411231041 +116,SPOON,SUM,0,0,0,0,0,2,5,14.8331520557 +116,,SUM,0,0,0,0,8,3,7,33.6988601685 +116,,,,,,,,,, +117,,,,,,,,,, +117,BOWL,SUM,0,0,0,0,0,0,6,9.7563149929 +117,CUP,SUM,0,0,0,0,0,0,13,9.3697500229 +117,SPOON,SUM,0,0,0,0,12,1,8,19.0869660378 +117,,SUM,0,0,0,0,12,1,27,38.2130310535 +117,,,,,,,,,, +118,,,,,,,,,, +118,BOWL,SUM,0,0,0,0,8,2,0,13.8831861019 +118,CUP,SUM,0,0,0,0,0,1,58,29.1042790413 +118,SPOON,SUM,0,0,0,0,0,4,8,13.3753929138 +118,,SUM,0,0,0,0,8,7,66,56.362858057 +118,,,,,,,,,, +119,,,,,,,,,, +119,BOWL,SUM,0,0,0,0,8,0,8,14.5605208874 +119,CUP,SUM,0,0,0,0,0,0,56,27.8634700775 +119,SPOON,SUM,0,0,0,0,0,3,12,14.3195030689 +119,,SUM,0,0,0,0,8,3,76,56.7434940338 +119,,,,,,,,,, +120,,,,,,,,,, +120,BOWL,SUM,0,0,0,0,8,4,24,18.0126640797 +120,CUP,SUM,0,0,0,0,8,2,10,11.1947000027 +120,SPOON,SUM,0,0,0,0,0,3,8,14.6660399437 +120,,SUM,0,0,0,0,16,9,42,43.873404026 +120,,,,,,,,,, +121,,,,,,,,,, +121,BOWL,SUM,0,0,0,0,8,9,38,21.6842601299 +121,CUP,SUM,0,0,0,0,8,0,48,33.0541598797 +121,SPOON,SUM,0,0,0,0,0,1,1,12.4957809448 +121,,SUM,0,0,0,0,16,10,87,67.2342009544 +121,,,,,,,,,, +122,,,,,,,,,, +122,BOWL,SUM,0,0,0,0,0,1,0,7.9808371067 +122,CUP,SUM,0,0,0,0,0,7,12,10.9543647766 +122,SPOON,SUM,0,0,0,0,0,9,20,16.0787661076 +122,,SUM,0,0,0,0,0,17,32,35.0139679909 +122,,,,,,,,,, +123,,,,,,,,,, +123,BOWL,SUM,0,0,0,0,0,0,4,9.2796809673 +123,CUP,SUM,0,0,0,0,0,0,3,6.6788079739 +123,SPOON,SUM,0,0,0,0,0,0,0,11.9989769459 +123,,SUM,0,0,0,0,0,0,7,27.9574658871 +123,,,,,,,,,, +124,,,,,,,,,, +124,BOWL,SUM,0,0,0,0,0,1,3,9.0994338989 +124,CUP,SUM,0,0,0,0,0,2,13,8.0218889713 +124,SPOON,SUM,0,0,0,0,14,1,0,18.1245131493 +124,,SUM,0,0,0,0,14,4,16,35.2458360195 +124,,,,,,,,,, +125,,,,,,,,,, +125,BOWL,SUM,0,0,0,0,8,4,10,15.1260309219 +125,CUP,SUM,1,0,0,1,0,0,51,0 +125,SPOON,SUM,0,0,0,0,0,2,1,12.4692161083 +125,,SUM,1,0,0,1,8,6,62,27.5952470303 +125,,,,,,,,,, +126,,,,,,,,,, +126,BOWL,SUM,0,0,0,0,0,0,4,8.9022769928 +126,CUP,SUM,0,0,0,0,8,1,7,12.0384180546 +126,SPOON,SUM,0,0,0,0,0,1,17,15.4897298813 +126,,SUM,0,0,0,0,8,2,28,36.4304249287 +126,,,,,,,,,, +127,,,,,,,,,, +127,BOWL,SUM,0,0,0,0,16,5,25,25.5456049442 +127,CUP,SUM,0,0,0,0,0,0,2,6.3506169319 +127,SPOON,SUM,0,0,0,0,0,2,8,14.0825178623 +127,,SUM,0,0,0,0,16,7,35,45.9787397385 +127,,,,,,,,,, +128,,,,,,,,,, +128,BOWL,SUM,0,0,0,0,8,0,0,13.6055428982 +128,CUP,SUM,0,0,0,0,0,0,11,7.2218708992 +128,SPOON,SUM,0,0,0,0,12,2,13,21.9605169296 +128,,SUM,0,0,0,0,20,2,24,42.787930727 +128,,,,,,,,,, +129,,,,,,,,,, +129,BOWL,SUM,0,0,0,0,0,4,8,10.4597380161 +129,CUP,SUM,0,0,0,0,0,1,6,7.4040448666 +129,SPOON,SUM,0,0,0,0,0,0,4,12.7344679832 +129,,SUM,0,0,0,0,0,5,18,30.5982508659 +129,,,,,,,,,, +130,,,,,,,,,, +130,BOWL,SUM,0,0,0,0,8,39,28,25.3400630951 +130,CUP,SUM,0,0,0,0,0,1,25,11.8041489124 +130,SPOON,SUM,0,0,0,0,0,2,38,19.5672988892 +130,,SUM,0,0,0,0,8,42,91,56.7115108967 +130,,,,,,,,,, +131,,,,,,,,,, +131,BOWL,SUM,0,0,0,0,0,3,28,15.1785299778 +131,CUP,SUM,0,0,0,0,0,1,2,6.1923620701 +131,SPOON,SUM,0,0,0,0,12,1,16,20.9050199986 +131,,SUM,0,0,0,0,12,5,46,42.2759120464 +131,,,,,,,,,, +132,,,,,,,,,, +132,BOWL,SUM,0,0,0,0,16,9,84,35.9350368977 +132,CUP,SUM,0,0,0,0,0,0,2,6.9105029106 +132,SPOON,SUM,0,0,0,0,6,1,4,15.5001299381 +132,,SUM,0,0,0,0,22,10,90,58.3456697464 +132,,,,,,,,,, +133,,,,,,,,,, +133,BOWL,SUM,0,0,0,0,0,4,0,8.9088990688 +133,CUP,SUM,0,0,0,0,8,0,10,12.6752429008 +133,SPOON,SUM,0,0,0,0,0,1,4,14.2103469372 +133,,SUM,0,0,0,0,8,5,14,35.7944889069 +133,,,,,,,,,, +134,,,,,,,,,, +134,BOWL,SUM,0,0,0,0,0,0,4,8.4709811211 +134,CUP,SUM,0,0,0,0,8,0,7,11.6575818062 +134,SPOON,SUM,0,0,0,0,0,2,6,13.2543981075 +134,,SUM,0,0,0,0,8,2,17,33.3829610348 +134,,,,,,,,,, +135,,,,,,,,,, +135,BOWL,SUM,0,0,0,0,20,0,2,18.3413441181 +135,CUP,SUM,1,0,0,1,0,1,51,0 +135,SPOON,SUM,0,0,0,0,16,0,0,21.3253350258 +135,,SUM,1,0,0,1,36,1,53,39.6666791439 +135,,,,,,,,,, +136,,,,,,,,,, +136,BOWL,SUM,0,0,0,0,0,1,0,7.4753768444 +136,CUP,SUM,0,0,0,0,24,2,4,20.9931070805 +136,SPOON,SUM,0,0,0,0,8,6,2,21.8333170414 +136,,SUM,0,0,0,0,32,9,6,50.3018009663 +136,,,,,,,,,, +137,,,,,,,,,, +137,BOWL,SUM,0,0,0,0,0,0,0,7.3021202087 +137,CUP,SUM,0,0,0,0,0,2,34,20.8928618431 +137,SPOON,SUM,0,0,0,0,16,0,4,20.5497660637 +137,,SUM,0,0,0,0,16,2,38,48.7447481155 +137,,,,,,,,,, +138,,,,,,,,,, +138,BOWL,SUM,0,0,0,0,12,3,20,18.7516279221 +138,CUP,SUM,0,0,0,0,0,0,2,6.5947680473 +138,SPOON,SUM,0,0,0,0,0,0,0,12.3777370453 +138,,SUM,0,0,0,0,12,3,22,37.7241330147 +138,,,,,,,,,, +139,,,,,,,,,, +139,BOWL,SUM,0,0,0,0,6,0,1,11.0141379833 +139,CUP,SUM,0,0,0,0,0,0,8,7.5752339363 +139,SPOON,SUM,0,0,0,0,0,0,8,13.225288868 +139,,SUM,0,0,0,0,6,0,17,31.8146607876 +139,,,,,,,,,, +140,, +140,BOWL,SUM,0,0,0,0,0,1,18,13.254175901412964 +140,CUP,SUM,0,0,0,0,0,0,17,9.571273803710938 +140,SPOON,SUM,0,0,0,0,20,0,0,18.191028833389282 +140,,SUM,0,0,0,0,20,1,35,41.016478538513184 +140,, +141,, +141,BOWL,SUM,0,0,0,0,0,1,4,7.161181926727295 +141,CUP,SUM,0,0,0,0,20,2,6,12.787253856658936 +141,SPOON,SUM,0,0,0,0,12,8,27,19.700588941574097 +141,,SUM,0,0,0,0,32,11,37,39.64902472496033 +141,, +142,, +142,BOWL,SUM,0,0,0,0,0,1,16,9.4899001121521 +142,CUP,SUM,0,0,0,0,0,0,2,4.077615022659302 +142,SPOON,SUM,0,0,0,0,16,2,3,16.176270961761475 +142,,SUM,0,0,0,0,16,3,21,29.743786096572876 +142,, +143,, +143,BOWL,SUM,0,0,0,0,8,0,8,10.062410116195679 +143,CUP,SUM,0,0,0,0,0,3,18,6.179131031036377 +143,SPOON,SUM,0,0,0,0,0,0,4,9.82832407951355 +143,,SUM,0,0,0,0,8,3,30,26.069865226745605 +143,, +144,, +144,BOWL,SUM,0,0,0,0,8,2,32,14.71783185005188 +144,CUP,SUM,0,0,0,0,0,0,22,9.784318923950195 +144,SPOON,SUM,0,0,0,0,0,4,17,12.861054182052612 +144,,SUM,0,0,0,0,8,6,71,37.36320495605469 +144,, +145,, +145,BOWL,SUM,0,0,0,0,0,4,3,6.748347997665405 +145,CUP,SUM,0,0,0,0,8,1,10,9.300237894058228 +145,SPOON,SUM,0,0,0,0,32,2,28,28.285474061965942 +145,,SUM,0,0,0,0,40,7,41,44.334059953689575 +145,, +146,, +146,BOWL,SUM,0,0,0,0,0,1,8,7.715286016464233 +146,CUP,SUM,0,0,0,0,0,0,4,4.1249189376831055 +146,SPOON,SUM,0,0,0,0,16,0,0,15.206550121307373 +146,,SUM,0,0,0,0,16,1,12,27.046755075454712 +146,, +147,, +147,BOWL,SUM,0,0,0,0,0,1,1,6.765604019165039 +147,CUP,SUM,0,0,0,0,48,3,2,22.053157806396484 +147,SPOON,SUM,0,0,0,0,8,0,2,13.193656921386719 +147,,SUM,0,0,0,0,56,4,5,42.01241874694824 +147,, +148,, +148,BOWL,SUM,0,0,0,0,0,0,0,6.157914876937866 +148,CUP,SUM,0,0,0,0,8,0,41,24.0885488986969 +148,SPOON,SUM,0,0,0,0,0,2,16,12.415299892425537 +148,,SUM,0,0,0,0,8,2,57,42.6617636680603 +148,, +149,, +149,BOWL,SUM,0,0,0,0,0,2,2,6.2880730628967285 +149,CUP,SUM,0,0,0,0,0,3,44,22.827225923538208 +149,SPOON,SUM,0,0,0,0,0,0,5,10.388996124267578 +149,,SUM,0,0,0,0,0,5,51,39.504295110702515 +149,, +150,, +150,BOWL,SUM,0,0,0,0,0,0,0,6.215072154998779 +150,CUP,SUM,0,0,0,0,0,2,2,4.0801169872283936 +150,SPOON,SUM,0,0,0,0,0,0,6,10.893266916275024 +150,,SUM,0,0,0,0,0,2,8,21.188456058502197 +150,, +151,, +151,BOWL,SUM,0,0,0,0,0,2,13,8.835331916809082 +151,CUP,SUM,0,0,0,0,0,1,12,7.128451824188232 +151,SPOON,SUM,0,0,0,0,0,0,2,10.250869989395142 +151,,SUM,0,0,0,0,0,3,27,26.214653730392456 +151,, +152,, +152,BOWL,SUM,0,0,0,0,0,12,21,10.780499935150146 +152,CUP,SUM,1,0,0,1,24,1,67,0.0 +152,SPOON,SUM,0,0,0,0,0,2,4,10.329346895217896 +152,,SUM,1,0,0,1,24,15,92,21.109846830368042 +152,, +153,, +153,BOWL,SUM,0,0,0,0,0,0,4,6.767704963684082 +153,CUP,SUM,0,0,0,0,12,3,11,10.795370101928711 +153,SPOON,SUM,0,0,0,0,8,1,0,12.345530033111572 +153,,SUM,0,0,0,0,20,4,15,29.908605098724365 +153,, +154,, +154,BOWL,SUM,0,0,0,0,8,32,184,45.51298785209656 +154,CUP,SUM,0,0,0,0,0,1,7,4.8926310539245605 +154,SPOON,SUM,0,0,0,0,0,2,0,9.563616037368774 +154,,SUM,0,0,0,0,8,35,191,59.96923494338989 +154,, +155,, +155,BOWL,SUM,0,0,0,0,0,3,48,15.947817087173462 +155,CUP,SUM,0,0,0,0,0,0,2,4.223170042037964 +155,SPOON,SUM,0,0,0,0,0,0,0,9.873634099960327 +155,,SUM,0,0,0,0,0,3,50,30.044621229171753 +155,, +156,, +156,BOWL,SUM,0,0,0,0,0,2,11,8.886243104934692 +156,CUP,SUM,0,0,0,0,0,9,29,17.986714124679565 +156,SPOON,SUM,0,0,0,0,0,6,32,16.05168104171753 +156,,SUM,0,0,0,0,0,17,72,42.92463827133179 +156,, +157,, +157,BOWL,SUM,0,0,0,0,0,1,22,10.633052110671997 +157,CUP,SUM,0,0,0,0,12,2,24,18.14969515800476 +157,SPOON,SUM,0,0,0,0,8,0,5,14.100103855133057 +157,,SUM,0,0,0,0,20,3,51,42.882851123809814 +157,, +158,, +158,BOWL,SUM,0,0,0,0,0,1,5,7.6548779010772705 +158,CUP,SUM,0,0,0,0,0,0,18,8.47749400138855 +158,SPOON,SUM,0,0,0,0,0,0,9,11.35426378250122 +158,,SUM,0,0,0,0,0,1,32,27.48663568496704 +158,, +159,, +159,BOWL,SUM,0,0,0,0,0,17,60,18.388856887817383 +159,CUP,SUM,1,0,0,1,0,0,51,0.0 +159,SPOON,SUM,0,0,0,0,10,4,16,17.673365831375122 +159,,SUM,1,0,0,1,10,21,127,36.062222719192505 +159,, +160,, +160,BOWL,SUM,0,0,0,0,0,0,4,7.114962816238403 +160,CUP,SUM,0,0,0,0,16,2,7,14.026718854904175 +160,SPOON,SUM,0,0,0,0,0,2,18,13.236496925354004 +160,,SUM,0,0,0,0,16,4,29,34.37817859649658 +160,, +161,, +161,BOWL,SUM,0,0,0,0,0,0,0,6.460599899291992 +161,CUP,SUM,0,0,0,0,0,0,15,9.470106840133667 +161,SPOON,SUM,0,0,0,0,0,1,4,11.27053713798523 +161,,SUM,0,0,0,0,0,1,19,27.20124387741089 +161,, +162,, +162,BOWL,SUM,0,0,0,0,8,9,28,15.769519090652466 +162,CUP,SUM,1,0,0,1,0,2,59,0.0 +162,SPOON,SUM,0,0,0,0,24,15,33,26.915421962738037 +162,,SUM,1,0,0,1,32,26,120,42.6849410533905 +162,, +163,, +163,BOWL,SUM,0,0,0,0,0,3,36,13.530049800872803 +163,CUP,SUM,0,0,0,0,8,1,11,9.812688112258911 +163,SPOON,SUM,0,0,0,0,0,2,9,12.086623907089233 +163,,SUM,0,0,0,0,8,6,56,35.42936182022095 +163,, +164,, +164,BOWL,SUM,0,0,0,0,0,6,8,8.719542980194092 +164,CUP,SUM,0,0,0,0,0,1,2,5.003866910934448 +164,SPOON,SUM,0,0,0,0,2,2,4,12.01035189628601 +164,,SUM,0,0,0,0,2,9,14,25.73376178741455 +164,, +165,, +165,BOWL,SUM,0,0,0,0,0,0,1,7.27709698677063 +165,CUP,SUM,0,0,0,0,16,0,13,16.034082889556885 +165,SPOON,SUM,0,0,0,0,8,0,13,17.058897018432617 +165,,SUM,0,0,0,0,24,0,27,40.37007689476013 +165,, +166,, +166,BOWL,SUM,0,0,0,0,0,1,0,7.129940032958984 +166,CUP,SUM,1,0,0,1,0,0,66,0.0 +166,SPOON,SUM,0,0,0,0,0,0,5,12.420130968093872 +166,,SUM,1,0,0,1,0,1,71,19.550071001052856 +166,, +167,, +167,BOWL,SUM,0,0,0,0,8,2,10,14.8211510181427 +167,CUP,SUM,0,0,0,0,6,0,5,7.1777119636535645 +167,SPOON,SUM,0,0,0,0,8,0,0,15.208556890487671 +167,,SUM,0,0,0,0,22,2,15,37.207419872283936 +167,, +168,, +168,BOWL,SUM,0,0,0,0,0,1,20,11.378844022750854 +168,CUP,SUM,0,0,0,0,0,2,18,10.42188286781311 +168,SPOON,SUM,0,0,0,0,0,2,0,12.403717994689941 +168,,SUM,0,0,0,0,0,5,38,34.204444885253906 +168,, +169,, +169,BOWL,SUM,0,0,0,0,0,0,0,6.724272966384888 +169,CUP,SUM,0,0,0,0,8,0,42,27.550779819488525 +169,SPOON,SUM,0,0,0,0,0,2,4,12.48380184173584 +169,,SUM,0,0,0,0,8,2,46,46.75885462760925 +169,, +170,, +170,BOWL,SUM,0,0,0,0,0,18,176,43.08479404449463 +170,CUP,SUM,0,0,0,0,12,1,6,11.928001165390015 +170,SPOON,SUM,0,0,0,0,0,4,8,14.04230523109436 +170,,SUM,0,0,0,0,12,23,190,69.055100440979 +170,, +171,, +171,BOWL,SUM,0,0,0,0,0,0,0,7.103800058364868 +171,CUP,SUM,0,0,0,0,0,0,43,24.20199489593506 +171,SPOON,SUM,0,0,0,0,0,0,0,11.257971048355103 +171,,SUM,0,0,0,0,0,0,43,42.56376600265503 +171,, +172,, +172,BOWL,SUM,0,0,0,0,0,1,0,8.247311115264893 +172,CUP,SUM,0,0,0,0,0,0,7,6.958992004394531 +172,SPOON,SUM,0,0,0,0,0,12,47,22.10333514213562 +172,,SUM,0,0,0,0,0,13,54,37.309638261795044 +172,, +173,, +173,BOWL,SUM,0,0,0,0,0,0,3,8.831927061080933 +173,CUP,SUM,0,0,0,0,14,1,6,13.002228021621704 +173,SPOON,SUM,0,0,0,0,0,0,5,13.53925609588623 +173,,SUM,0,0,0,0,14,1,14,35.37341117858887 +173,, +174,, +174,BOWL,SUM,0,0,0,0,0,0,4,7.7121570110321045 +174,CUP,SUM,0,0,0,0,16,0,15,17.86798095703125 +174,SPOON,SUM,0,0,0,0,0,4,11,13.699587106704712 +174,,SUM,0,0,0,0,16,4,30,39.279725074768066 +174,, +175,, +175,BOWL,SUM,0,0,0,0,12,0,0,13.171783924102783 +175,CUP,SUM,0,0,0,0,8,2,21,15.858865022659302 +175,SPOON,SUM,0,0,0,0,0,0,0,11.365931034088135 +175,,SUM,0,0,0,0,20,2,21,40.39657998085022 +175,, +176,, +176,BOWL,SUM,0,0,0,0,0,6,84,25.74063801765442 +176,CUP,SUM,0,0,0,0,0,2,17,12.168338060379028 +176,SPOON,SUM,0,0,0,0,0,1,4,12.808663129806519 +176,,SUM,0,0,0,0,0,9,105,50.717639207839966 +176,, +177,, +177,BOWL,SUM,0,0,0,0,0,5,30,15.066643953323364 +177,CUP,SUM,0,0,0,0,8,3,33,21.876862049102783 +177,SPOON,SUM,0,0,0,0,8,5,4,17.279477834701538 +177,,SUM,0,0,0,0,16,13,67,54.222983837127686 +177,, +178,, +178,BOWL,SUM,0,0,0,0,0,0,1,8.524921894073486 +178,CUP,SUM,0,0,0,0,0,0,7,7.47367000579834 +178,SPOON,SUM,0,0,0,0,0,1,13,14.935644149780273 +178,,SUM,0,0,0,0,0,1,21,30.9342360496521 +178,, +179,, +179,BOWL,SUM,0,0,0,0,12,0,5,15.010004043579102 +179,CUP,SUM,1,0,0,1,8,0,51,0.0 +179,SPOON,SUM,0,0,0,0,16,3,4,21.171390056610107 +179,,SUM,1,0,0,1,36,3,60,36.18139410018921 +179,, +180,, +180,BOWL,SUM,0,0,0,0,0,6,41,15.293370008468628 +180,CUP,SUM,0,0,0,0,0,0,6,5.187832832336426 +180,SPOON,SUM,0,0,0,0,0,2,0,12.558840990066528 +180,,SUM,0,0,0,0,0,8,47,33.04004383087158 +180,, +181,, +181,BOWL,SUM,0,0,0,0,0,4,18,10.43586277961731 +181,CUP,SUM,0,0,0,0,8,5,54,37.44101595878601 +181,SPOON,SUM,0,0,0,0,28,4,0,28.4790620803833 +181,,SUM,0,0,0,0,36,13,72,76.35594081878662 +181,, +182,, +182,BOWL,SUM,1,0,1,0,4,22,196,0.0 +182,CUP,SUM,1,0,0,1,24,2,51,0.0 +182,SPOON,SUM,0,0,0,0,24,7,1,28.580919981002808 +182,,SUM,2,0,1,1,52,31,248,28.580919981002808 +182,, +183,, +183,BOWL,SUM,0,0,0,0,0,0,0,8.964266061782837 +183,CUP,SUM,0,0,0,0,0,0,2,4.822875022888184 +183,SPOON,SUM,0,0,0,0,0,0,2,12.995568990707397 +183,,SUM,0,0,0,0,0,0,4,26.782710075378418 +183,, +184,, +184,BOWL,SUM,0,0,0,0,16,0,0,15.91485595703125 +184,CUP,SUM,0,0,0,0,12,0,2,12.426185131072998 +184,SPOON,SUM,0,0,0,0,0,1,0,11.551842212677002 +184,,SUM,0,0,0,0,28,1,2,39.89288330078125 +184,, +185,, +185,BOWL,SUM,0,0,0,0,8,3,21,18.634868144989014 +185,CUP,SUM,0,0,0,0,0,3,21,11.912768125534058 +185,SPOON,SUM,0,0,0,0,0,2,13,15.096560001373291 +185,,SUM,0,0,0,0,8,8,55,45.64419627189636 +185,, +186,, +186,BOWL,SUM,0,0,0,0,0,0,8,9.63208293914795 +186,CUP,SUM,0,0,0,0,0,2,23,14.247983932495117 +186,SPOON,SUM,0,0,0,0,0,1,0,11.220720052719116 +186,,SUM,0,0,0,0,0,3,31,35.10078692436218 +186,, +187,, +187,BOWL,SUM,0,0,0,0,0,4,10,10.845638990402222 +187,CUP,SUM,0,0,0,0,0,2,7,7.414214134216309 +187,SPOON,SUM,0,0,0,0,0,1,10,13.811771154403687 +187,,SUM,0,0,0,0,0,7,27,32.07162427902222 +187,, +188,, +188,BOWL,SUM,0,0,0,0,0,2,5,10.074436902999878 +188,CUP,SUM,0,0,0,0,0,1,2,5.182523012161255 +188,SPOON,SUM,0,0,0,0,0,1,4,10.69654393196106 +188,,SUM,0,0,0,0,0,4,11,25.953503847122192 +188,, +189,, +189,BOWL,SUM,0,0,0,0,0,3,8,9.701226949691772 +189,CUP,SUM,0,0,0,0,0,1,3,5.82650089263916 +189,SPOON,SUM,0,0,0,0,0,10,36,19.431666135787964 +189,,SUM,0,0,0,0,0,14,47,34.9593939781189 +189,, +190,, +190,BOWL,SUM,0,0,0,0,0,2,16,11.778557062149048 +190,CUP,SUM,0,0,0,0,0,2,6,6.005945920944214 +190,SPOON,SUM,0,0,0,0,0,1,16,14.504930019378662 +190,,SUM,0,0,0,0,0,5,38,32.289433002471924 +190,, +191,, +191,BOWL,SUM,0,0,0,0,0,11,60,20.568645000457764 +191,CUP,SUM,0,0,0,0,16,1,33,28.54251194000244 +191,SPOON,SUM,0,0,0,0,0,1,0,10.579431056976318 +191,,SUM,0,0,0,0,16,13,93,59.69058799743652 +191,, +192,, +192,BOWL,SUM,0,0,0,0,8,2,5,13.32099199295044 +192,CUP,SUM,0,0,0,0,0,1,8,5.457234859466553 +192,SPOON,SUM,0,0,0,0,0,0,3,12.46645212173462 +192,,SUM,0,0,0,0,8,3,16,31.24467897415161 +192,, +193,, +193,BOWL,SUM,0,0,0,0,0,0,5,9.680346012115479 +193,CUP,SUM,0,0,0,0,8,10,65,43.389946937561035 +193,SPOON,SUM,0,0,0,0,0,2,33,18.018511056900024 +193,,SUM,0,0,0,0,8,12,103,71.08880400657654 +193,, +194,, +194,BOWL,SUM,0,0,0,0,0,0,0,8.606698036193848 +194,CUP,SUM,0,0,0,0,0,1,18,11.422364950180054 +194,SPOON,SUM,0,0,0,0,0,2,5,13.22788119316101 +194,,SUM,0,0,0,0,0,3,23,33.25694417953491 +194,, +195,, +195,BOWL,SUM,0,0,0,0,0,0,12,10.619855880737305 +195,CUP,SUM,0,0,0,0,0,0,26,16.53536105155945 +195,SPOON,SUM,0,0,0,0,0,0,2,13.03675389289856 +195,,SUM,0,0,0,0,0,0,40,40.19197082519531 +195,, +196,, +196,BOWL,SUM,0,0,0,0,8,0,0,12.839002847671509 +196,CUP,SUM,0,0,0,0,0,4,8,8.348278045654297 +196,SPOON,SUM,0,0,0,0,0,0,0,12.004043817520142 +196,,SUM,0,0,0,0,8,4,8,33.19132471084595 +196,, +197,, +197,BOWL,SUM,0,0,0,0,32,1,0,29.206094980239868 +197,CUP,SUM,0,0,0,0,16,0,2,16.527390956878662 +197,SPOON,SUM,0,0,0,0,0,0,1,12.641416072845459 +197,,SUM,0,0,0,0,48,1,3,58.37490200996399 +197,, +198,, +198,BOWL,SUM,0,0,0,0,0,1,24,12.990669965744019 +198,CUP,SUM,0,0,0,0,0,2,47,27.09940791130066 +198,SPOON,SUM,0,0,0,0,0,4,10,15.077844858169556 +198,,SUM,0,0,0,0,0,7,81,55.16792273521423 +198,, +199,, +199,BOWL,SUM,0,0,0,0,8,0,8,14.773518085479736 +199,CUP,SUM,1,0,0,1,8,0,57,0.0 +199,SPOON,SUM,0,0,0,0,0,0,9,14.410346031188965 +199,,SUM,1,0,0,1,16,0,74,29.1838641166687 +199,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/paper/2.Pr2VrSimLikeReal.csv b/cram_knowrob/cram_knowrob_vr/experiments/paper/2.Pr2VrSimLikeReal.csv new file mode 100644 index 0000000000..537167346c --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/paper/2.Pr2VrSimLikeReal.csv @@ -0,0 +1,303 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,7,2,14.1363930702 +0,CUP,SUM,0,0,0,0,0,16,7,9.6061439514 +0,SPOON,SUM,0,0,0,0,0,15,2,14.6411380768 +0,,SUM,0,0,0,0,0,38,11,38.3836750984 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,6,24,2,12.8219151497 +1,CUP,SUM,0,0,0,0,0,14,8,8.9827091694 +1,SPOON,SUM,0,0,0,0,2,461,0,38.4582269192 +1,,SUM,0,0,0,0,8,499,10,60.2628512383 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,0,6,0,10.0326869488 +2,CUP,SUM,1,0,0,1,4,209,53,0 +2,SPOON,SUM,0,0,0,0,4,443,0,38.5402178764 +2,,SUM,1,0,0,1,8,658,53,48.5729048252 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,2,53,4,14.6690118313 +3,CUP,SUM,0,0,0,0,14,89,36,54.1937630177 +3,SPOON,SUM,1,0,1,0,0,1596,0,0 +3,,SUM,1,0,1,0,16,1738,40,68.8627748489 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,2,42,2,13.0301728249 +4,CUP,SUM,0,0,0,0,0,14,8,11.4678850174 +4,SPOON,SUM,0,0,0,0,0,47,0,14.8949370384 +4,,SUM,0,0,0,0,2,103,10,39.3929948807 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,0,50,0,11.2852580547 +5,CUP,SUM,0,0,0,0,2,22,2,9.5451338291 +5,SPOON,SUM,0,0,0,0,0,1,0,13.3528020382 +5,,SUM,0,0,0,0,2,73,2,34.183193922 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,0,20,0,10.6854729652 +6,CUP,SUM,0,0,0,0,4,15,2,9.9713129997 +6,SPOON,SUM,0,0,0,0,0,82,2,17.5681900978 +6,,SUM,0,0,0,0,4,117,4,38.2249760628 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,0,72,4,14.4747130871 +7,CUP,SUM,0,0,0,0,0,22,4,9.1190140247 +7,SPOON,SUM,0,0,0,0,6,2,0,15.4525411129 +7,,SUM,0,0,0,0,6,96,8,39.0462682247 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,0,138,0,17.5052568913 +8,CUP,SUM,0,0,0,0,0,22,4,9.1790728569 +8,SPOON,SUM,0,0,0,0,0,380,0,34.4191539288 +8,,SUM,0,0,0,0,0,540,4,61.1034836769 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,0,33,0,10.7849910259 +9,CUP,SUM,0,0,0,0,0,7,6,8.788339138 +9,SPOON,SUM,0,0,0,0,2,100,2,19.7836039066 +9,,SUM,0,0,0,0,2,140,8,39.3569340706 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,162,0,19.2491078377 +10,CUP,SUM,0,0,0,0,0,11,0,8.8869690895 +10,SPOON,SUM,0,0,0,0,0,131,0,20.8581609726 +10,,SUM,0,0,0,0,0,304,0,48.9942378998 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,0,13,2,10.9315729141 +11,CUP,SUM,0,0,0,0,0,13,0,8.7731189728 +11,SPOON,SUM,0,0,0,0,0,5,0,13.6908209324 +11,,SUM,0,0,0,0,0,31,2,33.3955128193 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,126,574,0,94.5502750874 +12,CUP,SUM,0,0,0,0,0,23,0,9.23782897 +12,SPOON,SUM,0,0,0,0,0,7,0,14.1358120441 +12,,SUM,0,0,0,0,126,604,0,117.9239161015 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,0,13,1,12.392482996 +13,CUP,SUM,0,0,0,0,0,14,4,9.0737011433 +13,SPOON,SUM,0,0,0,0,0,13,4,15.9506180286 +13,,SUM,0,0,0,0,0,40,9,37.4168021679 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,0,82,16,23.8006970882 +14,CUP,SUM,0,0,0,0,2,15,1,9.7386481762 +14,SPOON,SUM,0,0,0,0,0,338,0,31.7641458511 +14,,SUM,0,0,0,0,2,435,17,65.3034911156 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,0,11,1,12.2888159752 +15,CUP,SUM,0,0,0,0,4,20,4,10.8996429443 +15,SPOON,SUM,0,0,0,0,2,369,0,34.5334498882 +15,,SUM,0,0,0,0,6,400,5,57.7219088078 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,30,4,12.8648250103 +16,CUP,SUM,0,0,0,0,0,11,2,8.5995140076 +16,SPOON,SUM,0,0,0,0,0,5,2,13.9635119438 +16,,SUM,0,0,0,0,0,46,8,35.4278509617 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,0,41,0,12.4151360989 +17,CUP,SUM,0,0,0,0,0,22,2,9.0861959457 +17,SPOON,SUM,0,0,0,0,10,142,0,24.3935010433 +17,,SUM,0,0,0,0,10,205,2,45.8948330879 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,0,38,0,12.3251099586 +18,CUP,SUM,0,0,0,0,0,35,2,9.3397119045 +18,SPOON,SUM,0,0,0,0,0,46,0,16.0619139671 +18,,SUM,0,0,0,0,0,119,2,37.7267358303 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,120,52,2,68.5458071232 +19,CUP,SUM,0,0,0,0,0,11,2,8.6570489407 +19,SPOON,SUM,0,0,0,0,2,25,0,15.1914508343 +19,,SUM,0,0,0,0,122,88,4,92.3943068981 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,0,65,1,15.0724570751 +20,CUP,SUM,0,0,0,0,0,12,3,11.6316359043 +20,SPOON,SUM,0,0,0,0,2,12,0,14.9098129272 +20,,SUM,0,0,0,0,2,89,4,41.6139059067 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,13,0,10.7170348167 +21,CUP,SUM,1,0,0,1,0,189,53,0 +21,SPOON,SUM,0,0,0,0,8,68,0,21.5375728607 +21,,SUM,1,0,0,1,8,270,53,32.2546076775 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,6,16,0,12.8987689018 +22,CUP,SUM,1,0,0,1,0,247,53,0 +22,SPOON,SUM,0,0,0,0,2,15,1,15.2817409039 +22,,SUM,1,0,0,1,8,278,54,28.1805098057 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,76,8,17.2984490395 +23,CUP,SUM,0,0,0,0,0,25,14,17.2405910492 +23,SPOON,SUM,0,0,0,0,0,301,0,30.4740791321 +23,,SUM,0,0,0,0,0,402,22,65.0131192207 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,0,81,6,15.923584938 +24,CUP,SUM,0,0,0,0,0,11,4,9.1103551388 +24,SPOON,SUM,0,0,0,0,0,57,1,18.3546581268 +24,,SUM,0,0,0,0,0,149,11,43.3885982037 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,0,16,2,11.3467600346 +25,CUP,SUM,1,0,0,1,0,196,51,0 +25,SPOON,SUM,0,0,0,0,0,123,0,20.3003721237 +25,,SUM,1,0,0,1,0,335,53,31.6471321583 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,8,63,4,18.7226610184 +26,CUP,SUM,0,0,0,0,0,25,0,9.05605793 +26,SPOON,SUM,0,0,0,0,0,29,0,14.925590992 +26,,SUM,0,0,0,0,8,117,4,42.7043099403 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,0,14,2,11.138792038 +27,CUP,SUM,1,0,0,1,0,212,55,0 +27,SPOON,SUM,0,0,0,0,0,112,0,20.1115760803 +27,,SUM,1,0,0,1,0,338,57,31.2503681183 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,2,18,0,11.4790258408 +28,CUP,SUM,0,0,0,0,2,8,2,9.6611499786 +28,SPOON,SUM,0,0,0,0,0,41,0,16.1453771591 +28,,SUM,0,0,0,0,4,67,2,37.2855529785 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,0,12,2,11.2896208763 +29,CUP,SUM,0,0,0,0,2,12,2,9.5648770332 +29,SPOON,SUM,0,0,0,0,0,359,0,33.8653860092 +29,,SUM,0,0,0,0,2,383,4,54.7198839188 +29,,,,,,,,,, +31,, +31,BOWL,SUM,0,0,0,0,6,6,0,15.057893991470337 +31,CUP,SUM,0,0,0,0,0,10,3,8.617418050765991 +31,SPOON,SUM,0,0,0,0,0,146,0,20.908615827560425 +31,,SUM,0,0,0,0,6,162,3,44.58392786979675 +31,, +32,, +32,BOWL,SUM,0,0,0,0,2,19,2,14.10529088973999 +32,CUP,SUM,0,0,0,0,0,13,1,10.114291906356812 +32,SPOON,SUM,0,0,0,0,0,64,0,16.75191903114319 +32,,SUM,0,0,0,0,2,96,3,40.97150182723999 +32,, +33,, +33,BOWL,SUM,0,0,0,0,0,31,0,11.02997899055481 +33,CUP,SUM,1,0,1,0,2,339,84,0.0 +33,SPOON,SUM,0,0,0,0,0,23,1,15.289561986923218 +33,,SUM,1,0,1,0,2,393,85,26.319540977478027 +33,, +34,, +34,BOWL,SUM,0,0,0,0,0,1,0,10.39458680152893 +34,CUP,SUM,0,0,0,0,0,45,18,22.173605918884277 +34,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +34,,SUM,1,0,1,0,0,1627,18,32.56819272041321 +34,, +35,, +35,BOWL,SUM,0,0,0,0,4,9,4,13.501821994781494 +35,CUP,SUM,0,0,0,0,2,105,22,31.949313163757324 +35,SPOON,SUM,0,0,0,0,2,138,0,21.85546612739563 +35,,SUM,0,0,0,0,8,252,26,67.30660128593445 +35,, +36,, +36,BOWL,SUM,0,0,0,0,0,58,0,12.87164306640625 +36,CUP,SUM,1,0,0,1,0,237,54,0.0 +36,SPOON,SUM,0,0,0,0,48,1304,0,106.29555082321167 +36,,SUM,1,0,0,1,48,1599,54,119.16719388961792 +36,, +37,, +37,BOWL,SUM,0,0,0,0,0,3,2,10.336344957351685 +37,CUP,SUM,0,0,0,0,0,117,34,47.267849922180176 +37,SPOON,SUM,0,0,0,0,0,194,0,24.05083918571472 +37,,SUM,0,0,0,0,0,314,36,81.65503406524658 +37,, +38,, +38,BOWL,SUM,1,0,1,0,0,820,78,0.0 +38,CUP,SUM,0,0,0,0,0,23,3,11.766853094100952 +38,SPOON,SUM,0,0,0,0,0,27,1,16.132206916809082 +38,,SUM,1,0,1,0,0,870,82,27.899060010910034 +38,, +39,, +39,BOWL,SUM,0,0,0,0,0,10,0,10.39905309677124 +39,CUP,SUM,0,0,0,0,0,14,2,8.7240469455719 +39,SPOON,SUM,1,0,1,0,0,767,54,0.0 +39,,SUM,1,0,1,0,0,791,56,19.12310004234314 +39,, +40,, +40,BOWL,SUM,0,0,0,0,56,49,0,36.54698300361633 +40,CUP,SUM,0,0,0,0,0,17,4,10.230739116668701 +40,SPOON,SUM,0,0,0,0,10,82,0,22.156725883483887 +40,,SUM,0,0,0,0,66,148,4,68.93444800376892 +40,, +41,, +41,BOWL,SUM,0,0,0,0,0,35,0,10.755496978759766 +41,CUP,SUM,0,0,0,0,0,161,43,54.21676993370056 +41,SPOON,SUM,0,0,0,0,4,37,0,16.21724796295166 +41,,SUM,0,0,0,0,4,233,43,81.18951487541199 +41,, +42,, +42,BOWL,SUM,0,0,0,0,18,88,6,23.61358904838562 +42,CUP,SUM,1,0,0,1,0,205,51,0.0 +42,SPOON,SUM,0,0,0,0,2,89,0,18.129169940948486 +42,,SUM,1,0,0,1,20,382,57,41.742758989334106 +42,, +43,, +43,BOWL,SUM,0,0,0,0,0,33,0,11.076931953430176 +43,CUP,SUM,0,0,0,0,4,3,8,9.965747117996216 +43,SPOON,SUM,0,0,0,0,0,2,2,13.515909194946289 +43,,SUM,0,0,0,0,4,38,10,34.55858826637268 +43,, +44,, +44,BOWL,SUM,0,0,0,0,0,56,0,12.408797979354858 +44,CUP,SUM,0,0,0,0,0,5,2,8.19886302947998 +44,SPOON,SUM,0,0,0,0,0,26,0,14.308616876602173 +44,,SUM,0,0,0,0,0,87,2,34.91627788543701 +44,, +45,, +45,BOWL,SUM,0,0,0,0,0,8,1,10.972524166107178 +45,CUP,SUM,0,0,0,0,0,6,10,16.56041717529297 +45,SPOON,SUM,0,0,0,0,0,19,0,13.710371971130371 +45,,SUM,0,0,0,0,0,33,11,41.24331331253052 +45,, +46,, +46,BOWL,SUM,0,0,0,0,0,2,0,10.13145112991333 +46,CUP,SUM,0,0,0,0,0,5,1,8.553359985351563 +46,SPOON,SUM,0,0,0,0,0,75,0,17.69516110420227 +46,,SUM,0,0,0,0,0,82,1,36.37997221946716 +46,, +47,, +47,BOWL,SUM,0,0,0,0,0,5,0,10.841613054275513 +47,CUP,SUM,0,0,0,0,0,7,4,8.770914793014526 +47,SPOON,SUM,0,0,0,0,0,6,3,15.126304149627686 +47,,SUM,0,0,0,0,0,18,7,34.738831996917725 +47,, +48,, +48,BOWL,SUM,0,0,0,0,6,120,8,22.810351848602295 +48,CUP,SUM,0,0,0,0,0,10,0,8.56762409210205 +48,SPOON,SUM,0,0,0,0,2,12,0,14.541586875915527 +48,,SUM,0,0,0,0,8,142,8,45.91956281661987 +48,, +49,, +49,BOWL,SUM,0,0,0,0,4,23,1,13.452290058135986 +49,CUP,SUM,0,0,0,0,0,42,7,11.095093965530396 +49,SPOON,SUM,0,0,0,0,0,10,0,13.852302074432373 +49,,SUM,0,0,0,0,4,75,8,38.399686098098755 +49,, +50,, +50,BOWL,SUM,0,0,0,0,0,7,0,10.269216775894165 +50,CUP,SUM,0,0,0,0,0,3,9,9.185931921005249 +50,SPOON,SUM,0,0,0,0,0,12,0,13.818592071533203 +50,,SUM,0,0,0,0,0,22,9,33.27374076843262 +50,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/paper/3.Pr2VrSim.csv b/cram_knowrob/cram_knowrob_vr/experiments/paper/3.Pr2VrSim.csv new file mode 100644 index 0000000000..6a5fa1d0e1 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/paper/3.Pr2VrSim.csv @@ -0,0 +1,603 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,0,4,4,17.38674306869507 +0,CUP,SUM,1,0,0,1,0,336,70,0.0 +0,SPOON,SUM,0,0,0,0,0,2,0,14.158383131027222 +0,,SUM,1,0,0,1,0,342,74,31.54512619972229 +0,, +1,, +1,BOWL,SUM,0,0,0,0,0,44,6,15.820966005325317 +1,CUP,SUM,0,0,0,0,6,26,5,16.324048042297363 +1,SPOON,SUM,0,0,0,0,0,358,1,37.488423109054565 +1,,SUM,0,0,0,0,6,428,12,69.63343715667725 +1,, +2,, +2,BOWL,SUM,0,0,0,0,2,318,16,38.21247601509094 +2,CUP,SUM,0,0,0,0,0,4,2,11.197307825088501 +2,SPOON,SUM,0,0,0,0,30,470,0,56.631958961486816 +2,,SUM,0,0,0,0,32,792,18,106.04174280166626 +2,, +3,, +3,BOWL,SUM,0,0,0,0,136,140,11,84.6933240890503 +3,CUP,SUM,0,0,0,0,0,95,25,40.52929711341858 +3,SPOON,SUM,0,0,0,0,0,230,10,33.19463300704956 +3,,SUM,0,0,0,0,136,465,46,158.41725420951843 +3,, +4,, +4,BOWL,SUM,0,0,0,0,0,19,1,13.272509813308716 +4,CUP,SUM,0,0,0,0,0,6,1,9.672878980636597 +4,SPOON,SUM,0,0,0,0,0,95,1,19.15848994255066 +4,,SUM,0,0,0,0,0,120,3,42.10387873649597 +4,, +5,, +5,BOWL,SUM,0,0,0,0,2,10,0,11.854227781295776 +5,CUP,SUM,0,0,0,0,0,77,26,42.77812099456787 +5,SPOON,SUM,0,0,0,0,0,60,11,25.41764998435974 +5,,SUM,0,0,0,0,2,147,37,80.04999876022339 +5,, +6,, +6,BOWL,SUM,0,0,0,0,0,7,2,11.380239009857178 +6,CUP,SUM,0,0,0,0,0,25,13,13.7520170211792 +6,SPOON,SUM,0,0,0,0,2,53,2,20.646291971206665 +6,,SUM,0,0,0,0,2,85,17,45.77854800224304 +6,, +7,, +7,BOWL,SUM,0,0,0,0,0,43,12,20.595612049102783 +7,CUP,SUM,0,0,0,0,0,42,5,15.395230054855347 +7,SPOON,SUM,0,0,0,0,0,255,1,31.796453952789307 +7,,SUM,0,0,0,0,0,340,18,67.78729605674744 +7,, +8,, +8,BOWL,SUM,0,0,0,0,0,15,1,13.313484191894531 +8,CUP,SUM,0,0,0,0,2,45,7,14.536288976669312 +8,SPOON,SUM,0,0,0,0,0,50,0,16.836424112319946 +8,,SUM,0,0,0,0,2,110,8,44.68619728088379 +8,, +9,, +9,BOWL,SUM,0,0,0,0,2,12,4,13.97064995765686 +9,CUP,SUM,0,0,0,0,0,36,4,13.520473957061768 +9,SPOON,SUM,0,0,0,0,0,261,3,31.707485914230347 +9,,SUM,0,0,0,0,2,309,11,59.198609828948975 +9,, +10,, +10,BOWL,SUM,0,0,0,0,56,710,16,86.75786304473877 +10,CUP,SUM,0,0,0,0,0,11,5,9.974384069442749 +10,SPOON,SUM,0,0,0,0,0,5,0,14.488665103912354 +10,,SUM,0,0,0,0,56,726,21,111.22091221809387 +10,, +11,, +11,BOWL,SUM,0,0,0,0,0,80,27,34.93830895423889 +11,CUP,SUM,0,0,0,0,0,11,2,9.749168872833252 +11,SPOON,SUM,0,0,0,0,0,3,6,19.567821979522705 +11,,SUM,0,0,0,0,0,94,35,64.25529980659485 +11,, +12,, +12,BOWL,SUM,1,0,1,0,0,457,98,0.0 +12,CUP,SUM,1,0,0,1,0,379,56,0.0 +12,SPOON,SUM,0,0,0,0,0,115,4,22.5176260471344 +12,,SUM,2,0,1,1,0,951,158,22.5176260471344 +12,, +13,, +13,BOWL,SUM,0,0,0,0,0,76,18,26.49917197227478 +13,CUP,SUM,1,0,1,0,10,196,112,0.0 +13,SPOON,SUM,0,0,0,0,0,33,4,17.605313062667847 +13,,SUM,1,0,1,0,10,305,134,44.10448503494263 +13,, +14,, +14,BOWL,SUM,0,0,0,0,0,23,0,11.861204147338867 +14,CUP,SUM,0,0,0,0,0,98,28,34.514238119125366 +14,SPOON,SUM,0,0,0,0,0,92,0,19.491858959197998 +14,,SUM,0,0,0,0,0,213,28,65.86730122566223 +14,, +15,, +15,BOWL,SUM,0,0,0,0,0,19,0,11.802428007125854 +15,CUP,SUM,0,0,0,0,0,39,1,11.981474876403809 +15,SPOON,SUM,0,0,0,0,6,39,0,19.100377082824707 +15,,SUM,0,0,0,0,6,97,1,42.88427996635437 +15,, +16,, +16,BOWL,SUM,0,0,0,0,2,20,0,12.98158311843872 +16,CUP,SUM,0,0,0,0,2,186,52,84.85480499267578 +16,SPOON,SUM,0,0,0,0,2,67,0,19.979596853256226 +16,,SUM,0,0,0,0,6,273,52,117.81598496437073 +16,, +17,, +17,BOWL,SUM,0,0,0,0,2,15,6,15.340914011001587 +17,CUP,SUM,0,0,0,0,0,53,17,19.39366316795349 +17,SPOON,SUM,0,0,0,0,2,2,0,15.511380910873413 +17,,SUM,0,0,0,0,4,70,23,50.24595808982849 +17,, +18,, +18,BOWL,SUM,0,0,0,0,24,24,0,23.06280207633972 +18,CUP,SUM,0,0,0,0,0,282,63,88.79449987411499 +18,SPOON,SUM,0,0,0,0,0,14,19,32.017959117889404 +18,,SUM,0,0,0,0,24,320,82,143.87526106834412 +18,, +19,, +19,BOWL,SUM,0,0,0,0,0,4,8,16.704933166503906 +19,CUP,SUM,0,0,0,0,4,22,0,11.471373081207275 +19,SPOON,SUM,0,0,0,0,2,14,0,16.613867044448853 +19,,SUM,0,0,0,0,6,40,8,44.790173292160034 +19,, +20,, +20,BOWL,SUM,1,0,1,0,82,758,90,0.0 +20,CUP,SUM,1,0,1,0,0,143,70,0.0 +20,SPOON,SUM,0,0,0,0,0,98,0,21.09627389907837 +20,,SUM,2,0,2,0,82,999,160,21.09627389907837 +20,, +21,, +21,BOWL,SUM,0,0,0,0,0,45,2,14.059705972671509 +21,CUP,SUM,0,0,0,0,2,142,29,54.852001905441284 +21,SPOON,SUM,0,0,0,0,0,38,0,17.346137046813965 +21,,SUM,0,0,0,0,2,225,31,86.25784492492676 +21,, +22,, +22,BOWL,SUM,0,0,0,0,0,49,16,24.793577194213867 +22,CUP,SUM,0,0,0,0,0,6,2,10.184190034866333 +22,SPOON,SUM,0,0,0,0,0,691,12,66.92617583274841 +22,,SUM,0,0,0,0,0,746,30,101.90394306182861 +22,, +23,, +23,BOWL,SUM,0,0,0,0,4,27,8,19.05445098876953 +23,CUP,SUM,0,0,0,0,0,160,31,57.652284145355225 +23,SPOON,SUM,0,0,0,0,22,98,2,31.120989084243774 +23,,SUM,0,0,0,0,26,285,41,107.82772421836853 +23,, +24,, +24,BOWL,SUM,0,0,0,0,0,19,0,11.895342111587524 +24,CUP,SUM,0,0,0,0,0,5,2,9.706305027008057 +24,SPOON,SUM,0,0,0,0,0,1,3,16.64503002166748 +24,,SUM,0,0,0,0,0,25,5,38.24667716026306 +24,, +25,, +25,BOWL,SUM,0,0,0,0,0,18,0,11.651329040527344 +25,CUP,SUM,0,0,0,0,0,34,6,13.819875001907349 +25,SPOON,SUM,0,0,0,0,0,23,0,15.71885895729065 +25,,SUM,0,0,0,0,0,75,6,41.19006299972534 +25,, +26,, +26,BOWL,SUM,0,0,0,0,2,35,2,13.419137001037598 +26,CUP,SUM,0,0,0,0,0,0,3,10.03205394744873 +26,SPOON,SUM,0,0,0,0,0,22,1,16.649123907089233 +26,,SUM,0,0,0,0,2,57,6,40.10031485557556 +26,, +27,, +27,BOWL,SUM,0,0,0,0,0,91,0,15.825905084609985 +27,CUP,SUM,0,0,0,0,0,19,2,12.083311080932617 +27,SPOON,SUM,0,0,0,0,0,37,0,17.37863302230835 +27,,SUM,0,0,0,0,0,147,2,45.28784918785095 +27,, +28,, +28,BOWL,SUM,0,0,0,0,0,25,0,12.103953123092651 +28,CUP,SUM,0,0,0,0,0,14,18,14.451349973678589 +28,SPOON,SUM,0,0,0,0,2,362,0,37.68951487541199 +28,,SUM,0,0,0,0,2,401,18,64.24481797218323 +28,, +29,, +29,BOWL,SUM,0,0,0,0,2,37,4,14.978721141815186 +29,CUP,SUM,1,0,0,1,0,284,89,0.0 +29,SPOON,SUM,0,0,0,0,0,19,4,16.99510097503662 +29,,SUM,1,0,0,1,2,340,97,31.973822116851807 +29,, +30,, +30,BOWL,SUM,0,0,0,0,0,4,0,11.686330080032349 +30,CUP,SUM,0,0,0,0,0,10,2,10.009263038635254 +30,SPOON,SUM,0,0,0,0,0,81,5,22.782968997955322 +30,,SUM,0,0,0,0,0,95,7,44.478562116622925 +30,, +31,, +31,BOWL,SUM,0,0,0,0,6,7,0,13.974137783050537 +31,CUP,SUM,0,0,0,0,0,88,22,35.31103205680847 +31,SPOON,SUM,0,0,0,0,0,95,0,21.127153158187866 +31,,SUM,0,0,0,0,6,190,22,70.41232299804688 +31,, +32,, +32,BOWL,SUM,0,0,0,0,2,22,1,14.771456956863403 +32,CUP,SUM,1,0,1,0,0,208,112,0.0 +32,SPOON,SUM,0,0,0,0,0,45,0,18.225878953933716 +32,,SUM,1,0,1,0,2,275,113,32.99733591079712 +32,, +33,, +33,BOWL,SUM,0,0,0,0,0,12,1,13.478455066680908 +33,CUP,SUM,0,0,0,0,2,110,60,69.3212149143219 +33,SPOON,SUM,0,0,0,0,0,106,5,29.214197158813477 +33,,SUM,0,0,0,0,2,228,66,112.01386713981628 +33,, +34,, +34,BOWL,SUM,0,0,0,0,0,399,36,53.698949098587036 +34,CUP,SUM,0,0,0,0,2,230,44,72.55121397972107 +34,SPOON,SUM,0,0,0,0,0,79,0,20.014590978622437 +34,,SUM,0,0,0,0,2,708,80,146.26475405693054 +34,, +35,, +35,BOWL,SUM,0,0,0,0,0,60,16,24.811307907104492 +35,CUP,SUM,0,0,0,0,0,20,9,10.866365909576416 +35,SPOON,SUM,0,0,0,0,0,99,6,23.278811931610107 +35,,SUM,0,0,0,0,0,179,31,58.956485748291016 +35,, +36,, +36,BOWL,SUM,0,0,0,0,0,5,0,12.774794816970825 +36,CUP,SUM,0,0,0,0,0,68,17,26.796857833862305 +36,SPOON,SUM,0,0,0,0,0,4,12,29.017534971237183 +36,,SUM,0,0,0,0,0,77,29,68.58918762207031 +36,, +37,, +37,BOWL,SUM,0,0,0,0,2,15,0,12.767246007919312 +37,CUP,SUM,0,0,0,0,0,3,6,9.979308843612671 +37,SPOON,SUM,1,0,1,0,2,1241,44,0.0 +37,,SUM,1,0,1,0,4,1259,50,22.746554851531982 +37,, +38,, +38,BOWL,SUM,0,0,0,0,0,15,2,11.984149932861328 +38,CUP,SUM,1,0,1,0,0,564,101,0.0 +38,SPOON,SUM,0,0,0,0,0,155,0,24.09766387939453 +38,,SUM,1,0,1,0,0,734,103,36.08181381225586 +38,, +39,, +39,BOWL,SUM,0,0,0,0,0,71,4,16.21770405769348 +39,CUP,SUM,0,0,0,0,0,11,6,10.551981925964355 +39,SPOON,SUM,0,0,0,0,0,115,0,21.79610800743103 +39,,SUM,0,0,0,0,0,197,10,48.56579399108887 +39,, +40,, +40,BOWL,SUM,0,0,0,0,0,52,9,20.864085912704468 +40,CUP,SUM,1,0,0,1,0,409,72,0.0 +40,SPOON,SUM,0,0,0,0,2,361,4,44.54509997367859 +40,,SUM,1,0,0,1,2,822,85,65.40918588638306 +40,, +41,, +41,BOWL,SUM,0,0,0,0,0,20,4,14.121052980422974 +41,CUP,SUM,0,0,0,0,4,30,12,18.79146099090576 +41,SPOON,SUM,0,0,0,0,0,262,1,33.14855980873108 +41,,SUM,0,0,0,0,4,312,17,66.06107378005981 +41,, +42,, +42,BOWL,SUM,0,0,0,0,0,11,0,11.774681091308594 +42,CUP,SUM,0,0,0,0,0,7,2,9.787084817886353 +42,SPOON,SUM,0,0,0,0,0,165,2,27.280728101730347 +42,,SUM,0,0,0,0,0,183,4,48.84249401092529 +42,, +43,, +43,BOWL,SUM,0,0,0,0,0,9,0,11.613464832305908 +43,CUP,SUM,0,0,0,0,0,14,1,10.241597175598145 +43,SPOON,SUM,0,0,0,0,0,9,3,16.639904975891113 +43,,SUM,0,0,0,0,0,32,4,38.494966983795166 +43,, +44,, +44,BOWL,SUM,0,0,0,0,0,173,12,28.22457003593445 +44,CUP,SUM,1,0,0,1,0,283,84,0.0 +44,SPOON,SUM,0,0,0,0,0,73,19,34.27674102783203 +44,,SUM,1,0,0,1,0,529,115,62.50131106376648 +44,, +45,, +45,BOWL,SUM,0,0,0,0,0,43,10,19.343662977218628 +45,CUP,SUM,0,0,0,0,0,6,4,9.900611877441406 +45,SPOON,SUM,0,0,0,0,0,114,0,21.655517101287842 +45,,SUM,0,0,0,0,0,163,14,50.899791955947876 +45,, +46,, +46,BOWL,SUM,0,0,0,0,0,22,6,15.674717903137207 +46,CUP,SUM,1,0,0,1,6,261,77,0.0 +46,SPOON,SUM,0,0,0,0,0,821,0,67.37232303619385 +46,,SUM,1,0,0,1,6,1104,83,83.04704093933105 +46,, +47,, +47,BOWL,SUM,0,0,0,0,0,30,2,13.080656051635742 +47,CUP,SUM,0,0,0,0,0,15,2,10.850200891494751 +47,SPOON,SUM,0,0,0,0,0,99,4,27.336440086364746 +47,,SUM,0,0,0,0,0,144,8,51.26729702949524 +47,, +48,, +48,BOWL,SUM,0,0,0,0,0,37,1,12.508074045181274 +48,CUP,SUM,0,0,0,0,0,39,12,15.159426927566528 +48,SPOON,SUM,0,0,0,0,0,44,8,21.767677783966064 +48,,SUM,0,0,0,0,0,120,21,49.43517875671387 +48,, +49,, +49,BOWL,SUM,0,0,0,0,2,25,14,23.225387811660767 +49,CUP,SUM,0,0,0,0,0,3,6,10.077811002731323 +49,SPOON,SUM,0,0,0,0,0,702,21,72.64942598342896 +49,,SUM,0,0,0,0,2,730,41,105.95262479782104 +49,, +50,, +50,BOWL,SUM,0,0,0,0,0,19,0,12.473503828048706 +50,CUP,SUM,0,0,0,0,8,7,0,14.601938009262085 +50,SPOON,SUM,0,0,0,0,0,12,11,25.100987911224365 +50,,SUM,0,0,0,0,8,38,11,52.176429748535156 +50,, +51,, +51,BOWL,SUM,0,0,0,0,0,36,0,13.868879079818726 +51,CUP,SUM,0,0,0,0,2,41,20,25.1647789478302 +51,SPOON,SUM,1,0,1,0,0,1098,54,0.0 +51,,SUM,1,0,1,0,2,1175,74,39.033658027648926 +51,, +52,, +52,BOWL,SUM,0,0,0,0,6,16,12,22.55021905899048 +52,CUP,SUM,0,0,0,0,0,87,19,33.13393187522888 +52,SPOON,SUM,1,0,1,0,0,1352,34,0.0 +52,,SUM,1,0,1,0,6,1455,65,55.68415093421936 +52,, +53,, +53,BOWL,SUM,0,0,0,0,2,24,0,13.518126010894775 +53,CUP,SUM,0,0,0,0,2,160,29,47.23987317085266 +53,SPOON,SUM,0,0,0,0,6,2,4,19.085577964782715 +53,,SUM,0,0,0,0,10,186,33,79.84357714653015 +53,, +54,, +54,BOWL,SUM,0,0,0,0,0,7,1,14.0173020362854 +54,CUP,SUM,0,0,0,0,2,26,2,11.214240074157715 +54,SPOON,SUM,1,0,1,0,2,1378,87,0.0 +54,,SUM,1,0,1,0,4,1411,90,25.231542110443115 +54,, +55,, +55,BOWL,SUM,0,0,0,0,58,48,2,39.83039903640747 +55,CUP,SUM,0,0,0,0,16,48,16,27.675708055496216 +55,SPOON,SUM,0,0,0,0,0,62,2,22.49181604385376 +55,,SUM,0,0,0,0,74,158,20,89.99792313575745 +55,, +56,, +56,BOWL,SUM,0,0,0,0,0,27,2,12.510334014892578 +56,CUP,SUM,0,0,0,0,0,9,7,10.75282096862793 +56,SPOON,SUM,0,0,0,0,18,504,1,58.29476308822632 +56,,SUM,0,0,0,0,18,540,10,81.55791807174683 +56,, +57,, +57,BOWL,SUM,0,0,0,0,2,3,0,12.155151844024658 +57,CUP,SUM,0,0,0,0,0,14,2,10.41283106803894 +57,SPOON,SUM,0,0,0,0,0,592,3,57.227410078048706 +57,,SUM,0,0,0,0,2,609,5,79.7953929901123 +57,, +58,, +58,BOWL,SUM,0,0,0,0,0,18,0,11.875622987747192 +58,CUP,SUM,0,0,0,0,0,206,49,77.31166696548462 +58,SPOON,SUM,0,0,0,0,0,158,1,27.641334056854248 +58,,SUM,0,0,0,0,0,382,50,116.82862401008606 +58,, +59,, +59,BOWL,SUM,0,0,0,0,0,21,0,12.605969190597534 +59,CUP,SUM,1,0,0,1,0,306,54,0.0 +59,SPOON,SUM,0,0,0,0,2,95,1,22.58433508872986 +59,,SUM,1,0,0,1,2,422,55,35.19030427932739 +59,, +60,, +60,BOWL,SUM,0,0,0,0,0,45,0,14.203117847442627 +60,CUP,SUM,0,0,0,0,2,36,3,13.188416004180908 +60,SPOON,SUM,0,0,0,0,0,32,2,21.207638025283813 +60,,SUM,0,0,0,0,2,113,5,48.59917187690735 +60,, +61,, +61,BOWL,SUM,1,0,1,0,8,1222,36,0.0 +61,CUP,SUM,1,0,0,1,0,267,78,0.0 +61,SPOON,SUM,0,0,0,0,0,0,0,15.800107955932617 +61,,SUM,2,0,1,1,8,1489,114,15.800107955932617 +61,, +62,, +62,BOWL,SUM,0,0,0,0,0,7,2,12.735338926315308 +62,CUP,SUM,0,0,0,0,6,12,2,12.747550964355469 +62,SPOON,SUM,0,0,0,0,4,127,8,31.792898893356323 +62,,SUM,0,0,0,0,10,146,12,57.2757887840271 +62,, +63,, +63,BOWL,SUM,0,0,0,0,40,46,18,45.77597093582153 +63,CUP,SUM,1,0,1,0,8,440,78,0.0 +63,SPOON,SUM,0,0,0,0,0,34,5,20.749449014663696 +63,,SUM,1,0,1,0,48,520,101,66.52541995048523 +63,, +64,, +64,BOWL,SUM,0,0,0,0,0,14,6,15.514228820800781 +64,CUP,SUM,1,0,1,0,6,201,110,0.0 +64,SPOON,SUM,0,0,0,0,0,291,0,33.98711705207825 +64,,SUM,1,0,1,0,6,506,116,49.50134587287903 +64,, +65,, +65,BOWL,SUM,0,0,0,0,0,1,0,11.537220001220703 +65,CUP,SUM,0,0,0,0,0,2,2,10.131298065185547 +65,SPOON,SUM,0,0,0,0,16,96,0,28.320728063583374 +65,,SUM,0,0,0,0,16,99,2,49.989246129989624 +65,, +66,, +66,BOWL,SUM,0,0,0,0,8,116,10,25.670140027999878 +66,CUP,SUM,0,0,0,0,0,40,5,15.879999160766602 +66,SPOON,SUM,0,0,0,0,0,4,6,18.688222885131836 +66,,SUM,0,0,0,0,8,160,21,60.238362073898315 +66,, +67,, +67,BOWL,SUM,0,0,0,0,2,52,0,14.953797101974487 +67,CUP,SUM,0,0,0,0,0,74,24,36.98026919364929 +67,SPOON,SUM,0,0,0,0,0,4,5,20.152978897094727 +67,,SUM,0,0,0,0,2,130,29,72.0870451927185 +67,, +68,, +68,BOWL,SUM,0,0,0,0,0,13,0,11.877889156341553 +68,CUP,SUM,0,0,0,0,0,2,1,9.669941902160645 +68,SPOON,SUM,0,0,0,0,0,191,0,26.35793900489807 +68,,SUM,0,0,0,0,0,206,1,47.90577006340027 +68,, +69,, +69,BOWL,SUM,0,0,0,0,24,39,6,27.577190160751343 +69,CUP,SUM,0,0,0,0,0,15,2,10.448669910430908 +69,SPOON,SUM,0,0,0,0,0,21,0,15.932729959487915 +69,,SUM,0,0,0,0,24,75,8,53.958590030670166 +69,, +70,, +70,BOWL,SUM,0,0,0,0,56,44,0,39.468672037124634 +70,CUP,SUM,1,0,0,1,0,354,58,0.0 +70,SPOON,SUM,0,0,0,0,0,1,0,15.693617820739746 +70,,SUM,1,0,0,1,56,399,58,55.16228985786438 +70,, +71,, +71,BOWL,SUM,0,0,0,0,0,73,6,17.444552898406982 +71,CUP,SUM,0,0,0,0,8,36,14,20.914746046066284 +71,SPOON,SUM,0,0,0,0,0,120,9,29.361998081207275 +71,,SUM,0,0,0,0,8,229,29,67.72129702568054 +71,, +72,, +72,BOWL,SUM,0,0,0,0,0,119,20,31.700427055358887 +72,CUP,SUM,0,0,0,0,2,18,6,11.379082918167114 +72,SPOON,SUM,0,0,0,0,6,1,0,16.88980507850647 +72,,SUM,0,0,0,0,8,138,26,59.96931505203247 +72,, +73,, +73,BOWL,SUM,0,0,0,0,0,16,0,12.14620304107666 +73,CUP,SUM,0,0,0,0,0,7,2,10.126204013824463 +73,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +73,,SUM,1,0,1,0,0,1604,2,22.272407054901123 +73,, +74,, +74,BOWL,SUM,0,0,0,0,0,8,1,13.581148862838745 +74,CUP,SUM,0,0,0,0,2,47,8,15.094358205795288 +74,SPOON,SUM,0,0,0,0,0,78,0,20.048393964767456 +74,,SUM,0,0,0,0,2,133,9,48.72390103340149 +74,, +75,, +75,BOWL,SUM,0,0,0,0,0,14,4,14.664841890335083 +75,CUP,SUM,0,0,0,0,0,48,11,20.113159894943237 +75,SPOON,SUM,0,0,0,0,0,3,0,15.394704103469849 +75,,SUM,0,0,0,0,0,65,15,50.17270588874817 +75,, +76,, +76,BOWL,SUM,0,0,0,0,0,21,0,12.546725988388062 +76,CUP,SUM,0,0,0,0,0,44,12,24.49989104270935 +76,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +76,,SUM,1,0,1,0,0,1646,12,37.04661703109741 +76,, +77,, +77,BOWL,SUM,1,0,1,0,0,560,96,0.0 +77,CUP,SUM,0,0,0,0,0,23,6,11.070840835571289 +77,SPOON,SUM,0,0,0,0,0,12,0,15.531301975250244 +77,,SUM,1,0,1,0,0,595,102,26.602142810821533 +77,, +78,, +78,BOWL,SUM,0,0,0,0,0,55,0,14.31379508972168 +78,CUP,SUM,0,0,0,0,0,6,0,10.400300025939941 +78,SPOON,SUM,0,0,0,0,0,26,5,19.083147048950195 +78,,SUM,0,0,0,0,0,87,5,43.797242164611816 +78,, +79,, +79,BOWL,SUM,0,0,0,0,2,117,26,38.09994387626648 +79,CUP,SUM,0,0,0,0,0,41,10,13.656544923782349 +79,SPOON,SUM,0,0,0,0,0,9,6,19.111271858215332 +79,,SUM,0,0,0,0,2,167,42,70.86776065826416 +79,, +80,, +80,BOWL,SUM,0,0,0,0,0,24,8,17.989253997802734 +80,CUP,SUM,0,0,0,0,0,42,2,11.776211023330688 +80,SPOON,SUM,0,0,0,0,0,40,2,20.904775142669678 +80,,SUM,0,0,0,0,0,106,12,50.6702401638031 +80,, +81,, +81,BOWL,SUM,0,0,0,0,6,9,0,14.120737075805664 +81,CUP,SUM,0,0,0,0,58,105,16,51.303086042404175 +81,SPOON,SUM,0,0,0,0,26,5,0,28.01622200012207 +81,,SUM,0,0,0,0,90,119,16,93.44004511833191 +81,, +82,, +82,BOWL,SUM,0,0,0,0,0,22,1,13.982795000076294 +82,CUP,SUM,0,0,0,0,4,13,4,11.723069190979004 +82,SPOON,SUM,0,0,0,0,2,296,3,38.96694803237915 +82,,SUM,0,0,0,0,6,331,8,64.67281222343445 +82,, +83,, +83,BOWL,SUM,0,0,0,0,2,9,2,13.053606033325195 +83,CUP,SUM,0,0,0,0,0,35,2,12.043537855148315 +83,SPOON,SUM,0,0,0,0,0,147,4,26.7385151386261 +83,,SUM,0,0,0,0,2,191,8,51.83565902709961 +83,, +84,, +84,BOWL,SUM,0,0,0,0,0,272,31,46.66932511329651 +84,CUP,SUM,0,0,0,0,0,5,4,13.400423049926758 +84,SPOON,SUM,0,0,0,0,0,47,7,22.81483292579651 +84,,SUM,0,0,0,0,0,324,42,82.88458108901978 +84,, +85,, +85,BOWL,SUM,0,0,0,0,0,6,1,13.810908079147339 +85,CUP,SUM,0,0,0,0,0,52,24,27.527513027191162 +85,SPOON,SUM,0,0,0,0,2,0,0,16.052397966384888 +85,,SUM,0,0,0,0,2,58,25,57.39081907272339 +85,, +86,, +86,BOWL,SUM,0,0,0,0,0,103,5,20.53606605529785 +86,CUP,SUM,1,0,1,0,0,108,111,0.0 +86,SPOON,SUM,0,0,0,0,0,55,4,23.56334090232849 +86,,SUM,1,0,1,0,0,266,120,44.09940695762634 +86,, +87,, +87,BOWL,SUM,0,0,0,0,0,28,8,18.0699679851532 +87,CUP,SUM,0,0,0,0,0,18,4,10.44173002243042 +87,SPOON,SUM,0,0,0,0,0,164,0,25.945157766342163 +87,,SUM,0,0,0,0,0,210,12,54.45685577392578 +87,, +88,, +88,BOWL,SUM,0,0,0,0,0,626,58,85.26969909667969 +88,CUP,SUM,1,0,1,0,0,206,99,0.0 +88,SPOON,SUM,0,0,0,0,4,19,1,19.631336212158203 +88,,SUM,1,0,1,0,4,851,158,104.90103530883789 +88,, +89,, +89,BOWL,SUM,1,0,1,0,2,618,92,0.0 +89,CUP,SUM,0,0,0,0,0,30,8,11.457655906677246 +89,SPOON,SUM,0,0,0,0,10,16,1,21.982760906219482 +89,,SUM,1,0,1,0,12,664,101,33.44041681289673 +89,, +90,, +90,BOWL,SUM,0,0,0,0,2,180,28,40.01838707923889 +90,CUP,SUM,1,0,1,0,0,259,110,0.0 +90,SPOON,SUM,1,0,1,0,30,1592,0,0.0 +90,,SUM,2,0,2,0,32,2031,138,40.01838707923889 +90,, +91,, +91,BOWL,SUM,0,0,0,0,0,23,6,15.89646291732788 +91,CUP,SUM,1,0,1,0,4,224,108,0.0 +91,SPOON,SUM,0,0,0,0,0,4,1,16.622205018997192 +91,,SUM,1,0,1,0,4,251,115,32.51866793632507 +91,, +92,, +92,BOWL,SUM,0,0,0,0,0,59,10,20.597641944885254 +92,CUP,SUM,0,0,0,0,8,15,2,14.607192993164063 +92,SPOON,SUM,0,0,0,0,0,10,6,19.250631093978882 +92,,SUM,0,0,0,0,8,84,18,54.4554660320282 +92,, +93,, +93,BOWL,SUM,1,0,1,0,10,776,86,0.0 +93,CUP,SUM,0,0,0,0,0,153,41,58.912423849105835 +93,SPOON,SUM,0,0,0,0,10,285,6,47.04146599769592 +93,,SUM,1,0,1,0,20,1214,133,105.95388984680176 +93,, +94,, +94,BOWL,SUM,0,0,0,0,0,12,0,12.001936912536621 +94,CUP,SUM,0,0,0,0,6,21,5,12.916265964508057 +94,SPOON,SUM,1,0,1,0,8,687,86,0.0 +94,,SUM,1,0,1,0,14,720,91,24.918202877044678 +94,, +95,, +95,BOWL,SUM,0,0,0,0,0,19,1,14.619529008865356 +95,CUP,SUM,0,0,0,0,0,10,1,12.39228892326355 +95,SPOON,SUM,0,0,0,0,2,46,0,17.273895025253296 +95,,SUM,0,0,0,0,2,75,2,44.2857129573822 +95,, +96,, +96,BOWL,SUM,0,0,0,0,0,261,36,48.63484811782837 +96,CUP,SUM,0,0,0,0,0,54,18,23.738415002822876 +96,SPOON,SUM,0,0,0,0,0,1,4,17.53434419631958 +96,,SUM,0,0,0,0,0,316,58,89.90760731697083 +96,, +97,, +97,BOWL,SUM,0,0,0,0,0,26,0,12.667067050933838 +97,CUP,SUM,0,0,0,0,0,9,2,10.593016862869263 +97,SPOON,SUM,0,0,0,0,2,1,14,31.34060502052307 +97,,SUM,0,0,0,0,2,36,16,54.60068893432617 +97,, +98,, +98,BOWL,SUM,0,0,0,0,0,7,0,12.194375038146973 +98,CUP,SUM,0,0,0,0,0,278,66,102.71326112747192 +98,SPOON,SUM,0,0,0,0,0,153,8,30.04104995727539 +98,,SUM,0,0,0,0,0,438,74,144.9486861228943 +98,, +99,, +99,BOWL,SUM,0,0,0,0,2,1,0,12.725702047348022 +99,CUP,SUM,0,0,0,0,0,31,0,10.700498819351196 +99,SPOON,SUM,0,0,0,0,0,6,6,20.37502884864807 +99,,SUM,0,0,0,0,2,38,6,43.80122971534729 +99,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/paper/4.Pr2VrSimThird.csv b/cram_knowrob/cram_knowrob_vr/experiments/paper/4.Pr2VrSimThird.csv new file mode 100644 index 0000000000..e856c5c9cc --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/paper/4.Pr2VrSimThird.csv @@ -0,0 +1,291 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +50,, +50,BOWL,SUM,0,0,0,0,0,14,4,10.599961042404175 +50,CUP,SUM,0,0,0,0,0,5,0,6.82976508140564 +50,SPOON,SUM,1,0,1,0,2,1581,0,0.0 +50,,SUM,1,0,1,0,2,1600,4,17.429726123809814 +50,, +51,, +51,BOWL,SUM,0,0,0,0,0,12,0,8.819735050201416 +51,CUP,SUM,0,0,0,0,2,50,5,13.62477707862854 +51,SPOON,SUM,0,0,0,0,0,0,0,11.77640700340271 +51,,SUM,0,0,0,0,2,62,5,34.220919132232666 +51,, +52,, +52,BOWL,SUM,0,0,0,0,0,43,0,10.358792066574097 +52,CUP,SUM,0,0,0,0,2,12,4,7.626431941986084 +52,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +52,,SUM,1,0,1,0,2,1636,4,17.98522400856018 +52,, +53,, +53,BOWL,SUM,0,0,0,0,0,30,12,15.279633045196533 +53,CUP,SUM,0,0,0,0,0,16,7,8.061570882797241 +53,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +53,,SUM,1,0,1,0,0,1627,19,23.341203927993774 +53,, +54,, +54,BOWL,SUM,0,0,0,0,0,20,0,8.824887990951538 +54,CUP,SUM,0,0,0,0,0,46,2,7.7838640213012695 +54,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +54,,SUM,1,0,1,0,0,1647,2,16.608752012252808 +54,, +55,, +55,BOWL,SUM,0,0,0,0,0,22,2,9.265057802200317 +55,CUP,SUM,1,0,1,0,0,261,111,0.0 +55,SPOON,SUM,0,0,0,0,0,0,6,14.802527904510498 +55,,SUM,1,0,1,0,0,283,119,24.067585706710815 +55,, +56,, +56,BOWL,SUM,0,0,0,0,0,11,4,10.86034893989563 +56,CUP,SUM,0,0,0,0,0,32,1,9.013726949691772 +56,SPOON,SUM,0,0,0,0,0,0,7,16.014787197113037 +56,,SUM,0,0,0,0,0,43,12,35.88886308670044 +56,, +57,, +57,BOWL,SUM,0,0,0,0,0,12,0,8.734523057937622 +57,CUP,SUM,0,0,0,0,42,59,86,71.68465900421143 +57,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +57,,SUM,1,0,1,0,42,1652,86,80.41918206214905 +57,, +58,, +58,BOWL,SUM,0,0,0,0,0,18,3,10.268955945968628 +58,CUP,SUM,0,0,0,0,2,197,38,42.9977490901947 +58,SPOON,SUM,1,0,1,0,2,1326,42,0.0 +58,,SUM,1,0,1,0,4,1541,83,53.26670503616333 +58,, +59,, +59,BOWL,SUM,0,0,0,0,2,31,0,9.98353886604309 +59,CUP,SUM,0,0,0,0,0,30,14,18.098119020462036 +59,SPOON,SUM,0,0,0,0,6,6,3,15.140197038650513 +59,,SUM,0,0,0,0,8,67,17,43.22185492515564 +59,, +60,, +60,BOWL,SUM,0,0,0,0,0,37,0,10.481428861618042 +60,CUP,SUM,0,0,0,0,0,61,13,17.97027897834778 +60,SPOON,SUM,0,0,0,0,0,0,0,12.089012861251831 +60,,SUM,0,0,0,0,0,98,13,40.54072070121765 +60,, +61,, +61,BOWL,SUM,0,0,0,0,0,23,4,10.518329858779907 +61,CUP,SUM,0,0,0,0,2,10,8,8.249943971633911 +61,SPOON,SUM,0,0,0,0,0,33,5,15.682204961776733 +61,,SUM,0,0,0,0,2,66,17,34.45047879219055 +61,, +62,, +62,BOWL,SUM,0,0,0,0,2,3,0,9.43644905090332 +62,CUP,SUM,0,0,0,0,0,83,13,18.08749008178711 +62,SPOON,SUM,0,0,0,0,0,367,2,29.182981967926025 +62,,SUM,0,0,0,0,2,453,15,56.706921100616455 +62,, +63,, +63,BOWL,SUM,0,0,0,0,6,2,0,10.693027973175049 +63,CUP,SUM,0,0,0,0,0,104,22,19.450329065322876 +63,SPOON,SUM,1,0,1,0,2,1581,0,0.0 +63,,SUM,1,0,1,0,8,1687,22,30.143357038497925 +63,, +64,, +64,BOWL,SUM,1,0,1,0,0,1285,40,0.0 +64,CUP,SUM,0,0,0,0,0,35,0,7.634438991546631 +64,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +64,,SUM,2,0,2,0,0,2901,40,7.634438991546631 +64,, +65,, +65,BOWL,SUM,1,0,1,0,0,549,102,0.0 +65,CUP,SUM,0,0,0,0,0,26,1,7.4246909618377686 +65,SPOON,SUM,0,0,0,0,0,0,1,12.8157958984375 +65,,SUM,1,0,1,0,0,575,104,20.24048686027527 +65,, +66,, +66,BOWL,SUM,0,0,0,0,0,10,2,9.116393089294434 +66,CUP,SUM,0,0,0,0,38,52,13,29.734323978424072 +66,SPOON,SUM,0,0,0,0,0,34,29,28.66660189628601 +66,,SUM,0,0,0,0,38,96,44,67.51731896400452 +66,, +67,, +67,BOWL,SUM,1,1,0,0,160,78,0,0.0 +67,CUP,SUM,0,0,0,0,0,14,7,8.952981948852539 +67,SPOON,SUM,1,0,1,0,0,1582,0,0.0 +67,,SUM,2,1,1,0,160,1674,7,8.952981948852539 +67,, +68,, +68,BOWL,SUM,0,0,0,0,0,16,0,9.423910140991211 +68,CUP,SUM,0,0,0,0,0,26,10,12.244262933731079 +68,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +68,,SUM,1,0,1,0,0,1623,10,21.66817307472229 +68,, +69,, +69,BOWL,SUM,0,0,0,0,0,10,0,8.93390703201294 +69,CUP,SUM,1,0,0,1,0,285,51,0.0 +69,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +69,,SUM,2,0,1,1,0,1876,51,8.93390703201294 +69,, +70,, +70,BOWL,SUM,0,0,0,0,0,8,0,9.032894134521484 +70,CUP,SUM,1,0,1,0,4,244,71,0.0 +70,SPOON,SUM,0,0,0,0,0,176,4,23.54850196838379 +70,,SUM,1,0,1,0,4,428,75,32.58139610290527 +70,, +71,, +71,BOWL,SUM,0,0,0,0,0,13,0,9.875010013580322 +71,CUP,SUM,0,0,0,0,0,28,0,7.775708913803101 +71,SPOON,SUM,1,0,1,0,0,592,102,0.0 +71,,SUM,1,0,1,0,0,633,102,17.650718927383423 +71,, +72,, +72,BOWL,SUM,0,0,0,0,0,14,0,9.158792972564697 +72,CUP,SUM,1,0,0,1,0,242,53,0.0 +72,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +72,,SUM,2,0,1,1,0,1837,53,9.158792972564697 +72,, +73,, +73,BOWL,SUM,0,0,0,0,0,8,4,10.863928079605103 +73,CUP,SUM,0,0,0,0,0,14,7,9.10171389579773 +73,SPOON,SUM,0,0,0,0,0,0,1,13.112598180770874 +73,,SUM,0,0,0,0,0,22,12,33.078240156173706 +73,, +74,, +74,BOWL,SUM,1,0,1,0,0,1581,0,0.0 +74,CUP,SUM,0,0,0,0,0,298,40,46.43463110923767 +74,SPOON,SUM,0,0,0,0,0,11,2,14.50262999534607 +74,,SUM,1,0,1,0,0,1890,42,60.93726110458374 +74,, +75,, +75,BOWL,SUM,0,0,0,0,0,10,2,9.391451835632324 +75,CUP,SUM,0,0,0,0,2,5,8,8.284360885620117 +75,SPOON,SUM,0,0,0,0,0,27,0,12.70317792892456 +75,,SUM,0,0,0,0,2,42,10,30.378990650177002 +75,, +76,, +76,BOWL,SUM,0,0,0,0,2,17,8,13.663438081741333 +76,CUP,SUM,0,0,0,0,0,162,47,42.28623414039612 +76,SPOON,SUM,1,0,1,0,54,1062,0,0.0 +76,,SUM,1,0,1,0,56,1241,55,55.94967222213745 +76,, +77,, +77,BOWL,SUM,0,0,0,0,0,31,6,11.966325998306274 +77,CUP,SUM,1,0,0,1,0,305,51,0.0 +77,SPOON,SUM,0,0,0,0,0,77,1,16.68572688102722 +77,,SUM,1,0,0,1,0,413,58,28.652052879333496 +77,, +78,, +78,BOWL,SUM,0,0,0,0,0,7,0,9.105072021484375 +78,CUP,SUM,0,0,0,0,0,51,10,14.868062019348145 +78,SPOON,SUM,0,0,0,0,0,0,2,12.604153871536255 +78,,SUM,0,0,0,0,0,58,12,36.577287912368774 +78,, +79,, +79,BOWL,SUM,0,0,0,0,0,19,1,9.620437860488892 +79,CUP,SUM,1,0,1,0,0,143,112,0.0 +79,SPOON,SUM,1,0,1,0,0,899,78,0.0 +79,,SUM,2,0,2,0,0,1061,191,9.620437860488892 +79,, +80,, +80,BOWL,SUM,0,0,0,0,0,12,8,12.730754137039185 +80,CUP,SUM,0,0,0,0,0,18,5,10.660567045211792 +80,SPOON,SUM,0,0,0,0,0,6,13,20.492497205734253 +80,,SUM,0,0,0,0,0,36,26,43.88381838798523 +80,, +81,, +81,BOWL,SUM,0,0,0,0,0,14,8,13.050469160079956 +81,CUP,SUM,0,0,0,0,0,148,32,36.885241985321045 +81,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +81,,SUM,1,0,1,0,0,1743,40,49.935711145401 +81,, +82,, +82,BOWL,SUM,0,0,0,0,0,271,2,22.20917582511902 +82,CUP,SUM,0,0,0,0,0,85,30,29.510241985321045 +82,SPOON,SUM,1,0,1,0,10,1587,0,0.0 +82,,SUM,1,0,1,0,10,1943,32,51.71941781044006 +82,, +83,, +83,BOWL,SUM,0,0,0,0,0,14,0,9.251063823699951 +83,CUP,SUM,0,0,0,0,0,41,5,9.406798839569092 +83,SPOON,SUM,1,0,1,0,2,1581,0,0.0 +83,,SUM,1,0,1,0,2,1636,5,18.657862663269043 +83,, +84,, +84,BOWL,SUM,0,0,0,0,0,35,6,12.497748136520386 +84,CUP,SUM,1,0,1,0,4,320,110,0.0 +84,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +84,,SUM,2,0,2,0,4,1936,116,12.497748136520386 +84,, +85,, +85,BOWL,SUM,0,0,0,0,0,120,2,14.380787134170532 +85,CUP,SUM,0,0,0,0,6,93,31,36.29663109779358 +85,SPOON,SUM,0,0,0,0,0,38,0,14.628196001052856 +85,,SUM,0,0,0,0,6,251,33,65.30561423301697 +85,, +86,, +86,BOWL,SUM,1,0,1,0,0,1013,64,0.0 +86,CUP,SUM,0,0,0,0,0,20,4,8.184858083724976 +86,SPOON,SUM,0,0,0,0,0,0,2,12.805813074111938 +86,,SUM,1,0,1,0,0,1033,70,20.990671157836914 +86,, +87,, +87,BOWL,SUM,0,0,0,0,0,17,1,10.491102933883667 +87,CUP,SUM,0,0,0,0,2,106,30,27.989120960235596 +87,SPOON,SUM,0,0,0,0,0,2,7,17.713347911834717 +87,,SUM,0,0,0,0,2,125,38,56.19357180595398 +87,, +88,, +88,BOWL,SUM,1,0,1,0,0,491,102,0.0 +88,CUP,SUM,0,0,0,0,0,23,9,9.6980140209198 +88,SPOON,SUM,0,0,0,0,0,0,4,13.845911979675293 +88,,SUM,1,0,1,0,0,514,115,23.543926000595093 +88,, +89,, +89,BOWL,SUM,0,0,0,0,72,112,4,48.080251932144165 +89,CUP,SUM,0,0,0,0,0,17,2,9.52760910987854 +89,SPOON,SUM,0,0,0,0,0,4,2,12.896147966384888 +89,,SUM,0,0,0,0,72,133,8,70.50400900840759 +89,, +90,, +90,BOWL,SUM,1,0,1,0,0,714,88,0.0 +90,CUP,SUM,0,0,0,0,6,6,9,13.423007011413574 +90,SPOON,SUM,1,0,1,0,0,1590,0,0.0 +90,,SUM,2,0,2,0,6,2310,97,13.423007011413574 +90,, +91,, +91,BOWL,SUM,0,0,0,0,6,201,12,24.63028907775879 +91,CUP,SUM,1,0,0,1,0,357,58,0.0 +91,SPOON,SUM,0,0,0,0,0,0,14,19.229068994522095 +91,,SUM,1,0,0,1,6,558,84,43.859358072280884 +91,, +92,, +92,BOWL,SUM,0,0,0,0,0,11,0,9.569445133209229 +92,CUP,SUM,1,0,0,1,2,288,57,0.0 +92,SPOON,SUM,1,0,1,0,16,1452,0,0.0 +92,,SUM,2,0,1,1,18,1751,57,9.569445133209229 +92,, +93,, +93,BOWL,SUM,0,0,0,0,0,2,0,9.265429973602295 +93,CUP,SUM,0,0,0,0,0,5,0,7.2139599323272705 +93,SPOON,SUM,0,0,0,0,4,9,4,15.813823938369751 +93,,SUM,0,0,0,0,4,16,4,32.293213844299316 +93,, +94,, +94,BOWL,SUM,0,0,0,0,0,85,19,22.648711919784546 +94,CUP,SUM,0,0,0,0,0,22,2,8.69812798500061 +94,SPOON,SUM,0,0,0,0,4,4,10,19.86899209022522 +94,,SUM,0,0,0,0,4,111,31,51.215831995010376 +94,, +95,, +95,BOWL,SUM,0,0,0,0,0,32,0,10.771960020065308 +95,CUP,SUM,1,0,0,1,0,338,54,0.0 +95,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +95,,SUM,2,0,1,1,0,1951,54,10.771960020065308 +95,, +96,, +96,BOWL,SUM,0,0,0,0,0,39,6,13.384937047958374 +96,CUP,SUM,0,0,0,0,0,27,4,8.436053037643433 +96,SPOON,SUM,1,0,1,0,0,1582,0,0.0 +96,,SUM,1,0,1,0,0,1648,10,21.820990085601807 +96,, +97,, +97,BOWL,SUM,1,0,1,0,0,933,76,0.0 +97,CUP,SUM,1,0,0,1,0,251,55,0.0 +97,SPOON,SUM,0,0,0,0,4,311,0,28.879663944244385 +97,,SUM,2,0,1,1,4,1495,131,28.879663944244385 +97,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/paper/5.Pr2HrSimMod.csv b/cram_knowrob/cram_knowrob_vr/experiments/paper/5.Pr2HrSimMod.csv new file mode 100644 index 0000000000..a0a0f27956 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/paper/5.Pr2HrSimMod.csv @@ -0,0 +1,603 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,0,11,101,30.947895050048828 +0,CUP,SUM,0,0,0,0,0,2,12,6.757516145706177 +0,SPOON,SUM,0,0,0,0,0,1,6,11.062914848327637 +0,,SUM,0,0,0,0,0,14,119,48.76832604408264 +0,, +1,, +1,BOWL,SUM,1,0,1,0,0,54,204,0.0 +1,CUP,SUM,0,0,0,0,0,0,25,10.552206039428711 +1,SPOON,SUM,0,0,0,0,0,3,1,10.046876907348633 +1,,SUM,1,0,1,0,0,57,230,20.599082946777344 +1,, +2,, +2,BOWL,SUM,0,0,0,0,0,1,39,15.53513503074646 +2,CUP,SUM,0,0,0,0,0,3,18,9.428974866867065 +2,SPOON,SUM,0,0,0,0,16,10,40,23.712773084640503 +2,,SUM,0,0,0,0,16,14,97,48.67688298225403 +2,, +3,, +3,BOWL,SUM,0,0,0,0,0,1,15,13.767441987991333 +3,CUP,SUM,0,0,0,0,0,0,4,5.255272150039673 +3,SPOON,SUM,0,0,0,0,8,3,3,13.062561988830566 +3,,SUM,0,0,0,0,8,4,22,32.08527612686157 +3,, +4,, +4,BOWL,SUM,0,0,0,0,2,8,44,15.6176438331604 +4,CUP,SUM,0,0,0,0,0,1,13,6.98077392578125 +4,SPOON,SUM,0,0,0,0,0,1,4,10.228117942810059 +4,,SUM,0,0,0,0,2,10,61,32.82653570175171 +4,, +5,, +5,BOWL,SUM,1,0,1,0,16,36,204,0.0 +5,CUP,SUM,0,0,0,0,8,4,7,9.982322931289673 +5,SPOON,SUM,0,0,0,0,0,2,12,12.382373094558716 +5,,SUM,1,0,1,0,24,42,223,22.36469602584839 +5,, +6,, +6,BOWL,SUM,0,0,0,0,8,3,7,11.168004035949707 +6,CUP,SUM,0,0,0,0,0,0,6,4.450785875320435 +6,SPOON,SUM,0,0,0,0,0,1,16,12.690342903137207 +6,,SUM,0,0,0,0,8,4,29,28.30913281440735 +6,, +7,, +7,BOWL,SUM,0,0,0,0,8,0,6,11.877129793167114 +7,CUP,SUM,0,0,0,0,0,1,14,7.1929240226745605 +7,SPOON,SUM,0,0,0,0,10,0,8,14.81130599975586 +7,,SUM,0,0,0,0,18,1,28,33.881359815597534 +7,, +8,, +8,BOWL,SUM,0,0,0,0,0,0,4,8.286001920700073 +8,CUP,SUM,0,0,0,0,8,0,8,7.998787879943848 +8,SPOON,SUM,0,0,0,0,2,1,0,10.407246112823486 +8,,SUM,0,0,0,0,10,1,12,26.692035913467407 +8,, +9,, +9,BOWL,SUM,0,0,0,0,0,0,4,8.119594097137451 +9,CUP,SUM,0,0,0,0,0,0,11,7.226028919219971 +9,SPOON,SUM,0,0,0,0,8,1,6,15.145843029022217 +9,,SUM,0,0,0,0,8,1,21,30.49146604537964 +9,, +10,, +10,BOWL,SUM,0,0,0,0,0,0,3,7.55772590637207 +10,CUP,SUM,0,0,0,0,8,1,6,7.361175060272217 +10,SPOON,SUM,0,0,0,0,0,1,0,9.437873125076294 +10,,SUM,0,0,0,0,8,2,9,24.35677409172058 +10,, +11,, +11,BOWL,SUM,0,0,0,0,0,2,12,11.058701038360596 +11,CUP,SUM,0,0,0,0,0,0,9,6.512531995773315 +11,SPOON,SUM,0,0,0,0,0,3,22,13.890827894210815 +11,,SUM,0,0,0,0,0,5,43,31.462060928344727 +11,, +12,, +12,BOWL,SUM,1,0,1,0,8,68,204,0.0 +12,CUP,SUM,0,0,0,0,0,1,25,8.89723515510559 +12,SPOON,SUM,0,0,0,0,0,0,4,10.443244934082031 +12,,SUM,1,0,1,0,8,69,233,19.340480089187622 +12,, +13,, +13,BOWL,SUM,0,0,0,0,0,2,15,12.459026098251343 +13,CUP,SUM,0,0,0,0,0,0,4,4.932958126068115 +13,SPOON,SUM,0,0,0,0,8,2,12,16.124733209609985 +13,,SUM,0,0,0,0,8,4,31,33.51671743392944 +13,, +14,, +14,BOWL,SUM,0,0,0,0,0,0,3,7.806452989578247 +14,CUP,SUM,0,0,0,0,0,2,2,3.8844149112701416 +14,SPOON,SUM,1,0,1,0,4,86,196,0.0 +14,,SUM,1,0,1,0,4,88,201,11.690867900848389 +14,, +15,, +15,BOWL,SUM,0,0,0,0,8,2,16,14.482784032821655 +15,CUP,SUM,0,0,0,0,0,3,12,8.19175100326538 +15,SPOON,SUM,1,0,1,0,0,72,204,0.0 +15,,SUM,1,0,1,0,8,77,232,22.674535036087036 +15,, +16,, +16,BOWL,SUM,0,0,0,0,8,1,8,10.785851001739502 +16,CUP,SUM,0,0,0,0,0,3,17,8.56073808670044 +16,SPOON,SUM,0,0,0,0,0,8,81,25.5260329246521 +16,,SUM,0,0,0,0,8,12,106,44.87262201309204 +16,, +17,, +17,BOWL,SUM,1,0,1,0,0,31,204,0.0 +17,CUP,SUM,0,0,0,0,8,1,30,20.39389395713806 +17,SPOON,SUM,0,0,0,0,0,0,1,11.205448865890503 +17,,SUM,1,0,1,0,8,32,235,31.599342823028564 +17,, +18,, +18,BOWL,SUM,1,0,1,0,0,30,204,0.0 +18,CUP,SUM,0,0,0,0,0,1,6,5.273311138153076 +18,SPOON,SUM,0,0,0,0,0,2,1,10.706218004226685 +18,,SUM,1,0,1,0,0,33,211,15.97952914237976 +18,, +19,, +19,BOWL,SUM,0,0,0,0,8,5,16,14.567909955978394 +19,CUP,SUM,0,0,0,0,0,1,7,7.32523512840271 +19,SPOON,SUM,0,0,0,0,0,1,0,10.447367906570435 +19,,SUM,0,0,0,0,8,7,23,32.34051299095154 +19,, +20,, +20,BOWL,SUM,1,0,1,0,24,28,204,0.0 +20,CUP,SUM,0,0,0,0,8,1,8,13.280457019805908 +20,SPOON,SUM,0,0,0,0,0,2,16,16.712249040603638 +20,,SUM,1,0,1,0,32,31,228,29.992706060409546 +20,, +21,, +21,BOWL,SUM,0,0,0,0,0,1,14,11.126348972320557 +21,CUP,SUM,0,0,0,0,0,3,15,7.763705015182495 +21,SPOON,SUM,1,0,1,0,16,82,204,0.0 +21,,SUM,1,0,1,0,16,86,233,18.89005398750305 +21,, +22,, +22,BOWL,SUM,0,0,0,0,0,6,32,14.609799861907959 +22,CUP,SUM,0,0,0,0,0,0,5,5.957469940185547 +22,SPOON,SUM,0,0,0,0,0,3,33,18.1270489692688 +22,,SUM,0,0,0,0,0,9,70,38.694318771362305 +22,, +23,, +23,BOWL,SUM,0,0,0,0,0,1,2,8.711052179336548 +23,CUP,SUM,0,0,0,0,0,0,4,6.325968980789185 +23,SPOON,SUM,0,0,0,0,24,3,1,27.381815910339355 +23,,SUM,0,0,0,0,24,4,7,42.41883707046509 +23,, +24,, +24,BOWL,SUM,1,0,1,0,16,64,204,0.0 +24,CUP,SUM,0,0,0,0,0,21,173,51.07543706893921 +24,SPOON,SUM,0,0,0,0,0,3,32,18.02010488510132 +24,,SUM,1,0,1,0,16,88,409,69.09554195404053 +24,, +25,, +25,BOWL,SUM,0,0,0,0,8,1,4,13.44439697265625 +25,CUP,SUM,0,0,0,0,0,0,19,8.008301019668579 +25,SPOON,SUM,0,0,0,0,0,1,0,12.161245822906494 +25,,SUM,0,0,0,0,8,2,23,33.61394381523132 +25,, +26,, +26,BOWL,SUM,0,0,0,0,0,3,15,13.277894973754883 +26,CUP,SUM,0,0,0,0,0,0,11,10.962982892990112 +26,SPOON,SUM,0,0,0,0,0,0,26,17.281687021255493 +26,,SUM,0,0,0,0,0,3,52,41.52256488800049 +26,, +27,, +27,BOWL,SUM,0,0,0,0,0,1,0,7.927381992340088 +27,CUP,SUM,0,0,0,0,0,0,9,6.361402988433838 +27,SPOON,SUM,0,0,0,0,20,3,14,25.287647008895874 +27,,SUM,0,0,0,0,20,4,23,39.5764319896698 +27,, +28,, +28,BOWL,SUM,0,0,0,0,0,2,8,10.272153854370117 +28,CUP,SUM,0,0,0,0,0,0,18,8.025156021118164 +28,SPOON,SUM,1,0,1,0,40,56,204,0.0 +28,,SUM,1,0,1,0,40,58,230,18.29730987548828 +28,, +29,, +29,BOWL,SUM,0,0,0,0,0,0,6,10.29205584526062 +29,CUP,SUM,0,0,0,0,0,2,21,10.242625951766968 +29,SPOON,SUM,0,0,0,0,0,0,1,12.116567850112915 +29,,SUM,0,0,0,0,0,2,28,32.6512496471405 +29,, +30,, +30,BOWL,SUM,0,0,0,0,8,3,46,25.41502094268799 +30,CUP,SUM,0,0,0,0,0,0,16,9.71445107460022 +30,SPOON,SUM,0,0,0,0,0,2,15,14.874921083450317 +30,,SUM,0,0,0,0,8,5,77,50.004393100738525 +30,, +31,, +31,BOWL,SUM,0,0,0,0,0,2,0,8.627493858337402 +31,CUP,SUM,0,0,0,0,72,2,17,48.1632981300354 +31,SPOON,SUM,0,0,0,0,8,3,13,18.513195991516113 +31,,SUM,0,0,0,0,80,7,30,75.30398797988892 +31,, +32,, +32,BOWL,SUM,0,0,0,0,0,4,21,13.773112773895264 +32,CUP,SUM,0,0,0,0,24,3,8,21.706571102142334 +32,SPOON,SUM,0,0,0,0,0,1,5,13.453920125961304 +32,,SUM,0,0,0,0,24,8,34,48.9336040019989 +32,, +33,, +33,BOWL,SUM,0,0,0,0,0,0,23,15.409810066223145 +33,CUP,SUM,0,0,0,0,0,0,17,10.398370027542114 +33,SPOON,SUM,1,0,1,0,36,42,204,0.0 +33,,SUM,1,0,1,0,36,42,244,25.80818009376526 +33,, +34,, +34,BOWL,SUM,0,0,0,0,0,0,2,9.265542984008789 +34,CUP,SUM,0,0,0,0,0,0,11,7.431578874588013 +34,SPOON,SUM,0,0,0,0,2,1,0,12.320930004119873 +34,,SUM,0,0,0,0,2,1,13,29.018051862716675 +34,, +35,, +35,BOWL,SUM,0,0,0,0,8,4,18,21.273263931274414 +35,CUP,SUM,0,0,0,0,0,2,9,7.87228798866272 +35,SPOON,SUM,0,0,0,0,0,9,40,20.16071891784668 +35,,SUM,0,0,0,0,8,15,67,49.30627083778381 +35,, +36,, +36,BOWL,SUM,0,0,0,0,0,0,0,7.731735944747925 +36,CUP,SUM,0,0,0,0,0,1,23,8.87150502204895 +36,SPOON,SUM,0,0,0,0,0,1,4,11.947299003601074 +36,,SUM,0,0,0,0,0,2,27,28.55053997039795 +36,, +37,, +37,BOWL,SUM,0,0,0,0,0,2,30,15.662863969802856 +37,CUP,SUM,0,0,0,0,0,0,5,7.417399168014526 +37,SPOON,SUM,0,0,0,0,0,1,1,11.969904899597168 +37,,SUM,0,0,0,0,0,3,36,35.05016803741455 +37,, +38,, +38,BOWL,SUM,0,0,0,0,0,1,16,12.21382999420166 +38,CUP,SUM,1,0,1,0,8,18,51,0.0 +38,SPOON,SUM,1,0,1,0,8,85,204,0.0 +38,,SUM,2,0,2,0,16,104,271,12.21382999420166 +38,, +39,, +39,BOWL,SUM,0,0,0,0,0,0,13,13.705271005630493 +39,CUP,SUM,0,0,0,0,0,0,32,10.173105955123901 +39,SPOON,SUM,0,0,0,0,0,1,2,11.856977939605713 +39,,SUM,0,0,0,0,0,1,47,35.73535490036011 +39,, +40,, +40,BOWL,SUM,0,0,0,0,0,15,139,41.478070974349976 +40,CUP,SUM,0,0,0,0,0,1,14,11.863762855529785 +40,SPOON,SUM,0,0,0,0,0,1,9,13.706906080245972 +40,,SUM,0,0,0,0,0,17,162,67.04873991012573 +40,, +41,, +41,BOWL,SUM,0,0,0,0,0,0,7,10.941974878311157 +41,CUP,SUM,0,0,0,0,8,0,10,12.403064966201782 +41,SPOON,SUM,0,0,0,0,0,0,1,11.583636999130249 +41,,SUM,0,0,0,0,8,0,18,34.92867684364319 +41,, +42,, +42,BOWL,SUM,0,0,0,0,0,2,30,15.485456943511963 +42,CUP,SUM,0,0,0,0,0,1,22,9.095629930496216 +42,SPOON,SUM,0,0,0,0,0,1,5,13.356741189956665 +42,,SUM,0,0,0,0,0,4,57,37.937828063964844 +42,, +43,, +43,BOWL,SUM,0,0,0,0,8,15,80,31.662474870681763 +43,CUP,SUM,0,0,0,0,0,0,7,7.184250831604004 +43,SPOON,SUM,0,0,0,0,0,1,8,13.374405860900879 +43,,SUM,0,0,0,0,8,16,95,52.221131563186646 +43,, +44,, +44,BOWL,SUM,0,0,0,0,40,3,9,32.507761001586914 +44,CUP,SUM,0,0,0,0,0,0,11,8.499835968017578 +44,SPOON,SUM,0,0,0,0,2,1,3,13.63094186782837 +44,,SUM,0,0,0,0,42,4,23,54.63853883743286 +44,, +45,, +45,BOWL,SUM,0,0,0,0,8,1,26,21.200900077819824 +45,CUP,SUM,0,0,0,0,56,4,19,47.527421951293945 +45,SPOON,SUM,0,0,0,0,0,1,1,13.102787971496582 +45,,SUM,0,0,0,0,64,6,46,81.83111000061035 +45,, +46,, +46,BOWL,SUM,0,0,0,0,0,5,101,29.560819149017334 +46,CUP,SUM,1,0,1,0,0,39,153,0.0 +46,SPOON,SUM,0,0,0,0,0,1,0,12.06042194366455 +46,,SUM,1,0,1,0,0,45,254,41.621241092681885 +46,, +47,, +47,BOWL,SUM,0,0,0,0,0,2,55,25.000555992126465 +47,CUP,SUM,0,0,0,0,0,1,4,7.548130035400391 +47,SPOON,SUM,0,0,0,0,0,0,0,11.247426986694336 +47,,SUM,0,0,0,0,0,3,59,43.79611301422119 +47,, +48,, +48,BOWL,SUM,0,0,0,0,0,8,67,27.018110990524292 +48,CUP,SUM,0,0,0,0,8,1,4,11.367005109786987 +48,SPOON,SUM,0,0,0,0,0,0,20,16.628227949142456 +48,,SUM,0,0,0,0,8,9,91,55.013344049453735 +48,, +49,, +49,BOWL,SUM,1,0,1,0,0,82,204,0.0 +49,CUP,SUM,0,0,0,0,0,0,2,6.556262969970703 +49,SPOON,SUM,0,0,0,0,0,1,6,13.07364296913147 +49,,SUM,1,0,1,0,0,83,212,19.629905939102173 +49,, +50,, +50,BOWL,SUM,0,0,0,0,0,2,30,18.62345790863037 +50,CUP,SUM,0,0,0,0,0,2,8,8.239843130111694 +50,SPOON,SUM,0,0,0,0,24,3,10,29.568562030792236 +50,,SUM,0,0,0,0,24,7,48,56.4318630695343 +50,, +51,, +51,BOWL,SUM,0,0,0,0,0,1,8,10.541808128356934 +51,CUP,SUM,0,0,0,0,0,9,28,13.681670188903809 +51,SPOON,SUM,0,0,0,0,0,0,0,11.978713989257813 +51,,SUM,0,0,0,0,0,10,36,36.202192306518555 +51,, +52,, +52,BOWL,SUM,0,0,0,0,0,3,28,15.332066059112549 +52,CUP,SUM,0,0,0,0,40,1,6,33.51446509361267 +52,SPOON,SUM,0,0,0,0,8,0,4,16.747199058532715 +52,,SUM,0,0,0,0,48,4,38,65.59373021125793 +52,, +53,, +53,BOWL,SUM,0,0,0,0,0,1,22,19.81544804573059 +53,CUP,SUM,0,0,0,0,0,4,14,10.472105979919434 +53,SPOON,SUM,0,0,0,0,0,1,0,12.246814966201782 +53,,SUM,0,0,0,0,0,6,36,42.53436899185181 +53,, +54,, +54,BOWL,SUM,0,0,0,0,0,3,0,9.31118392944336 +54,CUP,SUM,0,0,0,0,0,2,9,7.5386879444122314 +54,SPOON,SUM,0,0,0,0,0,2,9,14.29137396812439 +54,,SUM,0,0,0,0,0,7,18,31.14124584197998 +54,, +55,, +55,BOWL,SUM,1,0,1,0,0,43,204,0.0 +55,CUP,SUM,0,0,0,0,0,2,29,19.920816898345947 +55,SPOON,SUM,0,0,0,0,0,2,4,12.95712399482727 +55,,SUM,1,0,1,0,0,47,237,32.87794089317322 +55,, +56,, +56,BOWL,SUM,0,0,0,0,0,1,12,10.506341934204102 +56,CUP,SUM,0,0,0,0,0,0,11,7.810647964477539 +56,SPOON,SUM,0,0,0,0,2,5,37,20.260270833969116 +56,,SUM,0,0,0,0,2,6,60,38.57726073265076 +56,, +57,, +57,BOWL,SUM,0,0,0,0,0,0,7,11.16220998764038 +57,CUP,SUM,0,0,0,0,0,0,6,7.841785907745361 +57,SPOON,SUM,1,0,1,0,0,58,204,0.0 +57,,SUM,1,0,1,0,0,58,217,19.003995895385742 +57,, +58,, +58,BOWL,SUM,0,0,0,0,0,2,11,11.295140981674194 +58,CUP,SUM,0,0,0,0,0,1,13,8.545651912689209 +58,SPOON,SUM,0,0,0,0,0,5,32,18.816601991653442 +58,,SUM,0,0,0,0,0,8,56,38.657394886016846 +58,, +59,, +59,BOWL,SUM,0,0,0,0,32,4,35,37.10544395446777 +59,CUP,SUM,0,0,0,0,0,0,2,5.746957063674927 +59,SPOON,SUM,0,0,0,0,0,1,4,13.116594076156616 +59,,SUM,0,0,0,0,32,5,41,55.968995094299316 +59,, +60,, +60,BOWL,SUM,0,0,0,0,0,0,6,11.471202850341797 +60,CUP,SUM,0,0,0,0,0,1,14,8.007760047912598 +60,SPOON,SUM,0,0,0,0,0,7,20,15.872313022613525 +60,,SUM,0,0,0,0,0,8,40,35.35127592086792 +60,, +61,, +61,BOWL,SUM,0,0,0,0,0,0,34,19.023357152938843 +61,CUP,SUM,0,0,0,0,0,4,21,9.41598391532898 +61,SPOON,SUM,0,0,0,0,0,0,1,11.418191194534302 +61,,SUM,0,0,0,0,0,4,56,39.857532262802124 +61,, +62,, +62,BOWL,SUM,0,0,0,0,0,3,29,13.806430101394653 +62,CUP,SUM,0,0,0,0,8,0,2,11.367779970169067 +62,SPOON,SUM,0,0,0,0,0,0,8,12.685835838317871 +62,,SUM,0,0,0,0,8,3,39,37.86004590988159 +62,, +63,, +63,BOWL,SUM,1,0,1,0,16,62,204,0.0 +63,CUP,SUM,0,0,0,0,0,5,9,9.952462911605835 +63,SPOON,SUM,0,0,0,0,0,2,36,19.851469039916992 +63,,SUM,1,0,1,0,16,69,249,29.803931951522827 +63,, +64,, +64,BOWL,SUM,1,0,1,0,0,22,204,0.0 +64,CUP,SUM,0,0,0,0,0,0,7,8.96185302734375 +64,SPOON,SUM,0,0,0,0,0,0,5,13.860907077789307 +64,,SUM,1,0,1,0,0,22,216,22.822760105133057 +64,, +65,, +65,BOWL,SUM,0,0,0,0,8,1,4,14.96309208869934 +65,CUP,SUM,0,0,0,0,0,0,21,16.118754148483276 +65,SPOON,SUM,0,0,0,0,0,1,0,17.147149085998535 +65,,SUM,0,0,0,0,8,2,25,48.22899532318115 +65,, +66,, +66,BOWL,SUM,0,0,0,0,0,0,4,14.041270017623901 +66,CUP,SUM,1,0,1,0,8,29,51,0.0 +66,SPOON,SUM,0,0,0,0,0,2,6,21.430290937423706 +66,,SUM,1,0,1,0,8,31,61,35.47156095504761 +66,, +67,, +67,BOWL,SUM,0,0,0,0,0,0,5,16.31893301010132 +67,CUP,SUM,0,0,0,0,0,0,4,13.015959978103638 +67,SPOON,SUM,0,0,0,0,0,8,32,26.566251039505005 +67,,SUM,0,0,0,0,0,8,41,55.90114402770996 +67,, +68,, +68,BOWL,SUM,0,0,0,0,0,4,5,17.156047821044922 +68,CUP,SUM,0,0,0,0,16,2,17,40.60695004463196 +68,SPOON,SUM,0,0,0,0,0,0,5,19.6299729347229 +68,,SUM,0,0,0,0,16,6,27,77.39297080039978 +68,, +69,, +69,BOWL,SUM,0,0,0,0,0,0,1,15.722517013549805 +69,CUP,SUM,0,0,0,0,0,1,8,14.97144103050232 +69,SPOON,SUM,0,0,0,0,0,0,1,19.38455605506897 +69,,SUM,0,0,0,0,0,1,10,50.078514099121094 +69,, +70,, +70,BOWL,SUM,0,0,0,0,8,3,34,45.04253697395325 +70,CUP,SUM,0,0,0,0,48,3,4,96.3755989074707 +70,SPOON,SUM,0,0,0,0,0,1,1,20.96127700805664 +70,,SUM,0,0,0,0,56,7,39,162.3794128894806 +70,, +71,, +71,BOWL,SUM,0,0,0,0,8,1,2,30.286651134490967 +71,CUP,SUM,0,0,0,0,0,0,23,19.809657096862793 +71,SPOON,SUM,0,0,0,0,0,3,20,25.906453847885132 +71,,SUM,0,0,0,0,8,4,45,76.00276207923889 +71,, +72,, +72,BOWL,SUM,0,0,0,0,0,9,8,18.753429889678955 +72,CUP,SUM,0,0,0,0,0,0,3,16.55836319923401 +72,SPOON,SUM,0,0,0,0,0,0,4,21.050112009048462 +72,,SUM,0,0,0,0,0,9,15,56.361905097961426 +72,, +73,, +73,BOWL,SUM,0,0,0,0,0,1,4,18.710783004760742 +73,CUP,SUM,0,0,0,0,8,1,5,32.107779026031494 +73,SPOON,SUM,0,0,0,0,0,4,14,24.72735095024109 +73,,SUM,0,0,0,0,8,6,23,75.54591298103333 +73,, +74,, +74,BOWL,SUM,0,0,0,0,0,1,9,21.384639978408813 +74,CUP,SUM,0,0,0,0,0,3,18,21.04399585723877 +74,SPOON,SUM,0,0,0,0,16,11,81,67.34350681304932 +74,,SUM,0,0,0,0,16,15,108,109.7721426486969 +74,, +75,, +75,BOWL,SUM,0,0,0,0,0,1,1,19.803544998168945 +75,CUP,SUM,0,0,0,0,0,12,12,23.10753607749939 +75,SPOON,SUM,0,0,0,0,0,1,1,22.766600847244263 +75,,SUM,0,0,0,0,0,14,14,65.6776819229126 +75,, +76,, +76,BOWL,SUM,0,0,0,0,0,0,3,19.689048051834106 +76,CUP,SUM,0,0,0,0,0,0,9,18.0261709690094 +76,SPOON,SUM,0,0,0,0,8,2,24,45.245166063308716 +76,,SUM,0,0,0,0,8,2,36,82.96038508415222 +76,, +77,, +77,BOWL,SUM,0,0,0,0,8,3,32,44.15650296211243 +77,CUP,SUM,0,0,0,0,0,11,130,49.6575391292572 +77,SPOON,SUM,0,0,0,0,0,0,1,23.591279983520508 +77,,SUM,0,0,0,0,8,14,163,117.40532207489014 +77,, +78,, +78,BOWL,SUM,0,0,0,0,0,0,3,21.63160800933838 +78,CUP,SUM,0,0,0,0,0,1,35,23.42210292816162 +78,SPOON,SUM,0,0,0,0,0,0,1,24.503586053848267 +78,,SUM,0,0,0,0,0,1,39,69.55729699134827 +78,, +79,, +79,BOWL,SUM,0,0,0,0,0,4,17,25.353588104248047 +79,CUP,SUM,0,0,0,0,0,0,9,21.17424488067627 +79,SPOON,SUM,0,0,0,0,0,1,14,27.04420804977417 +79,,SUM,0,0,0,0,0,5,40,73.57204103469849 +79,, +80,, +80,BOWL,SUM,0,0,0,0,0,11,48,34.152053117752075 +80,CUP,SUM,0,0,0,0,8,0,5,38.54307198524475 +80,SPOON,SUM,0,0,0,0,8,6,23,50.80345392227173 +80,,SUM,0,0,0,0,16,17,76,123.49857902526855 +80,, +81,, +81,BOWL,SUM,0,0,0,0,0,0,14,24.944035053253174 +81,CUP,SUM,0,0,0,0,0,2,6,22.62965703010559 +81,SPOON,SUM,0,0,0,0,8,5,28,53.3036150932312 +81,,SUM,0,0,0,0,8,7,48,100.87730717658997 +81,, +82,, +82,BOWL,SUM,0,0,0,0,0,2,4,23.01076102256775 +82,CUP,SUM,0,0,0,0,0,0,7,22.0569429397583 +82,SPOON,SUM,0,0,0,0,0,0,4,26.545329093933105 +82,,SUM,0,0,0,0,0,2,15,71.61303305625916 +82,, +83,, +83,BOWL,SUM,1,0,1,0,8,16,204,0.0 +83,CUP,SUM,1,0,1,0,0,24,51,0.0 +83,SPOON,SUM,0,0,0,0,0,1,6,30.773342847824097 +83,,SUM,2,0,2,0,8,41,261,30.773342847824097 +83,, +84,, +84,BOWL,SUM,0,0,0,0,0,3,24,27.948878049850464 +84,CUP,SUM,0,0,0,0,0,3,10,25.068488836288452 +84,SPOON,SUM,0,0,0,0,0,1,12,30.626184225082397 +84,,SUM,0,0,0,0,0,7,46,83.64355111122131 +84,, +85,, +85,BOWL,SUM,0,0,0,0,0,5,10,28.260425090789795 +85,CUP,SUM,0,0,0,0,0,0,9,23.8317449092865 +85,SPOON,SUM,0,0,0,0,0,0,2,29.55102014541626 +85,,SUM,0,0,0,0,0,5,21,81.64319014549255 +85,, +86,, +86,BOWL,SUM,0,0,0,0,0,0,10,27.73209500312805 +86,CUP,SUM,0,0,0,0,0,1,10,25.82732319831848 +86,SPOON,SUM,1,0,1,0,8,61,204,0.0 +86,,SUM,1,0,1,0,8,62,224,53.55941820144653 +86,, +87,, +87,BOWL,SUM,0,0,0,0,0,2,20,31.206475973129272 +87,CUP,SUM,0,0,0,0,6,1,21,29.47005581855774 +87,SPOON,SUM,0,0,0,0,0,21,52,40.739145040512085 +87,,SUM,0,0,0,0,6,24,93,101.4156768321991 +87,, +88,, +88,BOWL,SUM,0,0,0,0,0,3,19,33.0957670211792 +88,CUP,SUM,0,0,0,0,0,1,4,24.39895796775818 +88,SPOON,SUM,0,0,0,0,0,0,0,30.506335973739624 +88,,SUM,0,0,0,0,0,4,23,88.001060962677 +88,, +89,, +89,BOWL,SUM,0,0,0,0,8,1,9,49.990017890930176 +89,CUP,SUM,0,0,0,0,0,0,6,24.002909898757935 +89,SPOON,SUM,0,0,0,0,0,4,0,29.419127941131592 +89,,SUM,0,0,0,0,8,5,15,103.4120557308197 +89,, +90,, +90,BOWL,SUM,0,0,0,0,0,2,19,33.06211185455322 +90,CUP,SUM,0,0,0,0,0,4,17,28.42617678642273 +90,SPOON,SUM,0,0,0,0,0,2,0,29.618002891540527 +90,,SUM,0,0,0,0,0,8,36,91.10629153251648 +90,, +91,, +91,BOWL,SUM,0,0,0,0,0,1,1,25.663330078125 +91,CUP,SUM,0,0,0,0,0,1,27,34.9258451461792 +91,SPOON,SUM,0,0,0,0,0,1,6,32.08036494255066 +91,,SUM,0,0,0,0,0,3,34,92.66954016685486 +91,, +92,, +92,BOWL,SUM,0,0,0,0,0,1,8,27.704323053359985 +92,CUP,SUM,0,0,0,0,8,2,21,56.95499396324158 +92,SPOON,SUM,0,0,0,0,8,2,4,53.45513105392456 +92,,SUM,0,0,0,0,16,5,33,138.11444807052612 +92,, +93,, +93,BOWL,SUM,0,0,0,0,0,0,13,29.481024980545044 +93,CUP,SUM,0,0,0,0,0,1,5,25.398113012313843 +93,SPOON,SUM,0,0,0,0,8,2,14,58.326716899871826 +93,,SUM,0,0,0,0,8,3,32,113.20585489273071 +93,, +94,, +94,BOWL,SUM,0,0,0,0,0,1,5,26.875535011291504 +94,CUP,SUM,1,0,1,0,0,39,357,0.0 +94,SPOON,SUM,0,0,0,0,2,3,16,34.51984095573425 +94,,SUM,1,0,1,0,2,43,378,61.39537596702576 +94,, +95,, +95,BOWL,SUM,0,0,0,0,0,3,19,32.01110911369324 +95,CUP,SUM,1,0,1,0,0,23,51,0.0 +95,SPOON,SUM,0,0,0,0,8,0,0,54.63603901863098 +95,,SUM,1,0,1,0,8,26,70,86.64714813232422 +95,, +96,, +96,BOWL,SUM,0,0,0,0,0,3,45,39.32174110412598 +96,CUP,SUM,1,0,1,0,8,64,51,0.0 +96,SPOON,SUM,0,0,0,0,8,4,12,19.99161195755005 +96,,SUM,1,0,1,0,16,71,108,59.313353061676025 +96,, +97,, +97,BOWL,SUM,0,0,0,0,0,0,0,25.710938930511475 +97,CUP,SUM,0,0,0,0,0,2,4,25.750849962234497 +97,SPOON,SUM,0,0,0,0,0,2,16,33.67877006530762 +97,,SUM,0,0,0,0,0,4,20,85.14055895805359 +97,, +98,, +98,BOWL,SUM,0,0,0,0,0,9,30,33.88756799697876 +98,CUP,SUM,0,0,0,0,0,0,2,24.371878147125244 +98,SPOON,SUM,0,0,0,0,8,8,17,59.70134711265564 +98,,SUM,0,0,0,0,8,17,49,117.96079325675964 +98,, +99,, +99,BOWL,SUM,0,0,0,0,0,1,31,32.74997591972351 +99,CUP,SUM,0,0,0,0,0,2,6,26.52825689315796 +99,SPOON,SUM,1,0,1,0,20,46,204,0.0 +99,,SUM,1,0,1,0,20,49,241,59.27823281288147 +99,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/paper/7.BoxyHrSim.csv b/cram_knowrob/cram_knowrob_vr/experiments/paper/7.BoxyHrSim.csv new file mode 100644 index 0000000000..c20f0b1391 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/paper/7.BoxyHrSim.csv @@ -0,0 +1,1209 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,4,3,12.0770499706 +0,CUP,SUM,0,0,0,0,0,12,35,21.5131111145 +0,SPOON,SUM,0,0,0,0,0,2,0,10.6741280556 +0,,SUM,0,0,0,0,0,18,38,44.2642891407 +0,,,,,,,,,, +1,,,,,,,,,, +1,BOWL,SUM,0,0,0,0,8,1,13,16.4592130184 +1,CUP,SUM,0,0,0,0,0,6,79,32.2855000496 +1,SPOON,SUM,0,0,0,0,8,7,25,25.8515970707 +1,,SUM,0,0,0,0,16,14,117,74.5963101387 +1,,,,,,,,,, +2,,,,,,,,,, +2,BOWL,SUM,0,0,0,0,24,3,7,25.2449879646 +2,CUP,SUM,0,0,0,0,0,5,16,16.647578001 +2,SPOON,SUM,0,0,0,0,8,10,14,22.2254371643 +2,,SUM,0,0,0,0,32,18,37,64.11800313 +2,,,,,,,,,, +3,,,,,,,,,, +3,BOWL,SUM,0,0,0,0,0,12,18,16.5866129398 +3,CUP,SUM,1,0,0,1,0,45,61,0 +3,SPOON,SUM,0,0,0,0,8,3,4,19.6455690861 +3,,SUM,1,0,0,1,8,60,83,36.2321820259 +3,,,,,,,,,, +4,,,,,,,,,, +4,BOWL,SUM,0,0,0,0,0,8,65,40.1422801018 +4,CUP,SUM,0,0,0,0,14,4,29,25.7754869461 +4,SPOON,SUM,0,0,0,0,8,2,1,14.8742778301 +4,,SUM,0,0,0,0,22,14,95,80.792044878 +4,,,,,,,,,, +5,,,,,,,,,, +5,BOWL,SUM,0,0,0,0,0,4,9,18.9554190636 +5,CUP,SUM,0,0,0,0,0,4,2,7.2857279778 +5,SPOON,SUM,0,0,0,0,0,5,4,13.9568781853 +5,,SUM,0,0,0,0,0,13,15,40.1980252266 +5,,,,,,,,,, +6,,,,,,,,,, +6,BOWL,SUM,0,0,0,0,0,1,2,9.4788701534 +6,CUP,SUM,0,0,0,0,0,20,36,38.3783960342 +6,SPOON,SUM,0,0,0,0,0,1,17,21.0064430237 +6,,SUM,0,0,0,0,0,22,55,68.8637092113 +6,,,,,,,,,, +7,,,,,,,,,, +7,BOWL,SUM,0,0,0,0,2,3,9,18.1349329948 +7,CUP,SUM,0,0,0,0,0,3,39,18.9520041943 +7,SPOON,SUM,0,0,0,0,0,3,4,13.5247941017 +7,,SUM,0,0,0,0,2,9,52,50.6117312908 +7,,,,,,,,,, +8,,,,,,,,,, +8,BOWL,SUM,0,0,0,0,0,5,1,9.4055759907 +8,CUP,SUM,0,0,0,0,0,26,44,61.6272270679 +8,SPOON,SUM,0,0,0,0,0,1,6,12.524600029 +8,,SUM,0,0,0,0,0,32,51,83.5574030876 +8,,,,,,,,,, +9,,,,,,,,,, +9,BOWL,SUM,0,0,0,0,26,4,5,25.8357551098 +9,CUP,SUM,0,0,0,0,0,11,14,15.7592709064 +9,SPOON,SUM,0,0,0,0,0,4,10,17.956594944 +9,,SUM,0,0,0,0,26,19,29,59.5516209602 +9,,,,,,,,,, +10,,,,,,,,,, +10,BOWL,SUM,0,0,0,0,0,6,21,19.8333590031 +10,CUP,SUM,0,0,0,0,0,2,19,11.7307929993 +10,SPOON,SUM,0,0,0,0,42,6,25,40.6628680229 +10,,SUM,0,0,0,0,42,14,65,72.2270200253 +10,,,,,,,,,, +11,,,,,,,,,, +11,BOWL,SUM,0,0,0,0,0,12,0,8.8747339249 +11,CUP,SUM,0,0,0,0,10,0,9,13.4323480129 +11,SPOON,SUM,0,0,0,0,0,3,9,16.3990008831 +11,,SUM,0,0,0,0,10,15,18,38.7060828209 +11,,,,,,,,,, +12,,,,,,,,,, +12,BOWL,SUM,0,0,0,0,0,6,9,12.6035349369 +12,CUP,SUM,0,0,0,0,0,4,13,13.3185379505 +12,SPOON,SUM,0,0,0,0,0,1,0,10.675853014 +12,,SUM,0,0,0,0,0,11,22,36.5979259014 +12,,,,,,,,,, +13,,,,,,,,,, +13,BOWL,SUM,0,0,0,0,0,2,12,13.078592062 +13,CUP,SUM,0,0,0,0,2,5,60,29.4100151062 +13,SPOON,SUM,0,0,0,0,0,29,29,27.0527291298 +13,,SUM,0,0,0,0,2,36,101,69.541336298 +13,,,,,,,,,, +14,,,,,,,,,, +14,BOWL,SUM,0,0,0,0,2,6,2,11.0544989109 +14,CUP,SUM,0,0,0,0,0,13,9,14.832267046 +14,SPOON,SUM,0,0,0,0,16,20,8,29.2832632065 +14,,SUM,0,0,0,0,18,39,19,55.1700291634 +14,,,,,,,,,, +15,,,,,,,,,, +15,BOWL,SUM,0,0,0,0,6,2,6,17.9243249893 +15,CUP,SUM,0,0,0,0,0,1,13,14.1382060051 +15,SPOON,SUM,0,0,0,0,0,0,6,12.4566779137 +15,,SUM,0,0,0,0,6,3,25,44.5192089081 +15,,,,,,,,,, +16,,,,,,,,,, +16,BOWL,SUM,0,0,0,0,0,3,13,14.4290730953 +16,CUP,SUM,0,0,0,0,0,2,44,24.1614060402 +16,SPOON,SUM,0,0,0,0,0,0,6,13.8570261002 +16,,SUM,0,0,0,0,0,5,63,52.4475052357 +16,,,,,,,,,, +17,,,,,,,,,, +17,BOWL,SUM,0,0,0,0,8,8,10,24.2454550266 +17,CUP,SUM,0,0,0,0,2,9,8,9.9552350044 +17,SPOON,SUM,0,0,0,0,0,5,12,18.2358000278 +17,,SUM,0,0,0,0,10,22,30,52.4364900589 +17,,,,,,,,,, +18,,,,,,,,,, +18,BOWL,SUM,0,0,0,0,0,1,4,9.9994699955 +18,CUP,SUM,0,0,0,0,0,0,10,12.6149709225 +18,SPOON,SUM,0,0,0,0,0,1,6,14.8080019951 +18,,SUM,0,0,0,0,0,2,20,37.4224429131 +18,,,,,,,,,, +19,,,,,,,,,, +19,BOWL,SUM,0,0,0,0,0,3,9,12.109110117 +19,CUP,SUM,0,0,0,0,8,1,13,16.4277179241 +19,SPOON,SUM,0,0,0,0,2,2,20,21.8989338875 +19,,SUM,0,0,0,0,10,6,42,50.4357619286 +19,,,,,,,,,, +20,,,,,,,,,, +20,BOWL,SUM,0,0,0,0,0,1,8,12.2697238922 +20,CUP,SUM,0,0,0,0,0,4,9,10.1100721359 +20,SPOON,SUM,0,0,0,0,0,1,28,24.0044310093 +20,,SUM,0,0,0,0,0,6,45,46.3842270374 +20,,,,,,,,,, +21,,,,,,,,,, +21,BOWL,SUM,0,0,0,0,0,3,2,10.610532999 +21,CUP,SUM,1,0,0,1,0,36,121,0 +21,SPOON,SUM,0,0,0,0,0,4,2,12.2207608223 +21,,SUM,1,0,0,1,0,43,125,22.8312938213 +21,,,,,,,,,, +22,,,,,,,,,, +22,BOWL,SUM,0,0,0,0,8,2,10,15.596296072 +22,CUP,SUM,0,0,0,0,8,1,37,23.885215044 +22,SPOON,SUM,0,0,0,0,2,6,20,22.7432351112 +22,,SUM,0,0,0,0,18,9,67,62.2247462273 +22,,,,,,,,,, +23,,,,,,,,,, +23,BOWL,SUM,0,0,0,0,0,1,4,11.2698709965 +23,CUP,SUM,0,0,0,0,0,3,9,13.4256980419 +23,SPOON,SUM,0,0,0,0,2,9,8,14.5545458794 +23,,SUM,0,0,0,0,2,13,21,39.2501149178 +23,,,,,,,,,, +24,,,,,,,,,, +24,BOWL,SUM,0,0,0,0,18,1,1,16.1752681732 +24,CUP,SUM,0,0,0,0,0,24,66,43.9348459244 +24,SPOON,SUM,0,0,0,0,8,5,1,16.5965330601 +24,,SUM,0,0,0,0,26,30,68,76.7066471577 +24,,,,,,,,,, +25,,,,,,,,,, +25,BOWL,SUM,0,0,0,0,8,20,36,33.8320538998 +25,CUP,SUM,0,0,0,0,0,1,8,7.577837944 +25,SPOON,SUM,0,0,0,0,8,56,55,44.5961520672 +25,,SUM,0,0,0,0,16,77,99,86.006043911 +25,,,,,,,,,, +26,,,,,,,,,, +26,BOWL,SUM,0,0,0,0,0,2,0,8.8721039295 +26,CUP,SUM,0,0,0,0,0,1,46,21.7091929913 +26,SPOON,SUM,0,0,0,0,0,1,0,11.2764949799 +26,,SUM,0,0,0,0,0,4,46,41.8577919006 +26,,,,,,,,,, +27,,,,,,,,,, +27,BOWL,SUM,0,0,0,0,6,1,1,11.3495268822 +27,CUP,SUM,0,0,0,0,0,10,45,26.6689720154 +27,SPOON,SUM,0,0,0,0,4,0,11,19.8388800621 +27,,SUM,0,0,0,0,10,11,57,57.8573789597 +27,,,,,,,,,, +28,,,,,,,,,, +28,BOWL,SUM,0,0,0,0,0,4,20,19.2267580032 +28,CUP,SUM,0,0,0,0,8,18,65,33.8135020733 +28,SPOON,SUM,0,0,0,0,8,9,19,28.0125939846 +28,,SUM,0,0,0,0,16,31,104,81.0528540611 +28,,,,,,,,,, +29,,,,,,,,,, +29,BOWL,SUM,0,0,0,0,0,1,18,21.2568039894 +29,CUP,SUM,0,0,0,0,0,2,13,13.3974201679 +29,SPOON,SUM,0,0,0,0,0,1,20,20.3068358898 +29,,SUM,0,0,0,0,0,4,51,54.9610600471 +29,,,,,,,,,, +30,,,,,,,,,, +30,BOWL,SUM,0,0,0,0,8,6,1,13.3464961052 +30,CUP,SUM,0,0,0,0,0,9,153,62.9682660103 +30,SPOON,SUM,0,0,0,0,0,4,42,32.0627551079 +30,,SUM,0,0,0,0,8,19,196,108.3775172234 +30,,,,,,,,,, +31,,,,,,,,,, +31,BOWL,SUM,0,0,0,0,0,17,28,21.7850570679 +31,CUP,SUM,0,0,0,0,0,6,26,20.7700068951 +31,SPOON,SUM,0,0,0,0,0,0,6,13.8342058659 +31,,SUM,0,0,0,0,0,23,60,56.3892698288 +31,,,,,,,,,, +32,,,,,,,,,, +32,BOWL,SUM,0,0,0,0,0,5,12,14.6130449772 +32,CUP,SUM,0,0,0,0,0,2,9,9.6256320477 +32,SPOON,SUM,0,0,0,0,0,3,14,18.9390010834 +32,,SUM,0,0,0,0,0,10,35,43.1776781082 +32,,,,,,,,,, +33,,,,,,,,,, +33,BOWL,SUM,0,0,0,0,0,0,8,12.6596801281 +33,CUP,SUM,0,0,0,0,2,1,35,21.7693572044 +33,SPOON,SUM,0,0,0,0,0,2,4,17.3370859623 +33,,SUM,0,0,0,0,2,3,47,51.7661232948 +33,,,,,,,,,, +34,,,,,,,,,, +34,BOWL,SUM,0,0,0,0,0,2,7,14.7470958233 +34,CUP,SUM,0,0,0,0,0,41,74,61.2847468853 +34,SPOON,SUM,0,0,0,0,8,6,21,34.50147295 +34,,SUM,0,0,0,0,8,49,102,110.5333156586 +34,,,,,,,,,, +35,,,,,,,,,, +35,BOWL,SUM,0,0,0,0,0,4,28,20.1462049484 +35,CUP,SUM,0,0,0,0,24,14,28,28.7611598969 +35,SPOON,SUM,0,0,0,0,0,0,0,11.1654279232 +35,,SUM,0,0,0,0,24,18,56,60.0727927685 +35,,,,,,,,,, +36,,,,,,,,,, +36,BOWL,SUM,0,0,0,0,2,2,10,14.1225540638 +36,CUP,SUM,0,0,0,0,0,5,34,19.0679769516 +36,SPOON,SUM,0,0,0,0,40,5,6,42.3521690369 +36,,SUM,0,0,0,0,42,12,50,75.5427000523 +36,,,,,,,,,, +37,,,,,,,,,, +37,BOWL,SUM,0,0,0,0,0,2,8,12.1063091755 +37,CUP,SUM,0,0,0,0,0,10,41,23.8161900043 +37,SPOON,SUM,0,0,0,0,0,2,18,27.7428760529 +37,,SUM,0,0,0,0,0,14,67,63.6653752327 +37,,,,,,,,,, +38,,,,,,,,,, +38,BOWL,SUM,0,0,0,0,24,60,111,70.9372160435 +38,CUP,SUM,0,0,0,0,0,5,58,24.9346420765 +38,SPOON,SUM,0,0,0,0,0,3,16,18.1208519936 +38,,SUM,0,0,0,0,24,68,185,113.9927101135 +38,,,,,,,,,, +39,,,,,,,,,, +39,BOWL,SUM,0,0,0,0,0,1,5,12.6435592175 +39,CUP,SUM,0,0,0,0,0,4,37,19.9158611298 +39,SPOON,SUM,0,0,0,0,0,5,0,12.2953240871 +39,,SUM,0,0,0,0,0,10,42,44.8547444344 +39,,,,,,,,,, +40,,,,,,,,,, +40,BOWL,SUM,0,0,0,0,0,1,6,13.1143610477 +40,CUP,SUM,0,0,0,0,8,5,30,30.2739360332 +40,SPOON,SUM,0,0,0,0,0,3,0,11.0517370701 +40,,SUM,0,0,0,0,8,9,36,54.4400341511 +40,,,,,,,,,, +41,,,,,,,,,, +41,BOWL,SUM,0,0,0,0,8,0,2,12.2236318588 +41,CUP,SUM,0,0,0,0,0,6,20,15.7278051376 +41,SPOON,SUM,0,0,0,0,0,4,0,11.9923708439 +41,,SUM,0,0,0,0,8,10,22,39.9438078403 +41,,,,,,,,,, +42,,,,,,,,,, +42,BOWL,SUM,0,0,0,0,0,1,0,8.2760689259 +42,CUP,SUM,0,0,0,0,0,16,90,42.3932721615 +42,SPOON,SUM,0,0,0,0,0,6,52,37.353908062 +42,,SUM,0,0,0,0,0,23,142,88.0232491493 +42,,,,,,,,,, +43,,,,,,,,,, +43,BOWL,SUM,0,0,0,0,0,1,6,13.2893970013 +43,CUP,SUM,0,0,0,0,0,4,9,9.6974420547 +43,SPOON,SUM,0,0,0,0,0,1,3,14.2883741856 +43,,SUM,0,0,0,0,0,6,18,37.2752132416 +43,,,,,,,,,, +44,,,,,,,,,, +44,BOWL,SUM,0,0,0,0,0,4,4,12.9398999214 +44,CUP,SUM,0,0,0,0,0,15,34,22.6941149235 +44,SPOON,SUM,0,0,0,0,0,7,33,26.6158480644 +44,,SUM,0,0,0,0,0,26,71,62.2498629093 +44,,,,,,,,,, +45,,,,,,,,,, +45,BOWL,SUM,0,0,0,0,38,3,6,28.3603248596 +45,CUP,SUM,0,0,0,0,0,6,35,24.9356381893 +45,SPOON,SUM,0,0,0,0,10,14,4,18.4223470688 +45,,SUM,0,0,0,0,48,23,45,71.7183101177 +45,,,,,,,,,, +46,,,,,,,,,, +46,BOWL,SUM,0,0,0,0,0,2,2,9.0883131027 +46,CUP,SUM,0,0,0,0,0,25,58,47.5299360752 +46,SPOON,SUM,0,0,0,0,0,0,1,12.6433839798 +46,,SUM,0,0,0,0,0,27,61,69.2616331577 +46,,,,,,,,,, +47,,,,,,,,,, +47,BOWL,SUM,0,0,0,0,0,9,77,44.9056859016 +47,CUP,SUM,1,0,0,1,0,29,67,0 +47,SPOON,SUM,0,0,0,0,0,4,3,13.7421839237 +47,,SUM,1,0,0,1,0,42,147,58.6478698254 +47,,,,,,,,,, +48,,,,,,,,,, +48,BOWL,SUM,0,0,0,0,0,8,58,36.7876229286 +48,CUP,SUM,0,0,0,0,0,0,9,10.1302611828 +48,SPOON,SUM,0,0,0,0,24,3,3,23.9981780052 +48,,SUM,0,0,0,0,24,11,70,70.9160621166 +48,,,,,,,,,, +49,,,,,,,,,, +49,BOWL,SUM,0,0,0,0,2,0,9,14.1768369675 +49,CUP,SUM,0,0,0,0,16,3,18,18.8937339783 +49,SPOON,SUM,0,0,0,0,16,2,0,19.0441339016 +49,,SUM,0,0,0,0,34,5,27,52.1147048473 +49,,,,,,,,,, +50,,,,,,,,,, +50,BOWL,SUM,0,0,0,0,0,60,77,48.2240679264 +50,CUP,SUM,0,0,0,0,0,0,23,15.5188031197 +50,SPOON,SUM,0,0,0,0,2,3,0,13.3251340389 +50,,SUM,0,0,0,0,2,63,100,77.068005085 +50,,,,,,,,,, +51,,,,,,,,,, +51,BOWL,SUM,0,0,0,0,0,4,17,17.0555179119 +51,CUP,SUM,0,0,0,0,0,6,41,20.6041810513 +51,SPOON,SUM,0,0,0,0,0,0,0,11.5670788288 +51,,SUM,0,0,0,0,0,10,58,49.226777792 +51,,,,,,,,,, +52,,,,,,,,,, +52,BOWL,SUM,0,0,0,0,0,2,1,9.9776711464 +52,CUP,SUM,0,0,0,0,2,32,204,82.8793389797 +52,SPOON,SUM,0,0,0,0,0,5,3,13.6310341358 +52,,SUM,0,0,0,0,2,39,208,106.4880442619 +52,,,,,,,,,, +53,,,,,,,,,, +53,BOWL,SUM,0,0,0,0,0,5,4,11.402338028 +53,CUP,SUM,0,0,0,0,8,4,32,21.6910271645 +53,SPOON,SUM,0,0,0,0,8,3,8,19.1797890663 +53,,SUM,0,0,0,0,16,12,44,52.2731542587 +53,,,,,,,,,, +54,,,,,,,,,, +54,BOWL,SUM,0,0,0,0,8,1,1,12.7617070675 +54,CUP,SUM,0,0,0,0,2,7,31,19.4559972286 +54,SPOON,SUM,0,0,0,0,0,0,6,15.4991118908 +54,,SUM,0,0,0,0,10,8,38,47.7168161869 +54,,,,,,,,,, +55,,,,,,,,,, +55,BOWL,SUM,0,0,0,0,0,2,8,11.6451871395 +55,CUP,SUM,1,0,0,1,8,35,141,0 +55,SPOON,SUM,0,0,0,0,0,3,9,16.8259308338 +55,,SUM,1,0,0,1,8,40,158,28.4711179733 +55,,,,,,,,,, +56,,,,,,,,,, +56,BOWL,SUM,0,0,0,0,0,3,11,13.6318740845 +56,CUP,SUM,1,0,0,1,0,29,91,0 +56,SPOON,SUM,0,0,0,0,16,8,4,22.6801540852 +56,,SUM,1,0,0,1,16,40,106,36.3120281696 +56,,,,,,,,,, +57,,,,,,,,,, +57,BOWL,SUM,0,0,0,0,0,4,0,9.3105330467 +57,CUP,SUM,0,0,0,0,16,5,9,22.2582759857 +57,SPOON,SUM,0,0,0,0,16,3,5,21.0431239605 +57,,SUM,0,0,0,0,32,12,14,52.6119329929 +57,,,,,,,,,, +58,,,,,,,,,, +58,BOWL,SUM,0,0,0,0,24,7,1,19.3248310089 +58,CUP,SUM,0,0,0,0,16,13,9,36.0011079311 +58,SPOON,SUM,0,0,0,0,16,1,4,20.5024440289 +58,,SUM,0,0,0,0,56,21,14,75.8283829689 +58,,,,,,,,,, +59,,,,,,,,,, +59,BOWL,SUM,0,0,0,0,6,22,60,42.6724689007 +59,CUP,SUM,0,0,0,0,0,6,10,10.859359026 +59,SPOON,SUM,0,0,0,0,8,4,6,22.067305088 +59,,SUM,0,0,0,0,14,32,76,75.5991330147 +59,,,,,,,,,, +60,,,,,,,,,, +60,BOWL,SUM,0,0,0,0,2,7,9,16.0697100163 +60,CUP,SUM,0,0,0,0,0,2,14,13.759581089 +60,SPOON,SUM,0,0,0,0,0,3,6,15.7325520515 +60,,SUM,0,0,0,0,2,12,29,45.5618431568 +60,,,,,,,,,, +61,,,,,,,,,, +61,BOWL,SUM,0,0,0,0,0,0,9,12.8288969994 +61,CUP,SUM,0,0,0,0,2,2,112,46.6125991344 +61,SPOON,SUM,0,0,0,0,0,50,68,47.9524919987 +61,,SUM,0,0,0,0,2,52,189,107.3939881325 +61,,,,,,,,,, +62,,,,,,,,,, +62,BOWL,SUM,0,0,0,0,0,0,0,8.2080509663 +62,CUP,SUM,0,0,0,0,4,6,5,11.3617990017 +62,SPOON,SUM,0,0,0,0,2,1,9,18.0839390755 +62,,SUM,0,0,0,0,6,7,14,37.6537890434 +62,,,,,,,,,, +63,,,,,,,,,, +63,BOWL,SUM,0,0,0,0,8,3,12,18.0945360661 +63,CUP,SUM,0,0,0,0,0,3,23,15.9038710594 +63,SPOON,SUM,0,0,0,0,0,3,11,17.6008892059 +63,,SUM,0,0,0,0,8,9,46,51.5992963314 +63,,,,,,,,,, +64,,,,,,,,,, +64,BOWL,SUM,0,0,0,0,2,6,21,20.8261671066 +64,CUP,SUM,0,0,0,0,0,2,41,24.1043009758 +64,SPOON,SUM,0,0,0,0,0,4,11,22.2104871273 +64,,SUM,0,0,0,0,2,12,73,67.1409552097 +64,,,,,,,,,, +65,,,,,,,,,, +65,BOWL,SUM,0,0,0,0,0,2,4,11.0143258572 +65,CUP,SUM,1,0,0,1,0,32,234,0 +65,SPOON,SUM,0,0,0,0,0,4,6,17.4563670158 +65,,SUM,1,0,0,1,0,38,244,28.470692873 +65,,,,,,,,,, +66,,,,,,,,,, +66,BOWL,SUM,0,0,0,0,0,3,42,30.0879869461 +66,CUP,SUM,1,0,0,1,0,36,81,0 +66,SPOON,SUM,0,0,0,0,0,3,11,23.2088041306 +66,,SUM,1,0,0,1,0,42,134,53.2967910767 +66,,,,,,,,,, +67,,,,,,,,,, +67,BOWL,SUM,0,0,0,0,0,5,31,25.8886108398 +67,CUP,SUM,0,0,0,0,8,13,66,49.7677800655 +67,SPOON,SUM,0,0,0,0,0,2,9,16.8033120632 +67,,SUM,0,0,0,0,8,20,106,92.4597029686 +67,,,,,,,,,, +68,,,,,,,,,, +68,BOWL,SUM,0,0,0,0,0,2,2,11.0703210831 +68,CUP,SUM,0,0,0,0,2,17,134,64.6152908802 +68,SPOON,SUM,1,0,1,0,32,42,165,0 +68,,SUM,1,0,1,0,34,61,301,75.6856119633 +68,,,,,,,,,, +69,,,,,,,,,, +69,BOWL,SUM,0,0,0,0,0,6,0,8.8946270943 +69,CUP,SUM,0,0,0,0,8,8,38,34.2083539963 +69,SPOON,SUM,0,0,0,0,0,6,11,19.8471539021 +69,,SUM,0,0,0,0,8,20,49,62.9501349926 +69,,,,,,,,,, +70,,,,,,,,,, +70,BOWL,SUM,0,0,0,0,8,0,5,14.4376220703 +70,CUP,SUM,0,0,0,0,4,8,199,78.1846029758 +70,SPOON,SUM,0,0,0,0,24,5,14,37.9979012012 +70,,SUM,0,0,0,0,36,13,218,130.6201262474 +70,,,,,,,,,, +71,,,,,,,,,, +71,BOWL,SUM,0,0,0,0,0,6,5,12.5880680084 +71,CUP,SUM,0,0,0,0,4,14,62,57.1758389473 +71,SPOON,SUM,0,0,0,0,0,4,0,12.4180960655 +71,,SUM,0,0,0,0,4,24,67,82.1820030212 +71,,,,,,,,,, +72,,,,,,,,,, +72,BOWL,SUM,0,0,0,0,0,23,26,22.0999391079 +72,CUP,SUM,0,0,0,0,8,0,8,12.2291779518 +72,SPOON,SUM,0,0,0,0,0,0,7,17.0001871586 +72,,SUM,0,0,0,0,8,23,41,51.3293042183 +72,,,,,,,,,, +73,,,,,,,,,, +73,BOWL,SUM,0,0,0,0,0,2,4,10.9730389118 +73,CUP,SUM,0,0,0,0,0,5,17,19.1849589348 +73,SPOON,SUM,0,0,0,0,0,4,8,15.872590065 +73,,SUM,0,0,0,0,0,11,29,46.0305879116 +73,,,,,,,,,, +74,,,,,,,,,, +74,BOWL,SUM,0,0,0,0,0,2,3,9.9845600128 +74,CUP,SUM,1,0,0,1,0,29,65,0 +74,SPOON,SUM,0,0,0,0,2,0,2,11.919054985 +74,,SUM,1,0,0,1,2,31,70,21.9036149979 +74,,,,,,,,,, +75,,,,,,,,,, +75,BOWL,SUM,0,0,0,0,0,2,9,12.6102077961 +75,CUP,SUM,0,0,0,0,0,6,14,11.5181648731 +75,SPOON,SUM,0,0,0,0,0,6,12,24.6231241226 +75,,SUM,0,0,0,0,0,14,35,48.7514967918 +75,,,,,,,,,, +76,,,,,,,,,, +76,BOWL,SUM,0,0,0,0,0,0,8,17.937474966 +76,CUP,SUM,0,0,0,0,8,8,35,22.300896883 +76,SPOON,SUM,0,0,0,0,0,7,8,17.103276968 +76,,SUM,0,0,0,0,8,15,51,57.3416488171 +76,,,,,,,,,, +77,,,,,,,,,, +77,BOWL,SUM,0,0,0,0,8,4,11,25.861866951 +77,CUP,SUM,0,0,0,0,8,1,8,13.0013501644 +77,SPOON,SUM,0,0,0,0,2,23,29,27.7617990971 +77,,SUM,0,0,0,0,18,28,48,66.6250162125 +77,,,,,,,,,, +78,,,,,,,,,, +78,BOWL,SUM,0,0,0,0,0,9,0,9.6499249935 +78,CUP,SUM,0,0,0,0,0,0,46,21.9657900333 +78,SPOON,SUM,0,0,0,0,2,0,1,14.3538150787 +78,,SUM,0,0,0,0,2,9,47,45.9695301056 +78,,,,,,,,,, +79,,,,,,,,,, +79,BOWL,SUM,0,0,0,0,0,0,12,14.9729161263 +79,CUP,SUM,1,0,0,1,8,28,93,0 +79,SPOON,SUM,0,0,0,0,0,2,7,18.3992209435 +79,,SUM,1,0,0,1,8,30,112,33.3721370697 +79,,,,,,,,,, +80,,,,,,,,,, +80,BOWL,SUM,0,0,0,0,0,3,7,12.3295559883 +80,CUP,SUM,0,0,0,0,10,0,8,13.242634058 +80,SPOON,SUM,0,0,0,0,0,6,14,19.7955021858 +80,,SUM,0,0,0,0,10,9,29,45.3676922321 +80,,,,,,,,,, +81,,,,,,,,,, +81,BOWL,SUM,0,0,0,0,0,2,2,9.0526850224 +81,CUP,SUM,0,0,0,0,0,4,8,8.6552760601 +81,SPOON,SUM,0,0,0,0,16,32,148,91.5000259876 +81,,SUM,0,0,0,0,16,38,158,109.2079870701 +81,,,,,,,,,, +82,,,,,,,,,, +82,BOWL,SUM,0,0,0,0,8,1,4,13.4514360428 +82,CUP,SUM,0,0,0,0,0,2,16,15.0288498402 +82,SPOON,SUM,0,0,0,0,0,3,11,17.629128933 +82,,SUM,0,0,0,0,8,6,31,46.1094148159 +82,,,,,,,,,, +83,,,,,,,,,, +83,BOWL,SUM,0,0,0,0,16,5,5,17.787637949 +83,CUP,SUM,0,0,0,0,8,0,25,19.4262008667 +83,SPOON,SUM,0,0,0,0,0,34,48,36.2400012016 +83,,SUM,0,0,0,0,24,39,78,73.4538400173 +83,,,,,,,,,, +84,,,,,,,,,, +84,BOWL,SUM,0,0,0,0,0,3,11,23.1120290756 +84,CUP,SUM,0,0,0,0,0,1,32,17.3254489899 +84,SPOON,SUM,0,0,0,0,0,11,18,21.2291531563 +84,,SUM,0,0,0,0,0,15,61,61.6666312218 +84,,,,,,,,,, +85,,,,,,,,,, +85,BOWL,SUM,0,0,0,0,2,3,11,14.243265152 +85,CUP,SUM,1,0,0,1,0,36,107,0 +85,SPOON,SUM,0,0,0,0,0,2,17,22.5013217926 +85,,SUM,1,0,0,1,2,41,135,36.7445869446 +85,,,,,,,,,, +86,,,,,,,,,, +86,BOWL,SUM,0,0,0,0,0,1,12,18.4115679264 +86,CUP,SUM,0,0,0,0,8,8,83,40.9447159767 +86,SPOON,SUM,0,0,0,0,0,5,13,22.2598628998 +86,,SUM,0,0,0,0,8,14,108,81.6161468029 +86,,,,,,,,,, +87,,,,,,,,,, +87,BOWL,SUM,0,0,0,0,0,2,0,8.9825279713 +87,CUP,SUM,0,0,0,0,0,2,25,14.8542671204 +87,SPOON,SUM,0,0,0,0,0,10,6,16.1379449368 +87,,SUM,0,0,0,0,0,14,31,39.9747400284 +87,,,,,,,,,, +88,,,,,,,,,, +88,BOWL,SUM,0,0,0,0,0,5,14,20.3026919365 +88,CUP,SUM,0,0,0,0,2,5,25,16.7271699905 +88,SPOON,SUM,0,0,0,0,8,1,0,14.400028944 +88,,SUM,0,0,0,0,10,11,39,51.429890871 +88,,,,,,,,,, +89,,,,,,,,,, +89,BOWL,SUM,0,0,0,0,0,3,24,18.3462159634 +89,CUP,SUM,0,0,0,0,2,2,4,8.0055720806 +89,SPOON,SUM,0,0,0,0,0,0,0,11.0242190361 +89,,SUM,0,0,0,0,2,5,28,37.3760070801 +89,,,,,,,,,, +90,,,,,,,,,, +90,BOWL,SUM,0,0,0,0,0,5,15,19.4957530499 +90,CUP,SUM,1,0,0,1,0,48,55,0 +90,SPOON,SUM,0,0,0,0,2,3,2,16.4778628349 +90,,SUM,1,0,0,1,2,56,72,35.9736158848 +90,,,,,,,,,, +91,,,,,,,,,, +91,BOWL,SUM,0,0,0,0,0,0,16,16.6632900238 +91,CUP,SUM,0,0,0,0,2,5,147,59.8887281418 +91,SPOON,SUM,0,0,0,0,0,11,20,24.0351209641 +91,,SUM,0,0,0,0,2,16,183,100.5871391296 +91,,,,,,,,,, +92,,,,,,,,,, +92,BOWL,SUM,0,0,0,0,0,2,7,12.4545958042 +92,CUP,SUM,0,0,0,0,2,0,26,17.7279000282 +92,SPOON,SUM,0,0,0,0,0,42,42,33.510258913 +92,,SUM,0,0,0,0,2,44,75,63.6927547455 +92,,,,,,,,,, +93,,,,,,,,,, +93,BOWL,SUM,0,0,0,0,0,6,4,11.2177360058 +93,CUP,SUM,0,0,0,0,0,2,16,11.7129240036 +93,SPOON,SUM,0,0,0,0,0,4,12,17.8364171982 +93,,SUM,0,0,0,0,0,12,32,40.7670772076 +93,,,,,,,,,, +94,,,,,,,,,, +94,BOWL,SUM,0,0,0,0,0,5,26,21.0465779305 +94,CUP,SUM,0,0,0,0,0,2,8,8.8721880913 +94,SPOON,SUM,0,0,0,0,0,1,4,13.9941699505 +94,,SUM,0,0,0,0,0,8,38,43.9129359722 +94,,,,,,,,,, +95,,,,,,,,,, +95,BOWL,SUM,0,0,0,0,0,4,12,14.0828900337 +95,CUP,SUM,1,0,0,1,4,63,87,0 +95,SPOON,SUM,0,0,0,0,8,1,42,36.2504048347 +95,,SUM,1,0,0,1,12,68,141,50.3332948685 +95,,,,,,,,,, +96,,,,,,,,,, +96,BOWL,SUM,0,0,0,0,0,3,8,12.6698408127 +96,CUP,SUM,0,0,0,0,4,2,43,24.1099410057 +96,SPOON,SUM,0,0,0,0,0,1,0,12.8643960953 +96,,SUM,0,0,0,0,4,6,51,49.6441779137 +96,,,,,,,,,, +97,,,,,,,,,, +97,BOWL,SUM,0,0,0,0,0,3,4,13.9682872295 +97,CUP,SUM,0,0,0,0,0,6,62,27.7778551579 +97,SPOON,SUM,0,0,0,0,0,9,28,27.6302988529 +97,,SUM,0,0,0,0,0,18,94,69.3764412403 +97,,,,,,,,,, +98,,,,,,,,,, +98,BOWL,SUM,0,0,0,0,0,1,0,8.4316279888 +98,CUP,SUM,0,0,0,0,0,13,31,32.2144072056 +98,SPOON,SUM,0,0,0,0,0,4,12,17.8237938881 +98,,SUM,0,0,0,0,0,18,43,58.4698290825 +98,,,,,,,,,, +99,,,,,,,,,, +99,BOWL,SUM,0,0,0,0,8,4,16,18.8897659779 +99,CUP,SUM,1,0,0,1,24,35,61,0 +99,SPOON,SUM,0,0,0,0,4,9,28,29.6520869732 +99,,SUM,1,0,0,1,36,48,105,48.541852951 +99,,,,,,,,,, +100,,,,,,,,,, +100,BOWL,SUM,0,0,0,0,0,19,28,28.6015450954 +100,CUP,SUM,0,0,0,0,0,8,19,13.9253730774 +100,SPOON,SUM,0,0,0,0,2,0,0,11.6585171223 +100,,SUM,0,0,0,0,2,27,47,54.1854352951 +100,,,,,,,,,, +101,,,,,,,,,, +101,BOWL,SUM,0,0,0,0,0,11,65,40.3713548183 +101,CUP,SUM,0,0,0,0,8,6,10,15.1644179821 +101,SPOON,SUM,0,0,0,0,0,2,0,10.9562380314 +101,,SUM,0,0,0,0,8,19,75,66.4920108318 +101,,,,,,,,,, +102,,,,,,,,,, +102,BOWL,SUM,0,0,0,0,8,12,49,39.0906000137 +102,CUP,SUM,0,0,0,0,0,41,163,101.4877450466 +102,SPOON,SUM,0,0,0,0,8,14,2,16.173429966 +102,,SUM,0,0,0,0,16,67,214,156.7517750263 +102,,,,,,,,,, +103,,,,,,,,,, +103,BOWL,SUM,0,0,0,0,0,3,2,9.0838048458 +103,CUP,SUM,0,0,0,0,0,9,25,16.5667901039 +103,SPOON,SUM,0,0,0,0,16,4,9,29.1736590862 +103,,SUM,0,0,0,0,16,16,36,54.8242540359 +103,,,,,,,,,, +104,, +104,BOWL,SUM,0,0,0,0,0,19,28,27.929215908050537 +104,CUP,SUM,0,0,0,0,0,8,19,14.102808952331543 +104,SPOON,SUM,0,0,0,0,2,0,0,11.999412059783936 +104,,SUM,0,0,0,0,2,27,47,54.031436920166016 +104,, +105,, +105,BOWL,SUM,0,0,0,0,0,11,65,41.432589054107666 +105,CUP,SUM,0,0,0,0,8,6,10,16.057969093322754 +105,SPOON,SUM,0,0,0,0,0,2,0,10.756262063980103 +105,,SUM,0,0,0,0,8,19,75,68.24682021141052 +105,, +106,, +106,BOWL,SUM,0,0,0,0,8,12,49,41.38061308860779 +106,CUP,SUM,0,0,0,0,0,41,163,104.58359694480896 +106,SPOON,SUM,0,0,0,0,8,14,2,16.991039037704468 +106,,SUM,0,0,0,0,16,67,214,162.95524907112122 +106,, +107,, +107,BOWL,SUM,0,0,0,0,0,3,2,9.436041831970215 +107,CUP,SUM,0,0,0,0,0,9,25,16.921226024627686 +107,SPOON,SUM,0,0,0,0,16,4,9,30.885266065597534 +107,,SUM,0,0,0,0,16,16,36,57.242533922195435 +107,, +108,, +108,BOWL,SUM,0,0,0,0,2,0,0,10.161350965499878 +108,CUP,SUM,0,0,0,0,2,27,49,67.80019783973694 +108,SPOON,SUM,0,0,0,0,24,3,5,29.639067888259888 +108,,SUM,0,0,0,0,28,30,54,107.6006166934967 +108,, +109,, +109,BOWL,SUM,0,0,0,0,8,4,6,18.067124843597412 +109,CUP,SUM,0,0,0,0,0,6,44,22.904263973236084 +109,SPOON,SUM,0,0,0,0,0,6,11,17.08932113647461 +109,,SUM,0,0,0,0,8,16,61,58.060709953308105 +109,, +110,, +110,BOWL,SUM,0,0,0,0,0,0,1,9.784749031066895 +110,CUP,SUM,0,0,0,0,10,0,78,37.53702402114868 +110,SPOON,SUM,0,0,0,0,8,1,9,18.64061713218689 +110,,SUM,0,0,0,0,18,1,88,65.96239018440247 +110,, +111,, +111,BOWL,SUM,0,0,0,0,0,0,1,9.101906061172485 +111,CUP,SUM,0,0,0,0,0,8,32,19.844709873199463 +111,SPOON,SUM,0,0,0,0,0,7,27,26.810055017471313 +111,,SUM,0,0,0,0,0,15,60,55.75667095184326 +111,, +112,, +112,BOWL,SUM,0,0,0,0,8,2,4,12.956021070480347 +112,CUP,SUM,0,0,0,0,0,11,44,35.77800393104553 +112,SPOON,SUM,0,0,0,0,0,2,0,10.776010036468506 +112,,SUM,0,0,0,0,8,15,48,59.510035037994385 +112,, +113,, +113,BOWL,SUM,0,0,0,0,2,2,2,9.820525884628296 +113,CUP,SUM,0,0,0,0,32,9,26,41.10254406929016 +113,SPOON,SUM,0,0,0,0,0,1,8,15.124905109405518 +113,,SUM,0,0,0,0,34,12,36,66.04797506332397 +113,, +114,, +114,BOWL,SUM,0,0,0,0,0,2,0,8.00278902053833 +114,CUP,SUM,0,0,0,0,22,7,10,25.41716194152832 +114,SPOON,SUM,0,0,0,0,8,1,1,15.353732109069824 +114,,SUM,0,0,0,0,30,10,11,48.773683071136475 +114,, +115,, +115,BOWL,SUM,0,0,0,0,8,3,7,16.67108702659607 +115,CUP,SUM,0,0,0,0,16,3,74,36.650989055633545 +115,SPOON,SUM,0,0,0,0,0,2,5,14.360852003097534 +115,,SUM,0,0,0,0,24,8,86,67.68292808532715 +115,, +116,, +116,BOWL,SUM,0,0,0,0,2,12,1,11.956151008605957 +116,CUP,SUM,0,0,0,0,0,3,81,35.61701011657715 +116,SPOON,SUM,0,0,0,0,0,17,16,23.42335295677185 +116,,SUM,0,0,0,0,2,32,98,70.99651408195496 +116,, +117,, +117,BOWL,SUM,0,0,0,0,2,5,5,14.169718980789185 +117,CUP,SUM,0,0,0,0,16,12,51,37.65520906448364 +117,SPOON,SUM,0,0,0,0,0,3,17,19.999264001846313 +117,,SUM,0,0,0,0,18,20,73,71.82419204711914 +117,, +118,, +118,BOWL,SUM,0,0,0,0,8,2,8,14.994199991226196 +118,CUP,SUM,0,0,0,0,0,11,46,26.953962087631226 +118,SPOON,SUM,0,0,0,0,0,2,8,15.031354188919067 +118,,SUM,0,0,0,0,8,15,62,56.97951626777649 +118,, +119,, +119,BOWL,SUM,0,0,0,0,0,4,1,9.757030963897705 +119,CUP,SUM,0,0,0,0,0,3,29,16.761300086975098 +119,SPOON,SUM,0,0,0,0,2,2,4,12.051172971725464 +119,,SUM,0,0,0,0,2,9,34,38.56950402259827 +119,, +120,, +120,BOWL,SUM,0,0,0,0,0,18,30,29.423885107040405 +120,CUP,SUM,0,0,0,0,0,16,19,28.66416311264038 +120,SPOON,SUM,0,0,0,0,2,6,4,18.963908910751343 +120,,SUM,0,0,0,0,2,40,53,77.05195713043213 +120,, +121,, +121,BOWL,SUM,0,0,0,0,0,1,10,15.800713062286377 +121,CUP,SUM,0,0,0,0,24,39,214,97.63655710220337 +121,SPOON,SUM,0,0,0,0,0,2,9,17.69720482826233 +121,,SUM,0,0,0,0,24,42,233,131.13447499275208 +121,, +122,, +122,BOWL,SUM,0,0,0,0,8,5,2,22.27001190185547 +122,CUP,SUM,0,0,0,0,0,4,19,13.689356088638306 +122,SPOON,SUM,0,0,0,0,0,1,0,12.313279151916504 +122,,SUM,0,0,0,0,8,10,21,48.27264714241028 +122,, +123,, +123,BOWL,SUM,0,0,0,0,0,1,2,11.143609046936035 +123,CUP,SUM,0,0,0,0,0,5,9,10.286356925964355 +123,SPOON,SUM,0,0,0,0,0,7,2,13.308614015579224 +123,,SUM,0,0,0,0,0,13,13,34.738579988479614 +123,, +124,, +124,BOWL,SUM,0,0,0,0,6,8,16,19.036189079284668 +124,CUP,SUM,0,0,0,0,0,1,47,27.860198974609375 +124,SPOON,SUM,0,0,0,0,0,6,2,14.100965023040771 +124,,SUM,0,0,0,0,6,15,65,60.997353076934814 +124,, +125,, +125,BOWL,SUM,0,0,0,0,0,1,1,10.71995496749878 +125,CUP,SUM,0,0,0,0,8,6,5,18.823019981384277 +125,SPOON,SUM,0,0,0,0,0,1,0,11.048107147216797 +125,,SUM,0,0,0,0,8,8,6,40.59108209609985 +125,, +126,, +126,BOWL,SUM,0,0,0,0,8,2,0,12.770699977874756 +126,CUP,SUM,0,0,0,0,18,14,13,32.502676010131836 +126,SPOON,SUM,0,0,0,0,10,13,86,66.81303977966309 +126,,SUM,0,0,0,0,36,29,99,112.08641576766968 +126,, +127,, +127,BOWL,SUM,0,0,0,0,0,2,8,16.479416131973267 +127,CUP,SUM,0,0,0,0,2,3,40,26.296247005462646 +127,SPOON,SUM,0,0,0,0,0,3,5,15.617522954940796 +127,,SUM,0,0,0,0,2,8,53,58.39318609237671 +127,, +128,, +128,BOWL,SUM,1,0,1,0,0,71,192,0.0 +128,CUP,SUM,0,0,0,0,2,3,8,10.605578184127808 +128,SPOON,SUM,0,0,0,0,0,0,8,16.982015132904053 +128,,SUM,1,0,1,0,2,74,208,27.58759331703186 +128,, +129,, +129,BOWL,SUM,0,0,0,0,0,1,2,9.586380958557129 +129,CUP,SUM,0,0,0,0,16,3,9,20.561023950576782 +129,SPOON,SUM,0,0,0,0,0,6,7,18.635541915893555 +129,,SUM,0,0,0,0,16,10,18,48.782946825027466 +129,, +130,, +130,BOWL,SUM,0,0,0,0,0,2,1,10.659241914749146 +130,CUP,SUM,0,0,0,0,0,2,56,24.72844099998474 +130,SPOON,SUM,0,0,0,0,0,5,14,18.95421814918518 +130,,SUM,0,0,0,0,0,9,71,54.34190106391907 +130,, +131,, +131,BOWL,SUM,0,0,0,0,0,0,4,8.44313907623291 +131,CUP,SUM,0,0,0,0,8,4,18,20.98172903060913 +131,SPOON,SUM,0,0,0,0,2,0,10,17.10672903060913 +131,,SUM,0,0,0,0,10,4,32,46.53159713745117 +131,, +132,, +132,BOWL,SUM,0,0,0,0,0,3,0,8.382421970367432 +132,CUP,SUM,0,0,0,0,0,15,40,33.6412570476532 +132,SPOON,SUM,0,0,0,0,0,21,30,31.235488891601563 +132,,SUM,0,0,0,0,0,39,70,73.25916790962219 +132,, +133,, +133,BOWL,SUM,0,0,0,0,0,3,15,19.756561040878296 +133,CUP,SUM,0,0,0,0,8,4,14,18.51856803894043 +133,SPOON,SUM,0,0,0,0,0,1,1,12.245738983154297 +133,,SUM,0,0,0,0,8,8,30,50.52086806297302 +133,, +134,, +134,BOWL,SUM,0,0,0,0,8,7,3,17.92335820198059 +134,CUP,SUM,0,0,0,0,0,4,46,21.90714192390442 +134,SPOON,SUM,0,0,0,0,0,9,11,18.979650020599365 +134,,SUM,0,0,0,0,8,20,60,58.810150146484375 +134,, +135,, +135,BOWL,SUM,0,0,0,0,0,2,1,10.207993030548096 +135,CUP,SUM,0,0,0,0,2,3,26,15.94277286529541 +135,SPOON,SUM,0,0,0,0,0,17,21,24.676681995391846 +135,,SUM,0,0,0,0,2,22,48,50.82744789123535 +135,, +136,, +136,BOWL,SUM,0,0,0,0,16,1,8,18.17962384223938 +136,CUP,SUM,0,0,0,0,0,2,52,23.415377140045166 +136,SPOON,SUM,0,0,0,0,0,0,4,13.407725095748901 +136,,SUM,0,0,0,0,16,3,64,55.00272607803345 +136,, +137,, +137,BOWL,SUM,0,0,0,0,0,3,25,18.396801948547363 +137,CUP,SUM,0,0,0,0,0,2,8,10.990600109100342 +137,SPOON,SUM,0,0,0,0,0,0,0,11.270506858825684 +137,,SUM,0,0,0,0,0,5,33,40.65790891647339 +137,, +138,, +138,BOWL,SUM,0,0,0,0,0,0,4,9.299925088882446 +138,CUP,SUM,0,0,0,0,0,1,8,8.378817081451416 +138,SPOON,SUM,0,0,0,0,0,2,0,11.692605972290039 +138,,SUM,0,0,0,0,0,3,12,29.3713481426239 +138,, +139,, +139,BOWL,SUM,0,0,0,0,16,7,17,36.65086102485657 +139,CUP,SUM,0,0,0,0,0,2,8,8.48166298866272 +139,SPOON,SUM,0,0,0,0,0,1,7,14.81627106666565 +139,,SUM,0,0,0,0,16,10,32,59.94879508018494 +139,, +140,, +140,BOWL,SUM,0,0,0,0,0,6,42,30.121523141860962 +140,CUP,SUM,0,0,0,0,8,45,43,46.35043692588806 +140,SPOON,SUM,0,0,0,0,0,0,11,17.8267560005188 +140,,SUM,0,0,0,0,8,51,96,94.29871606826782 +140,, +141,, +141,BOWL,SUM,0,0,0,0,0,1,3,10.633234024047852 +141,CUP,SUM,0,0,0,0,0,1,59,26.379220008850098 +141,SPOON,SUM,0,0,0,0,0,3,12,18.004568099975586 +141,,SUM,0,0,0,0,0,5,74,55.017022132873535 +141,, +142,, +142,BOWL,SUM,0,0,0,0,8,2,12,18.266676902770996 +142,CUP,SUM,0,0,0,0,0,4,26,21.563902854919434 +142,SPOON,SUM,0,0,0,0,10,3,13,20.975256204605103 +142,,SUM,0,0,0,0,18,9,51,60.80583596229553 +142,, +143,, +143,BOWL,SUM,0,0,0,0,0,9,6,17.16957998275757 +143,CUP,SUM,1,0,0,1,0,37,75,0.0 +143,SPOON,SUM,0,0,0,0,2,12,17,25.981502056121826 +143,,SUM,1,0,0,1,2,58,98,43.151082038879395 +143,, +144,, +144,BOWL,SUM,0,0,0,0,16,8,34,39.52866506576538 +144,CUP,SUM,0,0,0,0,16,2,23,21.27524709701538 +144,SPOON,SUM,0,0,0,0,8,1,1,17.616525888442993 +144,,SUM,0,0,0,0,40,11,58,78.42043805122375 +144,, +145,, +145,BOWL,SUM,0,0,0,0,0,2,3,12.849640130996704 +145,CUP,SUM,1,0,0,1,8,24,87,0.0 +145,SPOON,SUM,0,0,0,0,0,1,2,11.244107007980347 +145,,SUM,1,0,0,1,8,27,92,24.09374713897705 +145,, +146,, +146,BOWL,SUM,0,0,0,0,0,3,0,10.234657049179077 +146,CUP,SUM,0,0,0,0,0,19,29,20.62289309501648 +146,SPOON,SUM,0,0,0,0,0,23,49,38.500319957733154 +146,,SUM,0,0,0,0,0,45,78,69.35787010192871 +146,, +147,, +147,BOWL,SUM,0,0,0,0,0,8,12,13.28510594367981 +147,CUP,SUM,1,0,0,1,2,40,74,0.0 +147,SPOON,SUM,0,0,0,0,0,2,25,25.192166090011597 +147,,SUM,1,0,0,1,2,50,111,38.477272033691406 +147,, +148,, +148,BOWL,SUM,0,0,0,0,0,1,6,11.094196081161499 +148,CUP,SUM,0,0,0,0,0,9,24,20.91757607460022 +148,SPOON,SUM,0,0,0,0,0,0,5,14.153205156326294 +148,,SUM,0,0,0,0,0,10,35,46.16497731208801 +148,, +149,, +149,BOWL,SUM,0,0,0,0,8,5,16,20.20341992378235 +149,CUP,SUM,0,0,0,0,8,6,18,24.386752128601074 +149,SPOON,SUM,0,0,0,0,0,2,1,11.889926195144653 +149,,SUM,0,0,0,0,16,13,35,56.480098247528076 +149,, +150,, +150,BOWL,SUM,0,0,0,0,0,6,17,16.98019313812256 +150,CUP,SUM,0,0,0,0,0,2,9,10.937092065811157 +150,SPOON,SUM,0,0,0,0,8,6,4,24.452383041381836 +150,,SUM,0,0,0,0,8,14,30,52.36966824531555 +150,, +151,, +151,BOWL,SUM,0,0,0,0,0,0,8,12.454985857009888 +151,CUP,SUM,0,0,0,0,0,0,17,12.730567932128906 +151,SPOON,SUM,0,0,0,0,0,1,4,13.306505918502808 +151,,SUM,0,0,0,0,0,1,29,38.4920597076416 +151,, +152,, +152,BOWL,SUM,0,0,0,0,2,4,16,18.231667041778564 +152,CUP,SUM,0,0,0,0,10,4,66,37.145318031311035 +152,SPOON,SUM,0,0,0,0,10,9,25,33.055875062942505 +152,,SUM,0,0,0,0,22,17,107,88.4328601360321 +152,, +153,, +153,BOWL,SUM,0,0,0,0,2,1,6,15.96946907043457 +153,CUP,SUM,0,0,0,0,0,32,33,27.417587995529175 +153,SPOON,SUM,0,0,0,0,4,2,5,17.205782890319824 +153,,SUM,0,0,0,0,6,35,44,60.59283995628357 +153,, +154,, +154,BOWL,SUM,0,0,0,0,2,3,0,10.080328941345215 +154,CUP,SUM,0,0,0,0,0,2,41,20.34007501602173 +154,SPOON,SUM,0,0,0,0,0,6,26,27.628055095672607 +154,,SUM,0,0,0,0,2,11,67,58.04845905303955 +154,, +155,, +155,BOWL,SUM,0,0,0,0,0,0,6,13.467150926589966 +155,CUP,SUM,0,0,0,0,0,1,18,13.613781929016113 +155,SPOON,SUM,0,0,0,0,0,6,19,32.18480396270752 +155,,SUM,0,0,0,0,0,7,43,59.2657368183136 +155,, +156,, +156,BOWL,SUM,0,0,0,0,0,5,17,21.04158902168274 +156,CUP,SUM,0,0,0,0,0,3,82,36.57166004180908 +156,SPOON,SUM,0,0,0,0,0,10,19,25.63810110092163 +156,,SUM,0,0,0,0,0,18,118,83.25135016441345 +156,, +157,, +157,BOWL,SUM,0,0,0,0,0,0,16,17.766587018966675 +157,CUP,SUM,0,0,0,0,8,3,30,24.87995195388794 +157,SPOON,SUM,0,0,0,0,0,10,46,37.01737713813782 +157,,SUM,0,0,0,0,8,13,92,79.66391611099243 +157,, +158,, +158,BOWL,SUM,0,0,0,0,0,6,15,21.191410064697266 +158,CUP,SUM,0,0,0,0,8,32,85,60.900630950927734 +158,SPOON,SUM,0,0,0,0,24,2,10,26.4148530960083 +158,,SUM,0,0,0,0,32,40,110,108.5068941116333 +158,, +159,, +159,BOWL,SUM,0,0,0,0,0,2,12,18.9167320728302 +159,CUP,SUM,0,0,0,0,16,3,10,22.835608959197998 +159,SPOON,SUM,0,0,0,0,0,7,2,16.162028074264526 +159,,SUM,0,0,0,0,16,12,24,57.914369106292725 +159,, +160,, +160,BOWL,SUM,0,0,0,0,0,6,3,11.267575979232788 +160,CUP,SUM,1,0,0,1,0,39,63,0.0 +160,SPOON,SUM,0,0,0,0,32,4,2,31.042449951171875 +160,,SUM,1,0,0,1,32,49,68,42.31002593040466 +160,, +161,, +161,BOWL,SUM,0,0,0,0,0,1,3,10.332636833190918 +161,CUP,SUM,0,0,0,0,0,1,11,11.9496750831604 +161,SPOON,SUM,0,0,0,0,0,0,0,11.635786056518555 +161,,SUM,0,0,0,0,0,2,14,33.91809797286987 +161,, +162,, +162,BOWL,SUM,0,0,0,0,26,12,10,33.07321906089783 +162,CUP,SUM,0,0,0,0,0,13,62,34.325103998184204 +162,SPOON,SUM,0,0,0,0,0,4,3,16.899513959884644 +162,,SUM,0,0,0,0,26,29,75,84.29783701896667 +162,, +163,, +163,BOWL,SUM,0,0,0,0,0,3,5,11.469825029373169 +163,CUP,SUM,0,0,0,0,16,6,9,22.739792108535767 +163,SPOON,SUM,0,0,0,0,0,0,0,13.11391806602478 +163,,SUM,0,0,0,0,16,9,14,47.323535203933716 +163,, +164,, +164,BOWL,SUM,0,0,0,0,0,0,1,11.422526121139526 +164,CUP,SUM,0,0,0,0,0,2,10,10.313378095626831 +164,SPOON,SUM,0,0,0,0,0,1,1,13.174352884292603 +164,,SUM,0,0,0,0,0,3,12,34.91025710105896 +164,, +165,, +165,BOWL,SUM,0,0,0,0,0,1,7,12.252137899398804 +165,CUP,SUM,0,0,0,0,2,2,36,19.385658979415894 +165,SPOON,SUM,0,0,0,0,0,3,21,25.033273935317993 +165,,SUM,0,0,0,0,2,6,64,56.67107081413269 +165,, +166,, +166,BOWL,SUM,0,0,0,0,0,2,12,15.911175966262817 +166,CUP,SUM,0,0,0,0,8,5,22,23.67223882675171 +166,SPOON,SUM,0,0,0,0,2,2,8,20.443201065063477 +166,,SUM,0,0,0,0,10,9,42,60.026615858078 +166,, +167,, +167,BOWL,SUM,0,0,0,0,0,1,1,9.926022052764893 +167,CUP,SUM,1,0,0,1,0,35,66,0.0 +167,SPOON,SUM,0,0,0,0,0,2,21,24.46167492866516 +167,,SUM,1,0,0,1,0,38,88,34.387696981430054 +167,, +168,, +168,BOWL,SUM,0,0,0,0,0,5,4,11.701008081436157 +168,CUP,SUM,0,0,0,0,2,6,14,16.712023973464966 +168,SPOON,SUM,0,0,0,0,8,3,2,22.794190168380737 +168,,SUM,0,0,0,0,10,14,20,51.20722222328186 +168,, +169,, +169,BOWL,SUM,0,0,0,0,8,2,3,15.930284023284912 +169,CUP,SUM,0,0,0,0,2,1,8,10.336577892303467 +169,SPOON,SUM,0,0,0,0,0,5,5,15.189657926559448 +169,,SUM,0,0,0,0,10,8,16,41.45651984214783 +169,, +170,, +170,BOWL,SUM,0,0,0,0,0,6,14,20.11457586288452 +170,CUP,SUM,0,0,0,0,8,4,15,19.631541967391968 +170,SPOON,SUM,0,0,0,0,14,22,66,58.038501024246216 +170,,SUM,0,0,0,0,22,32,95,97.7846188545227 +170,, +171,, +171,BOWL,SUM,0,0,0,0,0,0,0,8.289591073989868 +171,CUP,SUM,0,0,0,0,0,3,45,22.353986024856567 +171,SPOON,SUM,0,0,0,0,2,3,7,18.332741022109985 +171,,SUM,0,0,0,0,2,6,52,48.97631812095642 +171,, +172,, +172,BOWL,SUM,0,0,0,0,0,5,31,27.118900060653687 +172,CUP,SUM,0,0,0,0,2,2,8,9.765550136566162 +172,SPOON,SUM,0,0,0,0,0,9,3,14.959289789199829 +172,,SUM,0,0,0,0,2,16,42,51.84373998641968 +172,, +173,, +173,BOWL,SUM,0,0,0,0,0,8,14,16.997260808944702 +173,CUP,SUM,0,0,0,0,0,2,43,30.17957615852356 +173,SPOON,SUM,0,0,0,0,0,1,3,13.452217102050781 +173,,SUM,0,0,0,0,0,11,60,60.62905406951904 +173,, +174,, +174,BOWL,SUM,0,0,0,0,0,0,4,10.759026050567627 +174,CUP,SUM,1,0,0,1,0,30,79,0.0 +174,SPOON,SUM,0,0,0,0,24,1,3,30.765685081481934 +174,,SUM,1,0,0,1,24,31,86,41.52471113204956 +174,, +175,, +175,BOWL,SUM,0,0,0,0,0,1,8,18.186880826950073 +175,CUP,SUM,0,0,0,0,8,3,38,25.65276002883911 +175,SPOON,SUM,0,0,0,0,2,3,4,14.843183994293213 +175,,SUM,0,0,0,0,10,7,50,58.6828248500824 +175,, +176,, +176,BOWL,SUM,0,0,0,0,0,2,2,10.991513013839722 +176,CUP,SUM,1,0,0,1,0,47,112,0.0 +176,SPOON,SUM,0,0,0,0,0,2,3,14.966267108917236 +176,,SUM,1,0,0,1,0,51,117,25.957780122756958 +176,, +177,, +177,BOWL,SUM,0,0,0,0,2,0,0,11.351569890975952 +177,CUP,SUM,0,0,0,0,0,2,42,20.28758716583252 +177,SPOON,SUM,0,0,0,0,0,6,22,23.935675144195557 +177,,SUM,0,0,0,0,2,8,64,55.57483220100403 +177,, +178,, +178,BOWL,SUM,0,0,0,0,0,1,4,10.05449390411377 +178,CUP,SUM,0,0,0,0,0,1,49,23.28889298439026 +178,SPOON,SUM,0,0,0,0,0,0,5,14.420377969741821 +178,,SUM,0,0,0,0,0,2,58,47.76376485824585 +178,, +179,, +179,BOWL,SUM,0,0,0,0,0,1,1,10.182291984558105 +179,CUP,SUM,0,0,0,0,8,11,116,53.202078104019165 +179,SPOON,SUM,0,0,0,0,8,3,3,17.940169095993042 +179,,SUM,0,0,0,0,16,15,120,81.32453918457031 +179,, +180,, +180,BOWL,SUM,0,0,0,0,0,1,2,8.654798984527588 +180,CUP,SUM,1,0,0,1,8,32,51,0.0 +180,SPOON,SUM,0,0,0,0,2,6,4,16.32015085220337 +180,,SUM,1,0,0,1,10,39,57,24.974949836730957 +180,, +181,, +181,BOWL,SUM,0,0,0,0,8,6,13,23.683482885360718 +181,CUP,SUM,0,0,0,0,0,6,28,17.591875076293945 +181,SPOON,SUM,0,0,0,0,0,11,31,30.97537612915039 +181,,SUM,0,0,0,0,8,23,72,72.25073409080505 +181,, +182,, +182,BOWL,SUM,0,0,0,0,0,3,1,9.83558988571167 +182,CUP,SUM,0,0,0,0,16,17,142,80.43028593063354 +182,SPOON,SUM,0,0,0,0,18,13,0,22.801637172698975 +182,,SUM,0,0,0,0,34,33,143,113.06751298904419 +182,, +183,, +183,BOWL,SUM,0,0,0,0,0,3,5,13.317797899246216 +183,CUP,SUM,0,0,0,0,0,1,8,8.564082145690918 +183,SPOON,SUM,0,0,0,0,0,3,14,18.68388605117798 +183,,SUM,0,0,0,0,0,7,27,40.56576609611511 +183,, +184,, +184,BOWL,SUM,0,0,0,0,0,2,46,33.73436999320984 +184,CUP,SUM,0,0,0,0,0,6,129,58.1084189414978 +184,SPOON,SUM,0,0,0,0,2,4,0,13.630285024642944 +184,,SUM,0,0,0,0,2,12,175,105.47307395935059 +184,, +185,, +185,BOWL,SUM,0,0,0,0,8,21,10,27.841840028762817 +185,CUP,SUM,0,0,0,0,0,6,73,34.58004903793335 +185,SPOON,SUM,0,0,0,0,16,5,4,25.594264030456543 +185,,SUM,0,0,0,0,24,32,87,88.01615309715271 +185,, +186,, +186,BOWL,SUM,0,0,0,0,0,3,8,13.526717185974121 +186,CUP,SUM,0,0,0,0,8,12,14,24.229010105133057 +186,SPOON,SUM,0,0,0,0,0,83,93,63.071160078048706 +186,,SUM,0,0,0,0,8,98,115,100.82688736915588 +186,, +187,, +187,BOWL,SUM,0,0,0,0,0,5,8,14.419533014297485 +187,CUP,SUM,0,0,0,0,8,2,12,17.036720037460327 +187,SPOON,SUM,0,0,0,0,0,9,16,22.34933304786682 +187,,SUM,0,0,0,0,8,16,36,53.805586099624634 +187,, +188,, +188,BOWL,SUM,0,0,0,0,0,1,8,11.607836961746216 +188,CUP,SUM,1,0,0,1,0,28,71,0.0 +188,SPOON,SUM,0,0,0,0,0,7,0,13.609387159347534 +188,,SUM,1,0,0,1,0,36,79,25.21722412109375 +188,, +189,, +189,BOWL,SUM,0,0,0,0,0,4,1,10.050464868545532 +189,CUP,SUM,0,0,0,0,0,1,8,8.279722213745117 +189,SPOON,SUM,0,0,0,0,0,4,0,11.781866073608398 +189,,SUM,0,0,0,0,0,9,9,30.112053155899048 +189,, +190,, +190,BOWL,SUM,0,0,0,0,2,9,18,19.670212030410767 +190,CUP,SUM,0,0,0,0,8,5,9,14.422899961471558 +190,SPOON,SUM,0,0,0,0,16,1,7,21.740283966064453 +190,,SUM,0,0,0,0,26,15,34,55.83339595794678 +190,, +191,, +191,BOWL,SUM,0,0,0,0,0,1,6,11.301937103271484 +191,CUP,SUM,0,0,0,0,8,15,103,63.32354402542114 +191,SPOON,SUM,0,0,0,0,2,1,7,18.46735906600952 +191,,SUM,0,0,0,0,10,17,116,93.09284019470215 +191,, +192,, +192,BOWL,SUM,0,0,0,0,0,2,15,17.98362112045288 +192,CUP,SUM,0,0,0,0,2,9,23,24.000545024871826 +192,SPOON,SUM,0,0,0,0,2,5,5,16.494772911071777 +192,,SUM,0,0,0,0,4,16,43,58.478939056396484 +192,, +193,, +193,BOWL,SUM,0,0,0,0,4,2,4,16.546796083450317 +193,CUP,SUM,0,0,0,0,0,3,54,26.94080686569214 +193,SPOON,SUM,0,0,0,0,0,0,7,16.86823606491089 +193,,SUM,0,0,0,0,4,5,65,60.355839014053345 +193,, +194,, +194,BOWL,SUM,0,0,0,0,0,1,12,13.475688934326172 +194,CUP,SUM,1,0,0,1,0,34,59,0.0 +194,SPOON,SUM,0,0,0,0,0,3,14,24.018667936325073 +194,,SUM,1,0,0,1,0,38,85,37.494356870651245 +194,, +195,, +195,BOWL,SUM,0,0,0,0,0,10,11,19.34300208091736 +195,CUP,SUM,0,0,0,0,0,5,55,28.6088809967041 +195,SPOON,SUM,0,0,0,0,0,0,2,12.04930591583252 +195,,SUM,0,0,0,0,0,15,68,60.00118899345398 +195,, +196,, +196,BOWL,SUM,0,0,0,0,0,0,8,16.287348985671997 +196,CUP,SUM,0,0,0,0,16,5,17,22.203356981277466 +196,SPOON,SUM,0,0,0,0,0,1,3,12.946736097335815 +196,,SUM,0,0,0,0,16,6,28,51.43744206428528 +196,, +197,, +197,BOWL,SUM,0,0,0,0,0,2,12,12.630919933319092 +197,CUP,SUM,0,0,0,0,0,1,8,8.787729024887085 +197,SPOON,SUM,0,0,0,0,8,3,11,22.58549690246582 +197,,SUM,0,0,0,0,8,6,31,44.004145860672 +197,, +198,, +198,BOWL,SUM,0,0,0,0,0,1,22,22.224371194839478 +198,CUP,SUM,0,0,0,0,8,8,30,27.38603377342224 +198,SPOON,SUM,0,0,0,0,8,2,2,18.59175992012024 +198,,SUM,0,0,0,0,16,11,54,68.20216488838196 +198,, +199,, +199,BOWL,SUM,0,0,0,0,0,4,16,18.091618061065674 +199,CUP,SUM,0,0,0,0,4,8,36,29.826884031295776 +199,SPOON,SUM,0,0,0,0,16,2,18,29.273966789245605 +199,,SUM,0,0,0,0,20,14,70,77.19246888160706 +199,, +200,, +200,BOWL,SUM,0,0,0,0,0,7,1,9.784568071365356 +200,CUP,SUM,1,0,0,1,0,28,59,0.0 +200,SPOON,SUM,0,0,0,0,2,13,12,28.373988151550293 +200,,SUM,1,0,0,1,2,48,72,38.15855622291565 +200,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/paper/9.BoxyHrSimMod.csv b/cram_knowrob/cram_knowrob_vr/experiments/paper/9.BoxyHrSimMod.csv new file mode 100644 index 0000000000..8051471d95 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/paper/9.BoxyHrSimMod.csv @@ -0,0 +1,603 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC + + +0,, +0,BOWL,SUM,0,0,0,0,38,7,4,34.344462871551514 +0,CUP,SUM,0,0,0,0,0,21,35,44.70782518386841 +0,SPOON,SUM,0,0,0,0,0,7,7,16.770144939422607 +0,,SUM,0,0,0,0,38,35,46,95.82243299484253 +0,, +1,, +1,BOWL,SUM,1,0,1,0,8,743,176,0.0 +1,CUP,SUM,0,0,0,0,8,2,22,26.220234870910645 +1,SPOON,SUM,0,0,0,0,0,1,5,14.759235858917236 +1,,SUM,1,0,1,0,16,746,203,40.97947072982788 +1,, +2,, +2,BOWL,SUM,0,0,0,0,0,1,0,9.126543998718262 +2,CUP,SUM,0,0,0,0,32,115,89,60.77761387825012 +2,SPOON,SUM,0,0,0,0,0,6,9,21.386530876159668 +2,,SUM,0,0,0,0,32,122,98,91.29068875312805 +2,, +3,, +3,BOWL,SUM,0,0,0,0,24,0,2,20.68395209312439 +3,CUP,SUM,0,0,0,0,0,5,22,15.09244680404663 +3,SPOON,SUM,1,0,1,0,8,1583,0,0.0 +3,,SUM,1,0,1,0,32,1588,24,35.77639889717102 +3,, +4,, +4,BOWL,SUM,0,0,0,0,0,0,7,15.25937294960022 +4,CUP,SUM,1,0,1,0,6,1138,420,0.0 +4,SPOON,SUM,0,0,0,0,0,1,0,10.695035934448242 +4,,SUM,1,0,1,0,6,1139,427,25.954408884048462 +4,, +5,, +5,BOWL,SUM,0,0,0,0,0,7,68,35.921189069747925 +5,CUP,SUM,0,0,0,0,0,8,22,15.513466119766235 +5,SPOON,SUM,0,0,0,0,0,0,3,13.895228862762451 +5,,SUM,0,0,0,0,0,15,93,65.32988405227661 +5,, +6,, +6,BOWL,SUM,0,0,0,0,0,3,12,13.963188886642456 +6,CUP,SUM,0,0,0,0,0,3,11,12.819225072860718 +6,SPOON,SUM,0,0,0,0,8,6,2,15.303355932235718 +6,,SUM,0,0,0,0,8,12,25,42.08576989173889 +6,, +7,, +7,BOWL,SUM,1,0,1,0,16,479,196,0.0 +7,CUP,SUM,0,0,0,0,0,4,21,17.67791485786438 +7,SPOON,SUM,0,0,0,0,0,2,3,16.514517068862915 +7,,SUM,1,0,1,0,16,485,220,34.192431926727295 +7,, +8,, +8,BOWL,SUM,0,0,0,0,0,1,14,23.27755093574524 +8,CUP,SUM,0,0,0,0,0,6,24,25.88141703605652 +8,SPOON,SUM,1,0,1,0,30,726,176,0.0 +8,,SUM,1,0,1,0,30,733,214,49.15896797180176 +8,, +9,, +9,BOWL,SUM,0,0,0,0,2,0,1,10.46094298362732 +9,CUP,SUM,0,0,0,0,0,6,27,18.41954517364502 +9,SPOON,SUM,0,0,0,0,0,2,8,15.358075857162476 +9,,SUM,0,0,0,0,2,8,36,44.238564014434814 +9,, +10,, +10,BOWL,SUM,0,0,0,0,8,3,7,20.237590074539185 +10,CUP,SUM,0,0,0,0,16,12,72,38.959457874298096 +10,SPOON,SUM,0,0,0,0,0,2,0,10.921795129776001 +10,,SUM,0,0,0,0,24,17,79,70.11884307861328 +10,, +11,, +11,BOWL,SUM,1,0,1,0,0,565,188,0.0 +11,CUP,SUM,0,0,0,0,0,1,62,27.097379207611084 +11,SPOON,SUM,0,0,0,0,0,4,4,14.64023494720459 +11,,SUM,1,0,1,0,0,570,254,41.737614154815674 +11,, +12,, +12,BOWL,SUM,0,0,0,0,0,0,0,8.242691993713379 +12,CUP,SUM,0,0,0,0,0,88,224,87.01893019676208 +12,SPOON,SUM,0,0,0,0,0,7,6,16.00449299812317 +12,,SUM,0,0,0,0,0,95,230,111.26611518859863 +12,, +13,, +13,BOWL,SUM,0,0,0,0,0,2,73,43.364293813705444 +13,CUP,SUM,0,0,0,0,0,3,44,23.699573040008545 +13,SPOON,SUM,1,0,1,0,56,1056,120,0.0 +13,,SUM,1,0,1,0,56,1061,237,67.06386685371399 +13,, +14,, +14,BOWL,SUM,0,0,0,0,0,1,21,17.691666841506958 +14,CUP,SUM,0,0,0,0,0,1,38,17.900398015975952 +14,SPOON,SUM,1,0,1,0,16,1082,124,0.0 +14,,SUM,1,0,1,0,16,1084,183,35.59206485748291 +14,, +15,, +15,BOWL,SUM,0,0,0,0,2,1,4,12.239400863647461 +15,CUP,SUM,0,0,0,0,40,230,154,103.97183513641357 +15,SPOON,SUM,0,0,0,0,0,0,6,13.619953155517578 +15,,SUM,0,0,0,0,42,231,164,129.8311891555786 +15,, +16,, +16,BOWL,SUM,0,0,0,0,8,5,8,17.266101837158203 +16,CUP,SUM,1,0,1,0,0,1474,160,0.0 +16,SPOON,SUM,0,0,0,0,0,3,4,14.171331882476807 +16,,SUM,1,0,1,0,8,1482,172,31.43743371963501 +16,, +17,, +17,BOWL,SUM,0,0,0,0,0,0,10,14.777184009552002 +17,CUP,SUM,0,0,0,0,2,0,52,24.348668098449707 +17,SPOON,SUM,1,0,1,0,0,1375,52,0.0 +17,,SUM,1,0,1,0,2,1375,114,39.12585210800171 +17,, +18,, +18,BOWL,SUM,0,0,0,0,0,1,2,8.309523820877075 +18,CUP,SUM,0,0,0,0,10,22,75,56.83479690551758 +18,SPOON,SUM,0,0,0,0,0,1,2,13.198771953582764 +18,,SUM,0,0,0,0,10,24,79,78.34309267997742 +18,, +19,, +19,BOWL,SUM,1,0,1,0,0,975,128,0.0 +19,CUP,SUM,0,0,0,0,0,5,19,12.762521982192993 +19,SPOON,SUM,0,0,0,0,0,2,4,13.590637922286987 +19,,SUM,1,0,1,0,0,982,151,26.35315990447998 +19,, +20,, +20,BOWL,SUM,0,0,0,0,16,703,67,85.11807012557983 +20,CUP,SUM,0,0,0,0,0,5,30,36.101662158966064 +20,SPOON,SUM,0,0,0,0,0,2,0,11.129091024398804 +20,,SUM,0,0,0,0,16,710,97,132.3488233089447 +20,, +21,, +21,BOWL,SUM,0,0,0,0,0,59,2,12.121548891067505 +21,CUP,SUM,0,0,0,0,0,4,63,31.01805090904236 +21,SPOON,SUM,0,0,0,0,0,2,8,15.118974924087524 +21,,SUM,0,0,0,0,0,65,73,58.25857472419739 +21,, +22,, +22,BOWL,SUM,0,0,0,0,0,1,5,12.159448862075806 +22,CUP,SUM,0,0,0,0,0,390,82,66.0432071685791 +22,SPOON,SUM,0,0,0,0,0,1,4,14.052274942398071 +22,,SUM,0,0,0,0,0,392,91,92.25493097305298 +22,, +23,, +23,BOWL,SUM,1,0,1,0,8,1082,120,0.0 +23,CUP,SUM,0,0,0,0,0,1,30,15.989773035049438 +23,SPOON,SUM,0,0,0,0,0,3,0,13.491703033447266 +23,,SUM,1,0,1,0,8,1086,150,29.481476068496704 +23,, +24,, +24,BOWL,SUM,0,0,0,0,0,3,0,8.287431001663208 +24,CUP,SUM,1,0,1,0,0,942,272,0.0 +24,SPOON,SUM,0,0,0,0,8,7,37,34.03307104110718 +24,,SUM,1,0,1,0,8,952,309,42.320502042770386 +24,, +25,, +25,BOWL,SUM,1,0,1,0,2,1583,0,0.0 +25,CUP,SUM,0,0,0,0,0,10,61,50.97846293449402 +25,SPOON,SUM,0,0,0,0,0,9,5,20.43876314163208 +25,,SUM,1,0,1,0,2,1602,66,71.4172260761261 +25,, +26,, +26,BOWL,SUM,1,0,1,0,32,1118,100,0.0 +26,CUP,SUM,0,0,0,0,0,6,26,20.18726420402527 +26,SPOON,SUM,0,0,0,0,0,2,3,15.757317066192627 +26,,SUM,1,0,1,0,32,1126,129,35.944581270217896 +26,, +27,, +27,BOWL,SUM,0,0,0,0,2,0,3,14.058407068252563 +27,CUP,SUM,0,0,0,0,0,16,62,57.66805815696716 +27,SPOON,SUM,1,0,1,0,0,962,140,0.0 +27,,SUM,1,0,1,0,2,978,205,71.72646522521973 +27,, +28,, +28,BOWL,SUM,0,0,0,0,0,2,3,11.726841926574707 +28,CUP,SUM,0,0,0,0,0,10,17,21.935189962387085 +28,SPOON,SUM,1,0,1,0,10,1332,64,0.0 +28,,SUM,1,0,1,0,10,1344,84,33.66203188896179 +28,, +29,, +29,BOWL,SUM,0,0,0,0,0,10,12,19.730308055877686 +29,CUP,SUM,0,0,0,0,0,8,25,21.289146900177002 +29,SPOON,SUM,0,0,0,0,0,3,10,18.781864881515503 +29,,SUM,0,0,0,0,0,21,47,59.80131983757019 +29,, +30,, +30,BOWL,SUM,0,0,0,0,0,1,3,12.33359694480896 +30,CUP,SUM,0,0,0,0,0,12,78,50.3775269985199 +30,SPOON,SUM,0,0,0,0,0,93,28,36.794755935668945 +30,,SUM,0,0,0,0,0,106,109,99.5058798789978 +30,, +31,, +31,BOWL,SUM,0,0,0,0,0,1,2,12.55295205116272 +31,CUP,SUM,0,0,0,0,0,80,101,51.301384925842285 +31,SPOON,SUM,0,0,0,0,8,2,2,17.739484071731567 +31,,SUM,0,0,0,0,8,83,105,81.59382104873657 +31,, +32,, +32,BOWL,SUM,0,0,0,0,0,2,2,8.642399072647095 +32,CUP,SUM,0,0,0,0,0,134,154,70.88061499595642 +32,SPOON,SUM,0,0,0,0,0,1,5,15.92270302772522 +32,,SUM,0,0,0,0,0,137,161,95.44571709632874 +32,, +33,, +33,BOWL,SUM,0,0,0,0,0,3,12,14.080327033996582 +33,CUP,SUM,0,0,0,0,0,6,32,21.670546054840088 +33,SPOON,SUM,1,0,1,0,24,1365,56,0.0 +33,,SUM,1,0,1,0,24,1374,100,35.75087308883667 +33,, +34,, +34,BOWL,SUM,0,0,0,0,0,2,8,13.322662115097046 +34,CUP,SUM,0,0,0,0,0,2,20,13.228490114212036 +34,SPOON,SUM,1,0,1,0,0,1407,44,0.0 +34,,SUM,1,0,1,0,0,1411,72,26.551152229309082 +34,, +35,, +35,BOWL,SUM,0,0,0,0,0,0,2,10.874907970428467 +35,CUP,SUM,0,0,0,0,8,1,8,12.268631935119629 +35,SPOON,SUM,0,0,0,0,0,343,119,88.9008560180664 +35,,SUM,0,0,0,0,8,344,129,112.0443959236145 +35,, +36,, +36,BOWL,SUM,0,0,0,0,0,0,0,8.235314846038818 +36,CUP,SUM,1,0,1,0,56,1190,19,0.0 +36,SPOON,SUM,0,0,0,0,0,8,10,20.193845987319946 +36,,SUM,1,0,1,0,56,1198,29,28.429160833358765 +36,, +37,, +37,BOWL,SUM,0,0,0,0,0,73,22,22.82380199432373 +37,CUP,SUM,0,0,0,0,0,4,11,12.840473890304565 +37,SPOON,SUM,0,0,0,0,8,2,4,16.78911304473877 +37,,SUM,0,0,0,0,8,79,37,52.453388929367065 +37,, +38,, +38,BOWL,SUM,0,0,0,0,0,0,4,10.530174016952515 +38,CUP,SUM,1,0,1,0,0,1443,140,0.0 +38,SPOON,SUM,0,0,0,0,0,0,7,15.383347034454346 +38,,SUM,1,0,1,0,0,1443,151,25.91352105140686 +38,, +39,, +39,BOWL,SUM,0,0,0,0,2,2,4,10.706947803497314 +39,CUP,SUM,0,0,0,0,0,1,17,18.701497077941895 +39,SPOON,SUM,1,0,1,0,24,528,180,0.0 +39,,SUM,1,0,1,0,26,531,201,29.40844488143921 +39,, +40,, +40,BOWL,SUM,0,0,0,0,16,27,37,33.59475612640381 +40,CUP,SUM,0,0,0,0,0,2,12,12.339104890823364 +40,SPOON,SUM,0,0,0,0,0,1,3,14.567800045013428 +40,,SUM,0,0,0,0,16,30,52,60.5016610622406 +40,, +41,, +41,BOWL,SUM,0,0,0,0,0,3,14,17.156768083572388 +41,CUP,SUM,0,0,0,0,0,1,59,24.2078697681427 +41,SPOON,SUM,0,0,0,0,0,23,20,22.904385805130005 +41,,SUM,0,0,0,0,0,27,93,64.26902365684509 +41,, +42,, +42,BOWL,SUM,0,0,0,0,0,2,2,8.719316005706787 +42,CUP,SUM,0,0,0,0,0,0,16,12.185566902160645 +42,SPOON,SUM,0,0,0,0,0,0,6,14.272743940353394 +42,,SUM,0,0,0,0,0,2,24,35.177626848220825 +42,, +43,, +43,BOWL,SUM,0,0,0,0,0,5,6,14.38601016998291 +43,CUP,SUM,0,0,0,0,0,5,34,24.549623012542725 +43,SPOON,SUM,1,0,1,0,8,1582,0,0.0 +43,,SUM,1,0,1,0,8,1592,40,38.935633182525635 +43,, +44,, +44,BOWL,SUM,0,0,0,0,0,2,0,8.6159508228302 +44,CUP,SUM,0,0,0,0,0,8,85,45.49362015724182 +44,SPOON,SUM,1,0,1,0,0,1110,104,0.0 +44,,SUM,1,0,1,0,0,1120,189,54.10957098007202 +44,, +45,, +45,BOWL,SUM,0,0,0,0,0,3,1,10.092656135559082 +45,CUP,SUM,0,0,0,0,2,2,13,16.90589714050293 +45,SPOON,SUM,1,0,1,0,2,1581,0,0.0 +45,,SUM,1,0,1,0,4,1586,14,26.99855327606201 +45,, +46,, +46,BOWL,SUM,0,0,0,0,0,1,14,17.396122217178345 +46,CUP,SUM,0,0,0,0,0,26,44,48.18840789794922 +46,SPOON,SUM,0,0,0,0,0,13,12,23.09922504425049 +46,,SUM,0,0,0,0,0,40,70,88.68375515937805 +46,, +47,, +47,BOWL,SUM,1,0,1,0,16,905,144,0.0 +47,CUP,SUM,0,0,0,0,0,1,28,15.005815982818604 +47,SPOON,SUM,0,0,0,0,0,2,1,13.684960126876831 +47,,SUM,1,0,1,0,16,908,173,28.690776109695435 +47,, +48,, +48,BOWL,SUM,0,0,0,0,2,82,107,64.65864896774292 +48,CUP,SUM,0,0,0,0,8,5,28,27.67088508605957 +48,SPOON,SUM,0,0,0,0,0,1,3,15.887479066848755 +48,,SUM,0,0,0,0,10,88,138,108.21701312065125 +48,, +49,, +49,BOWL,SUM,0,0,0,0,0,0,10,12.93373990058899 +49,CUP,SUM,0,0,0,0,0,5,11,13.951781034469604 +49,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +49,,SUM,1,0,1,0,0,1586,21,26.885520935058594 +49,, +50,, +50,BOWL,SUM,0,0,0,0,0,5,3,10.53671407699585 +50,CUP,SUM,0,0,0,0,0,0,12,11.12476897239685 +50,SPOON,SUM,0,0,0,0,10,9,8,21.043680906295776 +50,,SUM,0,0,0,0,10,14,23,42.70516395568848 +50,, +51,, +51,BOWL,SUM,1,0,1,0,0,281,200,0.0 +51,CUP,SUM,0,0,0,0,0,0,8,8.018105030059814 +51,SPOON,SUM,0,0,0,0,0,0,21,24.36358618736267 +51,,SUM,1,0,1,0,0,281,229,32.381691217422485 +51,, +52,, +52,BOWL,SUM,1,0,1,0,0,278,198,0.0 +52,CUP,SUM,0,0,0,0,0,5,14,15.537199020385742 +52,SPOON,SUM,0,0,0,0,0,3,9,17.701005935668945 +52,,SUM,1,0,1,0,0,286,221,33.23820495605469 +52,, +53,, +53,BOWL,SUM,1,0,1,0,0,1466,28,0.0 +53,CUP,SUM,0,0,0,0,0,3,52,30.662821054458618 +53,SPOON,SUM,0,0,0,0,0,0,0,11.976227045059204 +53,,SUM,1,0,1,0,0,1469,80,42.63904809951782 +53,, +54,, +54,BOWL,SUM,0,0,0,0,0,1,27,24.158150911331177 +54,CUP,SUM,0,0,0,0,16,190,501,207.6888267993927 +54,SPOON,SUM,0,0,0,0,0,0,3,13.429229021072388 +54,,SUM,0,0,0,0,16,191,531,245.27620673179626 +54,, +55,, +55,BOWL,SUM,1,0,1,0,0,755,180,0.0 +55,CUP,SUM,0,0,0,0,0,2,12,11.600555896759033 +55,SPOON,SUM,0,0,0,0,0,3,9,16.74602699279785 +55,,SUM,1,0,1,0,0,760,201,28.346582889556885 +55,, +56,, +56,BOWL,SUM,0,0,0,0,0,2,14,15.138602018356323 +56,CUP,SUM,0,0,0,0,0,391,276,136.73033714294434 +56,SPOON,SUM,0,0,0,0,0,1,0,12.039993047714233 +56,,SUM,0,0,0,0,0,394,290,163.9089322090149 +56,, +57,, +57,BOWL,SUM,0,0,0,0,0,0,17,16.297691106796265 +57,CUP,SUM,0,0,0,0,0,7,38,23.73480200767517 +57,SPOON,SUM,1,0,1,0,0,1008,136,0.0 +57,,SUM,1,0,1,0,0,1015,191,40.032493114471436 +57,, +58,, +58,BOWL,SUM,0,0,0,0,0,2,1,11.857285976409912 +58,CUP,SUM,1,0,0,1,0,39,59,0.0 +58,SPOON,SUM,1,0,1,0,16,1270,42,0.0 +58,,SUM,2,0,1,1,16,1311,102,11.857285976409912 +58,, +59,, +59,BOWL,SUM,1,0,1,0,0,1302,72,0.0 +59,CUP,SUM,0,0,0,0,0,4,25,20.84594702720642 +59,SPOON,SUM,0,0,0,0,0,5,3,16.58079981803894 +59,,SUM,1,0,1,0,0,1311,100,37.42674684524536 +59,, +60,, +60,BOWL,SUM,0,0,0,0,0,2,0,9.670446157455444 +60,CUP,SUM,1,0,1,0,10,1227,255,0.0 +60,SPOON,SUM,0,0,0,0,0,0,0,11.657161951065063 +60,,SUM,1,0,1,0,10,1229,255,21.327608108520508 +60,, +61,, +61,BOWL,SUM,0,0,0,0,0,2,23,22.12329602241516 +61,CUP,SUM,0,0,0,0,24,96,6,37.71416091918945 +61,SPOON,SUM,0,0,0,0,8,4,12,26.535336017608643 +61,,SUM,0,0,0,0,32,102,41,86.37279295921326 +61,, +62,, +62,BOWL,SUM,0,0,0,0,0,30,38,40.22603392601013 +62,CUP,SUM,0,0,0,0,0,4,50,24.5029878616333 +62,SPOON,SUM,0,0,0,0,0,0,0,11.168511867523193 +62,,SUM,0,0,0,0,0,34,88,75.89753365516663 +62,, +63,, +63,BOWL,SUM,0,0,0,0,2,29,9,17.262409925460815 +63,CUP,SUM,0,0,0,0,0,4,79,39.233587980270386 +63,SPOON,SUM,0,0,0,0,0,0,4,13.402683019638062 +63,,SUM,0,0,0,0,2,33,92,69.89868092536926 +63,, +64,, +64,BOWL,SUM,0,0,0,0,0,1,1,9.82887601852417 +64,CUP,SUM,0,0,0,0,0,14,44,33.311142921447754 +64,SPOON,SUM,0,0,0,0,0,3,16,18.370910167694092 +64,,SUM,0,0,0,0,0,18,61,61.510929107666016 +64,, +65,, +65,BOWL,SUM,0,0,0,0,0,1,15,15.730149984359741 +65,CUP,SUM,0,0,0,0,0,1,10,12.230621099472046 +65,SPOON,SUM,1,0,1,0,24,1583,0,0.0 +65,,SUM,1,0,1,0,24,1585,25,27.960771083831787 +65,, +66,, +66,BOWL,SUM,0,0,0,0,0,0,6,18.226905822753906 +66,CUP,SUM,0,0,0,0,0,3,63,31.559123992919922 +66,SPOON,SUM,0,0,0,0,0,12,3,14.181736946105957 +66,,SUM,0,0,0,0,0,15,72,63.967766761779785 +66,, +67,, +67,BOWL,SUM,0,0,0,0,0,6,16,19.811497926712036 +67,CUP,SUM,0,0,0,0,0,62,25,39.2946138381958 +67,SPOON,SUM,0,0,0,0,0,3,12,23.838361024856567 +67,,SUM,0,0,0,0,0,71,53,82.9444727897644 +67,, +68,, +68,BOWL,SUM,0,0,0,0,0,1,8,17.17681908607483 +68,CUP,SUM,1,0,1,0,0,647,688,0.0 +68,SPOON,SUM,0,0,0,0,0,2,5,14.693490028381348 +68,,SUM,1,0,1,0,0,650,701,31.870309114456177 +68,, +69,, +69,BOWL,SUM,0,0,0,0,0,0,1,9.067167043685913 +69,CUP,SUM,0,0,0,0,0,154,303,123.68788313865662 +69,SPOON,SUM,0,0,0,0,0,2,0,12.156394958496094 +69,,SUM,0,0,0,0,0,156,304,144.91144514083862 +69,, +70,, +70,BOWL,SUM,0,0,0,0,2,2,12,17.077754020690918 +70,CUP,SUM,0,0,0,0,0,4,66,31.220447063446045 +70,SPOON,SUM,0,0,0,0,0,45,48,38.64461398124695 +70,,SUM,0,0,0,0,2,51,126,86.94281506538391 +70,, +71,, +71,BOWL,SUM,0,0,0,0,0,3,5,12.425264120101929 +71,CUP,SUM,0,0,0,0,2,1,9,11.95126986503601 +71,SPOON,SUM,1,0,1,0,8,646,184,0.0 +71,,SUM,1,0,1,0,10,650,198,24.37653398513794 +71,, +72,, +72,BOWL,SUM,0,0,0,0,16,5,8,20.62417483329773 +72,CUP,SUM,0,0,0,0,0,6,4,10.181729793548584 +72,SPOON,SUM,0,0,0,0,4,5,8,20.08465886116028 +72,,SUM,0,0,0,0,20,16,20,50.89056348800659 +72,, +73,, +73,BOWL,SUM,0,0,0,0,0,3,10,14.456724882125854 +73,CUP,SUM,0,0,0,0,8,13,30,43.49733781814575 +73,SPOON,SUM,0,0,0,0,0,8,18,28.20351815223694 +73,,SUM,0,0,0,0,8,24,58,86.15758085250854 +73,, +74,, +74,BOWL,SUM,0,0,0,0,0,8,14,27.740752935409546 +74,CUP,SUM,0,0,0,0,0,2,29,16.05211305618286 +74,SPOON,SUM,1,0,1,0,0,1293,76,0.0 +74,,SUM,1,0,1,0,0,1303,119,43.79286599159241 +74,, +75,, +75,BOWL,SUM,1,0,1,0,8,1499,28,0.0 +75,CUP,SUM,0,0,0,0,0,4,9,10.47593092918396 +75,SPOON,SUM,0,0,0,0,0,0,1,13.77982497215271 +75,,SUM,1,0,1,0,8,1503,38,24.25575590133667 +75,, +76,, +76,BOWL,SUM,0,0,0,0,2,4,10,21.04207491874695 +76,CUP,SUM,0,0,0,0,0,2,14,15.740460872650146 +76,SPOON,SUM,0,0,0,0,0,7,21,30.189975023269653 +76,,SUM,0,0,0,0,2,13,45,66.97251081466675 +76,, +77,, +77,BOWL,SUM,0,0,0,0,2,5,6,12.497574090957642 +77,CUP,SUM,0,0,0,0,16,5,67,42.84397506713867 +77,SPOON,SUM,1,0,1,0,8,711,180,0.0 +77,,SUM,1,0,1,0,26,721,253,55.34154915809631 +77,, +78,, +78,BOWL,SUM,0,0,0,0,0,1,11,18.88516616821289 +78,CUP,SUM,0,0,0,0,38,113,123,102.10998582839966 +78,SPOON,SUM,0,0,0,0,0,6,5,19.156291007995605 +78,,SUM,0,0,0,0,38,120,139,140.15144300460815 +78,, +79,, +79,BOWL,SUM,0,0,0,0,0,9,2,10.628620147705078 +79,CUP,SUM,0,0,0,0,0,5,44,29.97930598258972 +79,SPOON,SUM,1,0,1,0,2,1412,36,0.0 +79,,SUM,1,0,1,0,2,1426,82,40.6079261302948 +79,, +80,, +80,BOWL,SUM,0,0,0,0,8,159,114,75.32941603660583 +80,CUP,SUM,0,0,0,0,0,4,19,20.471377849578857 +80,SPOON,SUM,0,0,0,0,0,1,0,11.741981983184814 +80,,SUM,0,0,0,0,8,164,133,107.5427758693695 +80,, +81,, +81,BOWL,SUM,1,0,1,0,0,650,184,0.0 +81,CUP,SUM,0,0,0,0,0,17,121,70.73364400863647 +81,SPOON,SUM,0,0,0,0,0,0,5,16.911969900131226 +81,,SUM,1,0,1,0,0,667,310,87.6456139087677 +81,, +82,, +82,BOWL,SUM,0,0,0,0,0,0,0,9.170495986938477 +82,CUP,SUM,0,0,0,0,0,11,33,47.06053185462952 +82,SPOON,SUM,0,0,0,0,0,3,3,13.979394912719727 +82,,SUM,0,0,0,0,0,14,36,70.21042275428772 +82,, +83,, +83,BOWL,SUM,0,0,0,0,0,0,2,10.796741962432861 +83,CUP,SUM,1,0,1,0,0,1022,217,0.0 +83,SPOON,SUM,0,0,0,0,0,10,13,21.39863395690918 +83,,SUM,1,0,1,0,0,1032,232,32.19537591934204 +83,, +84,, +84,BOWL,SUM,0,0,0,0,0,0,1,10.311408042907715 +84,CUP,SUM,1,0,1,0,8,1285,209,0.0 +84,SPOON,SUM,0,0,0,0,0,4,9,18.649210929870605 +84,,SUM,1,0,1,0,8,1289,219,28.96061897277832 +84,, +85,, +85,BOWL,SUM,0,0,0,0,0,4,1,11.065698146820068 +85,CUP,SUM,0,0,0,0,0,2,23,27.531572103500366 +85,SPOON,SUM,1,0,1,0,8,1581,0,0.0 +85,,SUM,1,0,1,0,8,1587,24,38.597270250320435 +85,, +86,, +86,BOWL,SUM,0,0,0,0,0,0,2,9.484333992004395 +86,CUP,SUM,0,0,0,0,0,3,25,19.872880935668945 +86,SPOON,SUM,1,0,1,0,24,1194,92,0.0 +86,,SUM,1,0,1,0,24,1197,119,29.35721492767334 +86,, +87,, +87,BOWL,SUM,0,0,0,0,0,1,1,10.460668802261353 +87,CUP,SUM,0,0,0,0,6,0,14,13.59163784980774 +87,SPOON,SUM,1,0,1,0,0,576,184,0.0 +87,,SUM,1,0,1,0,6,577,199,24.052306652069092 +87,, +88,, +88,BOWL,SUM,0,0,0,0,0,1,2,10.111532926559448 +88,CUP,SUM,0,0,0,0,2,1,10,13.031744003295898 +88,SPOON,SUM,0,0,0,0,0,30,22,25.889543056488037 +88,,SUM,0,0,0,0,2,32,34,49.032819986343384 +88,, +89,, +89,BOWL,SUM,0,0,0,0,0,7,6,17.402456998825073 +89,CUP,SUM,0,0,0,0,2,13,18,29.01715087890625 +89,SPOON,SUM,0,0,0,0,16,2,0,20.13014507293701 +89,,SUM,0,0,0,0,18,22,24,66.54975295066833 +89,, +90,, +90,BOWL,SUM,0,0,0,0,0,0,5,16.056543827056885 +90,CUP,SUM,1,0,1,0,8,848,350,0.0 +90,SPOON,SUM,0,0,0,0,0,1,1,13.293684005737305 +90,,SUM,1,0,1,0,8,849,356,29.35022783279419 +90,, +91,, +91,BOWL,SUM,0,0,0,0,8,3,52,38.92052102088928 +91,CUP,SUM,0,0,0,0,24,3,30,39.077194929122925 +91,SPOON,SUM,0,0,0,0,2,149,42,57.141937017440796 +91,,SUM,0,0,0,0,34,155,124,135.139652967453 +91,, +92,, +92,BOWL,SUM,0,0,0,0,0,0,9,14.264434814453125 +92,CUP,SUM,0,0,0,0,0,6,24,24.69369411468506 +92,SPOON,SUM,1,0,1,0,8,701,180,0.0 +92,,SUM,1,0,1,0,8,707,213,38.958128929138184 +92,, +93,, +93,BOWL,SUM,0,0,0,0,0,1,1,10.985059976577759 +93,CUP,SUM,0,0,0,0,0,3,10,14.604749202728271 +93,SPOON,SUM,1,0,1,0,16,1581,0,0.0 +93,,SUM,1,0,1,0,16,1585,11,25.58980917930603 +93,, +94,, +94,BOWL,SUM,1,0,1,0,0,1472,28,0.0 +94,CUP,SUM,0,0,0,0,0,0,8,9.93462586402893 +94,SPOON,SUM,0,0,0,0,2,3,7,21.783353090286255 +94,,SUM,1,0,1,0,2,1475,43,31.717978954315186 +94,, +95,, +95,BOWL,SUM,0,0,0,0,0,5,12,28.865066051483154 +95,CUP,SUM,0,0,0,0,2,64,118,75.00186204910278 +95,SPOON,SUM,0,0,0,0,0,3,4,16.49447202682495 +95,,SUM,0,0,0,0,2,72,134,120.36140012741089 +95,, +96,, +96,BOWL,SUM,0,0,0,0,16,38,6,23.540854930877686 +96,CUP,SUM,0,0,0,0,8,4,40,24.850946187973022 +96,SPOON,SUM,0,0,0,0,0,3,8,18.613851070404053 +96,,SUM,0,0,0,0,24,45,54,67.00565218925476 +96,, +97,, +97,BOWL,SUM,0,0,0,0,2,1,11,16.249590158462524 +97,CUP,SUM,0,0,0,0,0,6,29,28.12461805343628 +97,SPOON,SUM,0,0,0,0,0,2,4,15.9788179397583 +97,,SUM,0,0,0,0,2,9,44,60.353026151657104 +97,, +98,, +98,BOWL,SUM,0,0,0,0,0,3,14,18.310253143310547 +98,CUP,SUM,0,0,0,0,0,17,43,44.222975969314575 +98,SPOON,SUM,0,0,0,0,40,169,56,77.37796902656555 +98,,SUM,0,0,0,0,40,189,113,139.91119813919067 +98,, +99,, +99,BOWL,SUM,0,0,0,0,0,2,4,12.556239128112793 +99,CUP,SUM,0,0,0,0,0,5,22,17.979054927825928 +99,SPOON,SUM,0,0,0,0,8,4,3,18.51698088645935 +99,,SUM,0,0,0,0,8,11,29,49.05227494239807 +99,, diff --git a/cram_knowrob/cram_knowrob_vr/experiments/param_fail.csv b/cram_knowrob/cram_knowrob_vr/experiments/param_fail.csv new file mode 100644 index 0000000000..439d99d931 --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/experiments/param_fail.csv @@ -0,0 +1,359 @@ +RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC +,,,,,,,,,, +,,,,,,,,,, +0,,,,,,,,,, +0,BOWL,SUM,0,0,0,0,0,112,16,32.7683079243 +0,CUP,SUM,1,0,1,0,10,316,55,0 +0,SPOON,SUM,0,0,0,0,0,29,2,17.0862081051 +0,,SUM,1,0,1,0,10,457,73,49.8545160294 +0,,,,,,,,,, +1,, +1,BOWL,SUM,0,0,0,0,0,41,8,20.2760112285614 +1,CUP,SUM,1,0,1,0,2,253,58,0.0 +1,SPOON,SUM,0,0,0,0,0,5,0,14.174990892410278 +1,,SUM,1,0,1,0,2,299,66,34.45100212097168 +1,, +2,, +2,BOWL,SUM,1,0,1,0,0,1394,24,0.0 +2,CUP,SUM,0,0,0,0,2,26,10,21.474703073501587 +2,SPOON,SUM,0,0,0,0,0,72,0,18.084784030914307 +2,,SUM,1,0,1,0,2,1492,34,39.559487104415894 +2,, +3,, +3,BOWL,SUM,0,0,0,0,0,24,2,12.354676008224487 +3,CUP,SUM,0,0,0,0,0,26,6,11.680999040603638 +3,SPOON,SUM,0,0,0,0,2,164,2,26.44410991668701 +3,,SUM,0,0,0,0,2,214,10,50.47978496551514 +3,, +4,, +4,BOWL,SUM,0,0,0,0,0,85,0,14.934913873672485 +4,CUP,SUM,0,0,0,0,0,21,5,10.665835857391357 +4,SPOON,SUM,0,0,0,0,24,322,1,40.62073087692261 +4,,SUM,0,0,0,0,24,428,6,66.22148060798645 +4,, +5,, +5,BOWL,SUM,1,0,1,0,24,1053,64,0.0 +5,CUP,SUM,1,0,1,0,0,467,58,0.0 +5,SPOON,SUM,0,0,0,0,0,71,0,16.666606187820435 +5,,SUM,2,0,2,0,24,1591,122,16.666606187820435 +5,, +6,, +6,BOWL,SUM,0,0,0,0,0,95,0,15.163646936416626 +6,CUP,SUM,0,0,0,0,0,5,8,11.211496114730835 +6,SPOON,SUM,1,0,1,0,20,1446,0,0.0 +6,,SUM,1,0,1,0,20,1546,8,26.37514305114746 +6,, +7,, +7,BOWL,SUM,0,0,0,0,14,12,0,15.97328805923462 +7,CUP,SUM,0,0,0,0,0,13,1,8.52950382232666 +7,SPOON,SUM,1,0,1,0,12,1489,0,0.0 +7,,SUM,1,0,1,0,26,1514,1,24.50279188156128 +7,, +8,, +8,BOWL,SUM,0,0,0,0,0,80,0,12.848326921463013 +8,CUP,SUM,1,0,1,0,2,235,111,0.0 +8,SPOON,SUM,0,0,0,0,0,14,0,13.550479173660278 +8,,SUM,1,0,1,0,2,329,111,26.39880609512329 +8,, +9,, +9,BOWL,SUM,1,0,1,0,0,1075,58,0.0 +9,CUP,SUM,0,0,0,0,0,34,17,17.961838960647583 +9,SPOON,SUM,1,0,1,0,0,1434,18,0.0 +9,,SUM,2,0,2,0,0,2543,93,17.961838960647583 +9,, +10,, +10,BOWL,SUM,0,0,0,0,6,26,2,12.71499490737915 +10,CUP,SUM,1,0,1,0,0,407,106,0.0 +10,SPOON,SUM,0,0,0,0,0,267,1,28.428436994552612 +10,,SUM,1,0,1,0,6,700,109,41.14343190193176 +10,, +11,, +11,BOWL,SUM,1,0,1,0,0,1312,34,0.0 +11,CUP,SUM,0,0,0,0,0,83,32,40.973098039627075 +11,SPOON,SUM,0,0,0,0,0,71,3,17.311681985855103 +11,,SUM,1,0,1,0,0,1466,69,58.28478002548218 +11,, +12,, +12,BOWL,SUM,1,0,1,0,0,744,90,0.0 +12,CUP,SUM,0,0,0,0,0,37,14,14.374969005584717 +12,SPOON,SUM,1,0,1,0,0,1106,54,0.0 +12,,SUM,2,0,2,0,0,1887,158,14.374969005584717 +12,, +13,, +13,BOWL,SUM,1,0,1,0,0,951,72,0.0 +13,CUP,SUM,1,0,1,0,4,362,76,0.0 +13,SPOON,SUM,1,0,1,0,98,576,0,0.0 +13,,SUM,3,0,3,0,102,1889,148,0.0 +13,, +14,, +14,BOWL,SUM,0,0,0,0,0,21,0,10.263143062591553 +14,CUP,SUM,0,0,0,0,0,8,9,10.254493951797485 +14,SPOON,SUM,0,0,0,0,0,1,1,14.509182929992676 +14,,SUM,0,0,0,0,0,30,10,35.026819944381714 +14,, +15,, +15,BOWL,SUM,0,0,0,0,0,9,6,13.228445053100586 +15,CUP,SUM,0,0,0,0,0,18,11,11.852144002914429 +15,SPOON,SUM,0,0,0,0,0,6,3,14.842733144760132 +15,,SUM,0,0,0,0,0,33,20,39.92332220077515 +15,, +16,, +16,BOWL,SUM,1,0,1,0,16,1414,8,0.0 +16,CUP,SUM,0,0,0,0,0,36,8,10.842745065689087 +16,SPOON,SUM,0,0,0,0,2,98,0,19.609802961349487 +16,,SUM,1,0,1,0,18,1548,16,30.452548027038574 +16,, +17,, +17,BOWL,SUM,1,0,1,0,6,1197,48,0.0 +17,CUP,SUM,0,0,0,0,0,25,7,10.969455003738403 +17,SPOON,SUM,0,0,0,0,0,292,1,30.241516828536987 +17,,SUM,1,0,1,0,6,1514,56,41.21097183227539 +17,, +18,, +18,BOWL,SUM,0,0,0,0,2,52,0,12.89676308631897 +18,CUP,SUM,0,0,0,0,0,140,33,48.64931392669678 +18,SPOON,SUM,1,0,1,0,16,1524,0,0.0 +18,,SUM,1,0,1,0,18,1716,33,61.54607701301575 +18,, +19,, +19,BOWL,SUM,0,0,0,0,0,14,0,10.383922815322876 +19,CUP,SUM,0,0,0,0,0,21,4,8.84513783454895 +19,SPOON,SUM,0,0,0,0,2,7,6,16.913980960845947 +19,,SUM,0,0,0,0,2,42,10,36.14304161071777 +19,, +20,, +20,BOWL,SUM,1,0,1,0,0,1269,36,0.0 +20,CUP,SUM,0,0,0,0,2,46,31,30.129568099975586 +20,SPOON,SUM,0,0,0,0,0,12,0,13.21860384941101 +20,,SUM,1,0,1,0,2,1327,67,43.3481719493866 +20,, +21,, +21,BOWL,SUM,1,0,1,0,0,1450,20,0.0 +21,CUP,SUM,1,0,1,0,0,465,61,0.0 +21,SPOON,SUM,0,0,0,0,0,4,1,14.969137191772461 +21,,SUM,2,0,2,0,0,1919,82,14.969137191772461 +21,, +22,, +22,BOWL,SUM,1,0,1,0,0,1509,12,0.0 +22,CUP,SUM,0,0,0,0,0,5,2,8.573272943496704 +22,SPOON,SUM,1,0,1,0,28,1360,0,0.0 +22,,SUM,2,0,2,0,28,2874,14,8.573272943496704 +22,, +23,, +23,BOWL,SUM,0,0,0,0,32,53,0,27.208103895187378 +23,CUP,SUM,1,0,1,0,0,266,110,0.0 +23,SPOON,SUM,1,0,1,0,12,1554,0,0.0 +23,,SUM,2,0,2,0,44,1873,110,27.208103895187378 +23,, +24,, +24,BOWL,SUM,1,0,1,0,6,1177,52,0.0 +24,CUP,SUM,0,0,0,0,0,57,7,16.64921498298645 +24,SPOON,SUM,0,0,0,0,0,232,2,25.057204008102417 +24,,SUM,1,0,1,0,6,1466,61,41.70641899108887 +24,, +25,, +25,BOWL,SUM,0,0,0,0,0,122,15,24.12792992591858 +25,CUP,SUM,0,0,0,0,0,5,6,8.821661949157715 +25,SPOON,SUM,0,0,0,0,0,0,1,14.885889053344727 +25,,SUM,0,0,0,0,0,127,22,47.83548092842102 +25,, +26,, +26,BOWL,SUM,1,0,1,0,0,1375,30,0.0 +26,CUP,SUM,0,0,0,0,0,36,5,12.129531860351563 +26,SPOON,SUM,0,0,0,0,0,193,3,27.874703884124756 +26,,SUM,1,0,1,0,0,1604,38,40.00423574447632 +26,, +27,, +27,BOWL,SUM,0,0,0,0,0,14,4,12.039686918258667 +27,CUP,SUM,1,0,1,0,4,433,106,0.0 +27,SPOON,SUM,0,0,0,0,0,531,0,42.984853982925415 +27,,SUM,1,0,1,0,4,978,110,55.02454090118408 +27,, +28,, +28,BOWL,SUM,1,0,1,0,0,1063,64,0.0 +28,CUP,SUM,0,0,0,0,16,46,16,27.430867910385132 +28,SPOON,SUM,0,0,0,0,0,130,0,20.673046827316284 +28,,SUM,1,0,1,0,16,1239,80,48.103914737701416 +28,, +29,, +29,BOWL,SUM,0,0,0,0,0,15,0,10.407140970230103 +29,CUP,SUM,0,0,0,0,2,7,9,11.257929801940918 +29,SPOON,SUM,1,0,1,0,22,1415,0,0.0 +29,,SUM,1,0,1,0,24,1437,9,21.66507077217102 +29,, +30,, +30,BOWL,SUM,1,0,1,0,22,1315,14,0.0 +30,CUP,SUM,0,0,0,0,0,20,6,12.051302909851074 +30,SPOON,SUM,0,0,0,0,0,26,0,14.096451997756958 +30,,SUM,1,0,1,0,22,1361,20,26.147754907608032 +30,, +31,, +31,BOWL,SUM,1,0,1,0,0,990,58,0.0 +31,CUP,SUM,1,0,1,0,2,441,110,0.0 +31,SPOON,SUM,1,0,1,0,0,1383,26,0.0 +31,,SUM,3,0,3,0,2,2814,194,0.0 +31,, +32,, +32,BOWL,SUM,1,0,1,0,0,1514,10,0.0 +32,CUP,SUM,0,0,0,0,2,7,7,11.36257791519165 +32,SPOON,SUM,0,0,0,0,0,14,0,14.125922918319702 +32,,SUM,1,0,1,0,2,1535,17,25.488500833511353 +32,, +33,, +33,BOWL,SUM,1,0,1,0,18,1352,14,0.0 +33,CUP,SUM,0,0,0,0,0,18,2,12.075277090072632 +33,SPOON,SUM,1,0,1,0,6,1406,28,0.0 +33,,SUM,2,0,2,0,24,2776,44,12.075277090072632 +33,, +34,, +34,BOWL,SUM,1,0,1,0,0,1126,52,0.0 +34,CUP,SUM,0,0,0,0,0,56,23,22.634598970413208 +34,SPOON,SUM,0,0,0,0,0,8,2,13.914203882217407 +34,,SUM,1,0,1,0,0,1190,77,36.548802852630615 +34,, +35,, +35,BOWL,SUM,1,0,1,0,0,1405,24,0.0 +35,CUP,SUM,0,0,0,0,2,45,11,16.06694793701172 +35,SPOON,SUM,1,0,1,0,32,1344,0,0.0 +35,,SUM,2,0,2,0,34,2794,35,16.06694793701172 +35,, +36,, +36,BOWL,SUM,1,0,1,0,0,1167,50,0.0 +36,CUP,SUM,0,0,0,0,0,67,25,32.0824818611145 +36,SPOON,SUM,0,0,0,0,0,168,15,31.008002996444702 +36,,SUM,1,0,1,0,0,1402,90,63.090484857559204 +36,, +37,, +37,BOWL,SUM,0,0,0,0,0,28,2,11.421064138412476 +37,CUP,SUM,0,0,0,0,0,17,4,9.12125301361084 +37,SPOON,SUM,0,0,0,0,0,54,4,17.439872980117798 +37,,SUM,0,0,0,0,0,99,10,37.98219013214111 +37,, +38,, +38,BOWL,SUM,0,0,0,0,0,5,0,10.175603866577148 +38,CUP,SUM,0,0,0,0,2,14,0,9.767898082733154 +38,SPOON,SUM,1,0,1,0,44,1275,0,0.0 +38,,SUM,1,0,1,0,46,1294,0,19.943501949310303 +38,, +39,, +39,BOWL,SUM,0,0,0,0,0,88,2,14.429382801055908 +39,CUP,SUM,1,0,1,0,6,466,104,0.0 +39,SPOON,SUM,1,0,1,0,0,1500,12,0.0 +39,,SUM,2,0,2,0,6,2054,118,14.429382801055908 +39,, +40,, +40,BOWL,SUM,0,0,0,0,0,22,4,13.247651100158691 +40,CUP,SUM,1,0,0,1,0,170,56,0.0 +40,SPOON,SUM,0,0,0,0,0,135,0,19.518676042556763 +40,,SUM,1,0,0,1,0,327,60,32.766327142715454 +40,, +41,, +41,BOWL,SUM,0,0,0,0,0,246,0,23.13299798965454 +41,CUP,SUM,0,0,0,0,6,134,60,55.227068185806274 +41,SPOON,SUM,0,0,0,0,0,51,0,16.17882800102234 +41,,SUM,0,0,0,0,6,431,60,94.53889417648315 +41,, +42,, +42,BOWL,SUM,1,0,1,0,0,1525,12,0.0 +42,CUP,SUM,1,0,1,0,2,230,110,0.0 +42,SPOON,SUM,0,0,0,0,0,251,2,28.711532831192017 +42,,SUM,2,0,2,0,2,2006,124,28.711532831192017 +42,, +43,, +43,BOWL,SUM,0,0,0,0,0,35,0,12.264400005340576 +43,CUP,SUM,0,0,0,0,0,68,30,40.84378695487976 +43,SPOON,SUM,0,0,0,0,2,59,4,19.810079097747803 +43,,SUM,0,0,0,0,2,162,34,72.91826605796814 +43,, +44,, +44,BOWL,SUM,0,0,0,0,0,8,2,10.819329977035522 +44,CUP,SUM,0,0,0,0,0,22,6,9.596866846084595 +44,SPOON,SUM,0,0,0,0,0,66,4,20.153451919555664 +44,,SUM,0,0,0,0,0,96,12,40.56964874267578 +44,, +45,, +45,BOWL,SUM,0,0,0,0,6,8,0,12.818115949630737 +45,CUP,SUM,1,0,1,0,0,279,111,0.0 +45,SPOON,SUM,0,0,0,0,0,235,2,28.728751182556152 +45,,SUM,1,0,1,0,6,522,113,41.54686713218689 +45,, +46,, +46,BOWL,SUM,0,0,0,0,0,20,2,11.27259612083435 +46,CUP,SUM,1,0,1,0,4,202,58,0.0 +46,SPOON,SUM,0,0,0,0,0,0,2,14.144083023071289 +46,,SUM,1,0,1,0,4,222,62,25.41667914390564 +46,, +47,, +47,BOWL,SUM,0,0,0,0,16,68,2,21.977657079696655 +47,CUP,SUM,0,0,0,0,0,18,2,9.477878093719482 +47,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +47,,SUM,1,0,1,0,16,1667,4,31.455535173416138 +47,, +48,, +48,BOWL,SUM,0,0,0,0,0,9,0,10.612251996994019 +48,CUP,SUM,1,0,1,0,0,345,108,0.0 +48,SPOON,SUM,0,0,0,0,0,42,4,17.2029390335083 +48,,SUM,1,0,1,0,0,396,112,27.81519103050232 +48,, +49,, +49,BOWL,SUM,0,0,0,0,0,4,0,10.36062502861023 +49,CUP,SUM,1,0,0,1,0,133,54,0.0 +49,SPOON,SUM,1,0,1,0,16,1407,0,0.0 +49,,SUM,2,0,1,1,16,1544,54,10.36062502861023 +49,, +50,, +50,BOWL,SUM,1,0,1,0,0,1584,0,0.0 +50,CUP,SUM,1,0,1,0,0,159,110,0.0 +50,SPOON,SUM,0,0,0,0,0,219,0,26.138139009475708 +50,,SUM,2,0,2,0,0,1962,110,26.138139009475708 +50,, +51,, +51,BOWL,SUM,0,0,0,0,2,126,4,19.865580797195435 +51,CUP,SUM,1,0,0,1,0,191,55,0.0 +51,SPOON,SUM,1,0,1,0,4,1581,0,0.0 +51,,SUM,2,0,1,1,6,1898,59,19.865580797195435 +51,, +52,, +52,BOWL,SUM,0,0,0,0,58,199,0,47.287779092788696 +52,CUP,SUM,0,0,0,0,0,47,13,14.591926097869873 +52,SPOON,SUM,0,0,0,0,0,64,1,17.259998083114624 +52,,SUM,0,0,0,0,58,310,14,79.1397032737732 +52,, +53,, +53,BOWL,SUM,0,0,0,0,0,17,1,12.33146595954895 +53,CUP,SUM,0,0,0,0,0,13,4,9.112069845199585 +53,SPOON,SUM,0,0,0,0,0,0,0,13.564654111862183 +53,,SUM,0,0,0,0,0,30,5,35.00818991661072 +53,, +54,, +54,BOWL,SUM,0,0,0,0,0,7,0,10.617570877075195 +54,CUP,SUM,0,0,0,0,0,15,7,14.73786997795105 +54,SPOON,SUM,0,0,0,0,2,107,1,21.468746185302734 +54,,SUM,0,0,0,0,2,129,8,46.82418704032898 +54,, +55,, +55,BOWL,SUM,0,0,0,0,6,21,0,12.889350175857544 +55,CUP,SUM,1,0,0,1,0,156,62,0.0 +55,SPOON,SUM,0,0,0,0,0,7,0,13.917734861373901 +55,,SUM,1,0,0,1,6,184,62,26.807085037231445 +55,, +56,, +56,BOWL,SUM,1,0,1,0,0,1150,50,0.0 +56,CUP,SUM,0,0,0,0,0,10,6,12.227536916732788 +56,SPOON,SUM,0,0,0,0,4,354,80,81.99061799049377 +56,,SUM,1,0,1,0,4,1514,136,94.21815490722656 +56,, +57,, +57,BOWL,SUM,1,0,1,0,26,1244,18,0.0 +57,CUP,SUM,0,0,0,0,0,11,0,9.134411096572876 +57,SPOON,SUM,1,0,1,0,0,1581,0,0.0 +57,,SUM,2,0,2,0,26,2836,18,9.134411096572876 +57,, +58,, +58,BOWL,SUM,1,0,1,0,0,1387,32,0.0 +58,CUP,SUM,0,0,0,0,0,8,9,9.551911115646362 +58,SPOON,SUM,0,0,0,0,0,4,5,17.128108024597168 +58,,SUM,1,0,1,0,0,1399,46,26.68001914024353 +58,, +59,, +59,BOWL,SUM,0,0,0,0,0,5,2,10.678754091262817 diff --git a/cram_knowrob/cram_knowrob_vr/src/debugging-utils.lisp b/cram_knowrob/cram_knowrob_vr/src/debugging-utils.lisp index dfe653d687..4fb0a487fc 100644 --- a/cram_knowrob/cram_knowrob_vr/src/debugging-utils.lisp +++ b/cram_knowrob/cram_knowrob_vr/src/debugging-utils.lisp @@ -82,9 +82,7 @@ If the result is anything but NIL, the world is stable." (cpl:seq (exe:perform (desig:an action - (type positioning-arm) - (left-configuration park) - (right-configuration park))))))) + (type parking-arms))))))) ;;if in back 'cereal-5 diff --git a/cram_knowrob/cram_knowrob_vr/src/experiment-log-generator.lisp b/cram_knowrob/cram_knowrob_vr/src/experiment-log-generator.lisp new file mode 100644 index 0000000000..124f1bd58f --- /dev/null +++ b/cram_knowrob/cram_knowrob_vr/src/experiment-log-generator.lisp @@ -0,0 +1,268 @@ +;; +;;; Copyright (c) 2019, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :kvr) + +(defparameter *experiment-log-filename* "package://cram_knowrob_vr/experiments/failures") +(defparameter *experiment-log-extension* ".csv") + +(defparameter *experiment-log-detailed?* nil) + +(defvar *experiment-log-current-object* nil) + +(defvar *experiment-log-current-demo-run-vr* -1) +(defvar *experiment-log-current-demo-run-heur* -1) + +(defparameter *experiment-log-failures-to-count* + '(common-fail:searching-failed common-fail:fetching-failed common-fail:delivering-failed + common-fail:perception-low-level-failure common-fail:navigation-low-level-failure + common-fail:manipulation-low-level-failure common-fail:ptu-low-level-failure)) +(defvar *experiment-log-current-demo-run-object-failures* nil) + +(defvar *experiment-log-current-execution-time-bowl* 0) +(defvar *experiment-log-current-execution-time-cup* 0) +(defvar *experiment-log-current-execution-time-spoon* 0) + + +(defun experiment-log (string &key + (object-type *experiment-log-current-object*) + (demo-run (if *kvr-enabled* + *experiment-log-current-demo-run-vr* + *experiment-log-current-demo-run-heur*))) + (let ((file-path + (physics-utils:parse-uri + (format nil + "~a_~a~a" + *experiment-log-filename* + (if *kvr-enabled* "VR" "HEUR") + *experiment-log-extension*)))) + (unless (probe-file file-path) + (with-open-file (stream file-path + :direction :output + :if-exists :error + :if-does-not-exist :create) + (format stream "RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,~ + SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,~ + PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC~%~%~%"))) + (with-open-file (stream file-path + :direction :output + :if-exists :append + :if-does-not-exist :error) + (format stream "~a,~a,~a~%" demo-run (or object-type "") string)))) + +(defun read-last-line (file-uri) + (with-open-file (stream (physics-utils:parse-uri file-uri) + :direction :input + :if-does-not-exist nil) + (when stream + (let (last-non-empty-line) + (do ((line (read-line stream nil 'eof) + (read-line stream nil 'eof))) + ((eql line 'eof)) + (unless (string-equal + (string-trim + '(#\Space #\Newline #\Backspace #\Tab #\Linefeed #\Page #\Return #\Rubout) + (remove #\Space (remove #\, line))) + "") + (setf last-non-empty-line line))) + last-non-empty-line)))) + +(defun find-experiment-log-last-current-demo-run (&key vr?) + (let ((last-line + (read-last-line + (format nil "~a_~a~a" + *experiment-log-filename* + (if vr? + "VR" + "HEUR") + *experiment-log-extension*)))) + (if last-line + (let ((last-current-demo-run + (read-from-string (first (split-sequence:split-sequence #\, last-line))))) + (if (or (not (numberp last-current-demo-run)) (< last-current-demo-run 0)) + (error "YOUR LOG FILE IS CORRUPTED!") + last-current-demo-run)) + -1))) + +(defun set-experiment-log-current-demo-run () + (if *kvr-enabled* + (when (< *experiment-log-current-demo-run-vr* 0) + (setf *experiment-log-current-demo-run-vr* + (1+ (find-experiment-log-last-current-demo-run :vr? t)))) + (when (< *experiment-log-current-demo-run-heur* 0) + (setf *experiment-log-current-demo-run-heur* + (1+ (find-experiment-log-last-current-demo-run :vr? nil)))))) + +(defmethod cpl:fail :before (&rest args) + (let ((failure-symbol + (typecase (first args) + (symbol (first args)) + (string 'cpl:simple-plan-failure) + (cpl:plan-failure (type-of (first args))) + (t 'unknown-failure---------------------)))) + (when *experiment-log-detailed?* + (experiment-log + (cut:replace-all + (format nil "~a" failure-symbol) + '(#\Newline) " "))) + (when (and *experiment-log-current-demo-run-object-failures* + *experiment-log-current-object*) + (if (getf *experiment-log-current-demo-run-object-failures* + *experiment-log-current-object*) + (mapc (lambda (tracked-failure-symbol) + (when (subtypep failure-symbol tracked-failure-symbol) + (incf (getf (getf *experiment-log-current-demo-run-object-failures* + *experiment-log-current-object*) + tracked-failure-symbol)))) + *experiment-log-failures-to-count*) + (warn "Object ~a is not tracked for failures!" *experiment-log-current-object*))))) + + +(defun generate-empty-failure-property-list () + (let (new-prop-list) + (mapc (lambda (failure-symbol) + (setf (getf new-prop-list failure-symbol) 0)) + *experiment-log-failures-to-count*) + new-prop-list)) + +(defun get-experiment-log-failures (failure-symbol &optional object-type) + (let ((failure-num + (if object-type + (getf (getf *experiment-log-current-demo-run-object-failures* + object-type) + failure-symbol) + (+ (getf (getf *experiment-log-current-demo-run-object-failures* + 'bowl) + failure-symbol) + (getf (getf *experiment-log-current-demo-run-object-failures* + 'cup) + failure-symbol) + (getf (getf *experiment-log-current-demo-run-object-failures* + 'spoon) + failure-symbol))))) + (if (eql failure-symbol 'common-fail:perception-low-level-failure) + (/ failure-num 5) + failure-num))) + +(defun get-experiment-log-transport-duration (&optional object-type) + (if object-type + (case object-type + (bowl *experiment-log-current-execution-time-bowl*) + (cup *experiment-log-current-execution-time-cup*) + (spoon *experiment-log-current-execution-time-spoon*)) + (+ *experiment-log-current-execution-time-bowl* + *experiment-log-current-execution-time-cup* + *experiment-log-current-execution-time-spoon*))) + + +(defun experiment-log-current-demo-run-failures (&optional object-type) + (let* ((searching-failures + (get-experiment-log-failures + 'common-fail:searching-failed object-type)) + (fetching-failures + (get-experiment-log-failures + 'common-fail:fetching-failed object-type)) + (delivering-failures + (get-experiment-log-failures + 'common-fail:delivering-failed object-type)) + (transporting-failed + (+ searching-failures fetching-failures delivering-failures)) + (navigation-failures + (get-experiment-log-failures + 'common-fail:navigation-low-level-failure object-type)) + (manipulation-failures + (get-experiment-log-failures + 'common-fail:manipulation-low-level-failure object-type)) + (perception-failures + (get-experiment-log-failures + 'common-fail:perception-low-level-failure object-type)) + (duration + (get-experiment-log-transport-duration object-type))) + (experiment-log (format nil "SUM,~a,~a,~a,~a,~a,~a,~a,~f" + transporting-failed + searching-failures fetching-failures delivering-failures + perception-failures navigation-failures manipulation-failures + duration)) + (when *experiment-log-detailed?* + (experiment-log (format nil "~%"))))) + + +(defun experiment-log-start-demo-run () + (set-experiment-log-current-demo-run) + (setf *experiment-log-current-object* nil) + (if *experiment-log-detailed?* + (experiment-log (format nil "~%~%")) + (experiment-log (format nil ""))) + + (setf (getf *experiment-log-current-demo-run-object-failures* 'bowl) + (generate-empty-failure-property-list)) + (setf (getf *experiment-log-current-demo-run-object-failures* 'cup) + (generate-empty-failure-property-list)) + (setf (getf *experiment-log-current-demo-run-object-failures* 'spoon) + (generate-empty-failure-property-list)) + + (setf *experiment-log-current-execution-time-bowl* 0 + *experiment-log-current-execution-time-cup* 0 + *experiment-log-current-execution-time-spoon* 0)) + +(defun experiment-log-finish-demo-run () + (setf *experiment-log-current-object* nil) + (experiment-log-current-demo-run-failures) + (if *experiment-log-detailed?* + (experiment-log (format nil "~%~%")) + (experiment-log (format nil ""))) + (if *kvr-enabled* + (incf *experiment-log-current-demo-run-vr*) + (incf *experiment-log-current-demo-run-heur*))) + +(defun experiment-log-start-object-transport (object-type) + (setf *experiment-log-current-object* object-type) + (case object-type + (bowl (setf *experiment-log-current-execution-time-bowl* (roslisp:ros-time))) + (cup (setf *experiment-log-current-execution-time-cup* (roslisp:ros-time))) + (spoon (setf *experiment-log-current-execution-time-spoon* (roslisp:ros-time))))) + +(defun experiment-log-finish-object-transport-successful (object-type) + (when *experiment-log-detailed?* + (experiment-log (format nil "TRANSPORTING SUCCEEDED~%"))) + (case object-type + (bowl (setf *experiment-log-current-execution-time-bowl* + (- (roslisp:ros-time) *experiment-log-current-execution-time-bowl*))) + (cup (setf *experiment-log-current-execution-time-cup* + (- (roslisp:ros-time) *experiment-log-current-execution-time-cup*))) + (spoon (setf *experiment-log-current-execution-time-spoon* + (- (roslisp:ros-time) *experiment-log-current-execution-time-spoon*))))) + +(defun experiment-log-finish-object-transport-failed (object-type) + (when *experiment-log-detailed?* + (experiment-log (format nil "TRANSPORTING FAILED~%"))) + (case object-type + (bowl (setf *experiment-log-current-execution-time-bowl* 0)) + (cup (setf *experiment-log-current-execution-time-cup* 0)) + (spoon (setf *experiment-log-current-execution-time-spoon* 0)))) diff --git a/cram_knowrob/cram_knowrob_vr/src/fetch-and-deliver-based-demo.lisp b/cram_knowrob/cram_knowrob_vr/src/fetch-and-deliver-based-demo.lisp index 56f4543e57..2d0a7ad68b 100644 --- a/cram_knowrob/cram_knowrob_vr/src/fetch-and-deliver-based-demo.lisp +++ b/cram_knowrob/cram_knowrob_vr/src/fetch-and-deliver-based-demo.lisp @@ -29,12 +29,14 @@ (in-package :kvr) +;;; These are not used, as the objects are spawned randomly on the sink +;;; in randomly chosen 'buckets' (defparameter *object-spawning-poses* '((:bowl . ((1.6 0.5 0.87) (0 0 0.4 0.6))) (:cup . ((1.3 0.1 0.9) (0 0 -0.7 0.7))) (:spoon . ((1.43 0.4 0.85) (0 0 0.3 0.7))) - ;; (:breakfast-cereal . ((1.4 0.4 0.85) (0 0 0 1))) - ;; (:milk . ((1.4 0.62 0.95) (0 0 1 0))) + ;; (:breakfast-cereal . ((1.4 0.4 0.85) (0 0 0 1))) + ;; (:milk . ((1.4 0.62 0.95) (0 0 1 0))))) )) (defparameter *object-delivering-poses* @@ -46,9 +48,9 @@ )) (defparameter *object-delivering-poses-varied-kitchen* - '((bowl . ((-0.7846 0.3 0.89953) (0 0 0.1 0.9))) - (cup . ((-0.95 0.2 0.9) (0 0 0.99 0.07213))) - (spoon . ((-1.0573 0.35 0.86835) (0.0 -0.0 -0.5 0.5))))) + '((bowl . ((-0.68 0.95 0.89953) (0 0 0.1 0.9))) + (cup . ((-0.85 0.85 0.9) (0 0 0.99 0.07213))) + (spoon . ((-0.9573 1.0 0.86835) (0.0 -0.0 -0.5 0.5))))) ;; (defparameter *object-delivering-poses* ;; '((breakfast-cereal . ((1.4 0.4 0.85) (0 0 0 1))) @@ -77,18 +79,17 @@ (btr-utils:kill-all-objects) (btr:add-objects-to-mesh-list "cram_pr2_pick_place_demo") (btr:detach-all-objects (btr:get-robot-object)) - (let* ((varied-kitchen? (> (cl-transforms:y - (cl-transforms:origin - (btr:pose - (btr:rigid-body - (btr:get-environment-object) - :|KITCHEN.sink_area|)))) - 1.0)) + (let* ((sink-area-y (cl-transforms:y + (cl-transforms:origin + (btr:pose + (btr:rigid-body + (btr:get-environment-object) + :|ENVIRONMENT.sink_area|))))) (object-types '(:cup :bowl :spoon)) (delta-alpha (* 2 pi)) (delta-y 0.3) - (x0 (if varied-kitchen? 1.25 1.35)) - (y0 (if varied-kitchen? 1.0 (- 0.2))) + (x0 1.35) + (y0 (- sink-area-y 0.3)) (y-bucket-padding 0.2) (y-bucket-length 0.3) (y-buckets (alexandria:shuffle '(0 1 2)))) @@ -137,9 +138,7 @@ (cpl:par (exe:perform (desig:an action - (type positioning-arm) - (left-configuration park) - (right-configuration park))) + (type parking-arms))) (let ((?pose (cl-transforms-stamped:make-pose-stamped cram-tf:*fixed-frame* 0.0 @@ -166,23 +165,20 @@ (setf proj-reasoning::*projection-checks-enabled* t) (btr:detach-all-objects (btr:get-robot-object)) - (btr:detach-all-objects (btr:object btr:*current-bullet-world* :kitchen)) + (btr:detach-all-objects (btr:get-environment-object)) (btr-utils:kill-all-objects) - (setf (btr:joint-state (btr:object btr:*current-bullet-world* :kitchen) + (setf (btr:joint-state (btr:get-environment-object) "sink_area_left_upper_drawer_main_joint") 0.0) (btr-belief::publish-environment-joint-state - (btr:joint-states (btr:object btr:*current-bullet-world* :kitchen))) + (btr:joint-states (btr:get-environment-object))) (setf desig::*designators* (tg:make-weak-hash-table :weakness :key)) (unless cram-projection:*projection-environment* (json-prolog:prolog-simple "rdf_retractall(A,B,C,belief_state).") ;; (cram-occasions-events:clear-belief) ; to clear giskard environment - ) - - ;; (setf cram-robot-pose-guassian-costmap::*orientation-samples* 3) - ) + )) (defun finalize () ;; (setf proj-reasoning::*projection-reasoning-enabled* nil) @@ -199,250 +195,6 @@ ;; (ccl::connect-to-cloud-logger) ;; (ccl::reset-logged-owl)) - -;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; EXPERIMENT LOG STUFF ;;;;;;;;;;;;;;;;;;;;; - -(defparameter *experiment-log-filename* "package://cram_knowrob_vr/experiments/failures") -(defparameter *experiment-log-extension* ".csv") - -(defparameter *experiment-log-detailed?* nil) - -(defvar *experiment-log-current-object* nil) - -(defvar *experiment-log-current-demo-run-vr* -1) -(defvar *experiment-log-current-demo-run-heur* -1) - -(defparameter *experiment-log-failures-to-count* - '(common-fail:searching-failed common-fail:fetching-failed common-fail:delivering-failed - common-fail:perception-low-level-failure common-fail:navigation-low-level-failure - common-fail:manipulation-low-level-failure common-fail:ptu-low-level-failure)) -(defvar *experiment-log-current-demo-run-object-failures* nil) - -(defvar *experiment-log-current-execution-time-bowl* 0) -(defvar *experiment-log-current-execution-time-cup* 0) -(defvar *experiment-log-current-execution-time-spoon* 0) - - -(defun experiment-log (string &key - (object-type *experiment-log-current-object*) - (demo-run (if *kvr-enabled* - *experiment-log-current-demo-run-vr* - *experiment-log-current-demo-run-heur*))) - (let ((file-path - (physics-utils:parse-uri - (format nil - "~a_~a~a" - *experiment-log-filename* - (if *kvr-enabled* "VR" "HEUR") - *experiment-log-extension*)))) - (unless (probe-file file-path) - (with-open-file (stream file-path - :direction :output - :if-exists :error - :if-does-not-exist :create) - (format stream "RUN_ID,OBJ_TYPE,FAIL_TYPE,TRANSPORT_FAIL,~ - SEARCH_FAIL,FETCH_FAIL,DELIVER_FAIL,~ - PERCEPT_FAIL,NAV_FAIL,MANIP_FAIL,TIME_SEC~%~%~%"))) - (with-open-file (stream file-path - :direction :output - :if-exists :append - :if-does-not-exist :error) - (format stream "~a,~a,~a~%" demo-run (or object-type "") string)))) - -(defun read-last-line (file-uri) - (with-open-file (stream (physics-utils:parse-uri file-uri) - :direction :input - :if-does-not-exist nil) - (when stream - (let (last-non-empty-line) - (do ((line (read-line stream nil 'eof) - (read-line stream nil 'eof))) - ((eql line 'eof)) - (unless (string-equal - (string-trim - '(#\Space #\Newline #\Backspace #\Tab #\Linefeed #\Page #\Return #\Rubout) - (remove #\Space (remove #\, line))) - "") - (setf last-non-empty-line line))) - last-non-empty-line)))) - -(defun find-experiment-log-last-current-demo-run (&key vr?) - (let ((last-line - (read-last-line - (format nil "~a_~a~a" - *experiment-log-filename* - (if vr? - "VR" - "HEUR") - *experiment-log-extension*)))) - (if last-line - (let ((last-current-demo-run - (read-from-string (first (split-sequence:split-sequence #\, last-line))))) - (if (or (not (numberp last-current-demo-run)) (< last-current-demo-run 0)) - (error "YOUR LOG FILE IS CORRUPTED!") - last-current-demo-run)) - -1))) - -(defun set-experiment-log-current-demo-run () - (if *kvr-enabled* - (when (< *experiment-log-current-demo-run-vr* 0) - (setf *experiment-log-current-demo-run-vr* - (1+ (find-experiment-log-last-current-demo-run :vr? t)))) - (when (< *experiment-log-current-demo-run-heur* 0) - (setf *experiment-log-current-demo-run-heur* - (1+ (find-experiment-log-last-current-demo-run :vr? nil)))))) - -(defmethod cpl:fail :before (&rest args) - (let ((failure-symbol - (typecase (first args) - (symbol (first args)) - (string 'cpl:simple-plan-failure) - (cpl:plan-failure (type-of (first args))) - (t 'unknown-failure---------------------)))) - (when *experiment-log-detailed?* - (experiment-log - (btr-belief::replace-all - (format nil "~a" failure-symbol) - '(#\Newline) " "))) - (when (and *experiment-log-current-demo-run-object-failures* - *experiment-log-current-object*) - (if (getf *experiment-log-current-demo-run-object-failures* - *experiment-log-current-object*) - (mapc (lambda (tracked-failure-symbol) - (when (subtypep failure-symbol tracked-failure-symbol) - (incf (getf (getf *experiment-log-current-demo-run-object-failures* - *experiment-log-current-object*) - tracked-failure-symbol)))) - *experiment-log-failures-to-count*) - (warn "Object ~a is not tracked for failures!" *experiment-log-current-object*))))) - - -(defun generate-empty-failure-property-list () - (let (new-prop-list) - (mapc (lambda (failure-symbol) - (setf (getf new-prop-list failure-symbol) 0)) - *experiment-log-failures-to-count*) - new-prop-list)) - -(defun get-experiment-log-failures (failure-symbol &optional object-type) - (let ((failure-num - (if object-type - (getf (getf *experiment-log-current-demo-run-object-failures* - object-type) - failure-symbol) - (+ (getf (getf *experiment-log-current-demo-run-object-failures* - 'bowl) - failure-symbol) - (getf (getf *experiment-log-current-demo-run-object-failures* - 'cup) - failure-symbol) - (getf (getf *experiment-log-current-demo-run-object-failures* - 'spoon) - failure-symbol))))) - (if (eql failure-symbol 'common-fail:perception-low-level-failure) - (/ failure-num 5) - failure-num))) - -(defun get-experiment-log-transport-duration (&optional object-type) - (if object-type - (case object-type - (bowl *experiment-log-current-execution-time-bowl*) - (cup *experiment-log-current-execution-time-cup*) - (spoon *experiment-log-current-execution-time-spoon*)) - (+ *experiment-log-current-execution-time-bowl* - *experiment-log-current-execution-time-cup* - *experiment-log-current-execution-time-spoon*))) - - -(defun experiment-log-current-demo-run-failures (&optional object-type) - (let* ((searching-failures - (get-experiment-log-failures - 'common-fail:searching-failed object-type)) - (fetching-failures - (get-experiment-log-failures - 'common-fail:fetching-failed object-type)) - (delivering-failures - (get-experiment-log-failures - 'common-fail:delivering-failed object-type)) - (transporting-failed - (+ searching-failures fetching-failures delivering-failures)) - (navigation-failures - (get-experiment-log-failures - 'common-fail:navigation-low-level-failure object-type)) - (manipulation-failures - (get-experiment-log-failures - 'common-fail:manipulation-low-level-failure object-type)) - (perception-failures - (get-experiment-log-failures - 'common-fail:perception-low-level-failure object-type)) - (duration - (get-experiment-log-transport-duration object-type))) - (experiment-log (format nil "SUM,~a,~a,~a,~a,~a,~a,~a,~f" - transporting-failed - searching-failures fetching-failures delivering-failures - perception-failures navigation-failures manipulation-failures - duration)) - (when *experiment-log-detailed?* - (experiment-log (format nil "~%"))))) - - -(defun experiment-log-start-demo-run () - (set-experiment-log-current-demo-run) - (setf *experiment-log-current-object* nil) - (if *experiment-log-detailed?* - (experiment-log (format nil "~%~%")) - (experiment-log (format nil ""))) - - (setf (getf *experiment-log-current-demo-run-object-failures* 'bowl) - (generate-empty-failure-property-list)) - (setf (getf *experiment-log-current-demo-run-object-failures* 'cup) - (generate-empty-failure-property-list)) - (setf (getf *experiment-log-current-demo-run-object-failures* 'spoon) - (generate-empty-failure-property-list)) - - (setf *experiment-log-current-execution-time-bowl* 0 - *experiment-log-current-execution-time-cup* 0 - *experiment-log-current-execution-time-spoon* 0)) - -(defun experiment-log-finish-demo-run () - (setf *experiment-log-current-object* nil) - (experiment-log-current-demo-run-failures) - (if *experiment-log-detailed?* - (experiment-log (format nil "~%~%")) - (experiment-log (format nil ""))) - (if *kvr-enabled* - (incf *experiment-log-current-demo-run-vr*) - (incf *experiment-log-current-demo-run-heur*))) - -(defun experiment-log-start-object-transport (object-type) - (setf *experiment-log-current-object* object-type) - (case object-type - (bowl (setf *experiment-log-current-execution-time-bowl* (roslisp:ros-time))) - (cup (setf *experiment-log-current-execution-time-cup* (roslisp:ros-time))) - (spoon (setf *experiment-log-current-execution-time-spoon* (roslisp:ros-time))))) - -(defun experiment-log-finish-object-transport-successful (object-type) - (when *experiment-log-detailed?* - (experiment-log (format nil "TRANSPORTING SUCCEEDED~%"))) - (case object-type - (bowl (setf *experiment-log-current-execution-time-bowl* - (- (roslisp:ros-time) *experiment-log-current-execution-time-bowl*))) - (cup (setf *experiment-log-current-execution-time-cup* - (- (roslisp:ros-time) *experiment-log-current-execution-time-cup*))) - (spoon (setf *experiment-log-current-execution-time-spoon* - (- (roslisp:ros-time) *experiment-log-current-execution-time-spoon*))))) - -(defun experiment-log-finish-object-transport-failed (object-type) - (when *experiment-log-detailed?* - (experiment-log (format nil "TRANSPORTING FAILED~%"))) - (case object-type - (bowl (setf *experiment-log-current-execution-time-bowl* 0)) - (cup (setf *experiment-log-current-execution-time-cup* 0)) - (spoon (setf *experiment-log-current-execution-time-spoon* 0)))) - -;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; END OF EXPERIMENT LOG STUFF ;;;;;;;;;;;;;;; - - (defun demo (&optional (list-of-objects '(bowl @@ -456,122 +208,86 @@ (spawn-objects-on-sink-counter)) (park-robot) - (dolist (type list-of-objects) - - (experiment-log-start-object-transport type) - - (cpl:with-failure-handling - ((common-fail:high-level-failure (e) - (declare (ignore e)) - (experiment-log-finish-object-transport-failed type) - (return))) - - (if *kvr-enabled* - - (let* ((?bullet-type - (object-type-filter-bullet type)) - (?search-poses - (alexandria:shuffle - (cut:force-ll (look-poses-ll-for-searching type)))) - (?grasps - (alexandria:shuffle - (ecase ?bullet-type - (:bowl '(:top)) - (:cup '(::RIGHT-SIDE :FRONT :LEFT-SIDE :TOP :BACK)) - (:spoon '(:top))) - ;; (cut:force-ll (object-grasped-faces-ll-from-kvr-type type)) - )) - (?arms - (alexandria:shuffle - '(:left :right) ;; (cut:force-ll (arms-for-fetching-ll type)) - )) - (bowl-pose - (cl-transforms-stamped:pose->pose-stamped - cram-tf:*fixed-frame* 0.0 - (cram-tf:list->pose - (cdr (assoc 'bowl - (if (> (cl-transforms:y - (cl-transforms:origin - (btr:pose - (btr:rigid-body - (btr:get-environment-object) - :|KITCHEN.sink_area|)))) - 1.0) - *object-delivering-poses-varied-kitchen* - *object-delivering-poses*)))))) - (bowl-transform - (cram-tf:pose-stamped->transform-stamped bowl-pose "bowl")) - (?delivering-poses - (case ?bullet-type - (:bowl (list bowl-pose)) - (t - (list (cl-transforms-stamped:pose->pose-stamped - cram-tf:*fixed-frame* 0.0 - (cram-tf:list->pose - (cdr (assoc type - (if (> (cl-transforms:y - (cl-transforms:origin - (btr:pose - (btr:rigid-body - (btr:get-environment-object) - :|KITCHEN.sink_area|)))) - 1.0) - *object-delivering-poses-varied-kitchen* - *object-delivering-poses*)))))) - ;; (alexandria:shuffle - ;; (cut:force-ll (object-poses-ll-for-placing type bowl-transform))) - )))) - - (exe:perform - (desig:an action - (type transporting) - (object (desig:an object (type ?bullet-type))) - (location (desig:a location (poses ?search-poses))) - (arms ?arms) - (grasps ?grasps) - (target (desig:a location (poses ?delivering-poses)))))) - - (let ((?bullet-type - (object-type-filter-bullet type)) - ;; (?arms - ;; (alexandria:shuffle '(:left :right))) - (?delivering-poses - (list (cl-transforms-stamped:pose->pose-stamped - cram-tf:*fixed-frame* 0.0 - (cram-tf:list->pose - (cdr (assoc type - (if (> (cl-transforms:y - (cl-transforms:origin - (btr:pose - (btr:rigid-body - (btr:get-environment-object) - :|KITCHEN.sink_area|)))) - 1.0) - *object-delivering-poses-varied-kitchen* - *object-delivering-poses*)))))))) - - (exe:perform - (desig:an action - (type transporting) - (object (desig:an object (type ?bullet-type))) - (location (desig:a location - (on (desig:an object - (type counter-top) - (urdf-name sink-area-surface) - (part-of kitchen))) - (side front))) - (target (desig:a location (poses ?delivering-poses))))))) - - (experiment-log-finish-object-transport-successful type)) - - (experiment-log-current-demo-run-failures *experiment-log-current-object*)) - - (experiment-log-finish-demo-run) - - (park-robot) - - (finalize) - - cpl:*current-path*) + (unwind-protect + (dolist (type list-of-objects) + + (experiment-log-start-object-transport type) + + (cpl:with-failure-handling + ((common-fail:high-level-failure (e) + (declare (ignore e)) + (experiment-log-finish-object-transport-failed type) + (return))) + + (let* ((?delivering-poses + (list (cl-transforms-stamped:pose->pose-stamped + cram-tf:*fixed-frame* 0.0 + (cram-tf:list->pose + (cdr + (assoc type + (if (> (cl-transforms:y + (cl-transforms:origin + (btr:pose + (btr:rigid-body + (btr:get-environment-object) + :|ENVIRONMENT.sink_area|)))) + 1.0) + *object-delivering-poses-varied-kitchen* + *object-delivering-poses*))))))) + + (?bullet-type + (object-type-filter-bullet type))) + + (if *kvr-enabled* + + (let* ((?search-poses + (alexandria:shuffle + (cut:force-ll (look-poses-ll-for-searching type)))) + (?arms + (alexandria:shuffle + ;; (cut:force-ll (arms-for-fetching-ll type)) + '(:left :right))) + (?grasps + (alexandria:shuffle + (ecase ?bullet-type + (:bowl '(:top)) + (:cup '(::RIGHT-SIDE :FRONT :LEFT-SIDE :TOP :BACK)) + (:spoon '(:top)))))) + ;; (cut:force-ll (object-grasped-faces-ll-from-kvr-type type)) + + (exe:perform + (desig:an action + (type transporting) + (object (desig:an object (type ?bullet-type))) + (target (desig:a location (poses ?delivering-poses))) + + (location (desig:a location (poses ?search-poses))) + (arms ?arms) + (grasps ?grasps)))) + + (exe:perform + (desig:an action + (type transporting) + (object (desig:an object (type ?bullet-type))) + (target (desig:a location (poses ?delivering-poses))) + + (location (desig:a location + (on (desig:an object + (type counter-top) + (urdf-name sink-area-surface) + (part-of iai-kitchen))) + (side front))))))) + + (experiment-log-finish-object-transport-successful type)) + + (experiment-log-current-demo-run-failures *experiment-log-current-object*)) + + (experiment-log-finish-demo-run) + + (park-robot) + + (finalize) + + cpl:*current-path*)) diff --git a/cram_knowrob/cram_knowrob_vr/src/grasping.lisp b/cram_knowrob/cram_knowrob_vr/src/grasping.lisp index 8d2e3df5e5..6a80b95a2a 100644 --- a/cram_knowrob/cram_knowrob_vr/src/grasping.lisp +++ b/cram_knowrob/cram_knowrob_vr/src/grasping.lisp @@ -71,39 +71,35 @@ RETURNS: a cl-transform." transform))) transform-stamped)) -(defmethod get-object-type-to-gripper-pregrasp-transform (object-type +(defmethod get-object-type-to-gripper-pregrasp-transforms (object-type object-name arm - (grasp (eql :human-grasp)) + (grasp (eql :human-grasp)) + location grasp-transform) - (cram-tf:translate-transform-stamped - grasp-transform - :x-offset (- objects::*cereal-pregrasp-xy-offset*) - :z-offset objects::*lift-z-offset*)) + (list + (cram-tf:translate-transform-stamped + grasp-transform + :x-offset (- objects::*cereal-pregrasp-xy-offset*) + :z-offset objects::*lift-z-offset*) + (cram-tf:translate-transform-stamped + grasp-transform + :x-offset (- objects::*cereal-pregrasp-xy-offset*)))) -(defmethod get-object-type-to-gripper-2nd-pregrasp-transform (object-type - object-name - arm - (grasp (eql :human-grasp)) - grasp-transform) - (cram-tf:translate-transform-stamped - grasp-transform - :x-offset (- objects::*cereal-pregrasp-xy-offset*))) - -(defmethod get-object-type-to-gripper-lift-transform (object-type - object-name - arm - (grasp (eql :human-grasp)) - grasp-transform) - (cram-tf:translate-transform-stamped - grasp-transform - :z-offset objects::*lift-z-offset*)) - -(defmethod get-object-type-to-gripper-2nd-lift-transform (object-type - object-name - arm - (grasp (eql :human-grasp)) - grasp-transform) - (cram-tf:translate-transform-stamped - grasp-transform - :x-offset 0.0)) +(defmethod get-object-type-wrt-base-frame-lift-transforms (object-type + arm + (grasp (eql :human-grasp)) + location) + (list + (cl-transforms-stamped:make-transform-stamped + cram-tf:*robot-base-frame* + cram-tf:*robot-base-frame* + 0.0 + (cl-transforms:make-3d-vector 0.0 0.0 objects::*lift-z-offset*) + (cl-transforms:make-identity-rotation)) + (cl-transforms-stamped:make-transform-stamped + cram-tf:*robot-base-frame* + cram-tf:*robot-base-frame* + 0.0 + (cl-transforms:make-3d-vector 0.0 0.0 objects::*lift-z-offset*) + (cl-transforms:make-identity-rotation)))) diff --git a/cram_knowrob/cram_knowrob_vr/src/init.lisp b/cram_knowrob/cram_knowrob_vr/src/init.lisp index 699cc8e9f3..ea3ad87dd8 100644 --- a/cram_knowrob/cram_knowrob_vr/src/init.lisp +++ b/cram_knowrob/cram_knowrob_vr/src/init.lisp @@ -37,13 +37,55 @@ ;;; rcg_f has the to date better grasps ;;; eval2 has best full set pick and place ;;; rcg_d different grasps + (in-package :kvr) (defvar *kvr-enabled* t) (defvar *episode-path* - "/home/cram/ros_workspace/episode_data/episodes/Own-Episodes/set-clean-table/" - "path of where the episode data is located") + (directory-namestring + (cram-physics-utils:parse-uri "package://episodes/Own-Episodes/set-clean-table/")) + "rospackage path of where the episode data is located") + +(defparameter *furniture-offsets-original-kitchen* + '(("sink_area_footprint_joint" + ((1.855d0 1.3d0 0.0d0) (0 0 1 0))) + ("oven_area_footprint_joint" + ((1.855d0 2.47d0 0.0d0) (0 0 1 0))) + ("kitchen_island_footprint_joint" + ((-1.365d0 0.59d0 0.0d0) (0 0 0 1))) + ("fridge_area_footprint_joint" + ((1.845d0 -0.73d0 0.0d0) (0 0 1 0))) + ("table_area_main_joint" + ((-2.4d0 -1.5d0 0.0d0) (0 0 1 0))))) + +(defparameter *furniture-offsets-flipped-sink-kitchen* + '(("sink_area_footprint_joint" + ((1.155d0 0.9d0 0.0d0) (0 0 0 1))) + ("oven_area_footprint_joint" + ((-0.155d0 2.97d0 0.0d0) (0 0 -0.5 0.5))) + ("kitchen_island_footprint_joint" + ((-0.60d0 -0.2d0 0.0d0) (0 0 0.5 0.5))) + ("fridge_area_footprint_joint" + ((-2.30d0 0.5d0 0.0d0) (0 0 0.5 0.5))) + ("table_area_main_joint" + ((1.6d0 -1.0d0 0.0d0) (0 0 0.5 0.5))))) + +(defparameter *furniture-offsets-realistic-kitchen-variation* + '(("sink_area_footprint_joint" + ((1.855d0 2.9d0 0.0d0) (0 0 1 0))) + ("oven_area_footprint_joint" + ((1.2d0 -1.8d0 0.0d0) (0 0 0.5 0.5))) + ("kitchen_island_footprint_joint" + ((-0.5d0 0.45d0 0.0d0) (0 0 0.5 0.5))) + ("fridge_area_footprint_joint" + ((-0.05d0 -1.78d0 0.0d0) (0 0 0.5 0.5))) + ("table_area_main_joint" + ((1.6d0 -1.0d0 0.0d0) (0 0 0.5 0.5))))) + +(defparameter *robot-starting-pose-in-realistic-kitchen-variation* + '((-1 2.0 0) (0 0 0 1))) + (defun load-multiple-episodes (&optional namedir-list) ;;make a list of all directories of episodes and load them @@ -131,18 +173,6 @@ semantic map kitchen." object-types))) objects))) -(defun init-location-costmap-parameters () - (def-fact-group costmap-metadata (costmap:costmap-size - costmap:costmap-origin - costmap:costmap-resolution - costmap:orientation-samples - costmap:orientation-sample-step) - (<- (location-costmap:costmap-size 5 5)) - (<- (location-costmap:costmap-origin -2.5 -2.5)) - (<- (location-costmap:costmap-resolution 0.04)) - (<- (location-costmap:orientation-samples 2)) - (<- (location-costmap:orientation-sample-step 0.1)))) - (defun init-full-simulation (&key namedir urdf-new-kitchen?) "Spawns all the objects which are necessary for the current scenario (Meaning: Kitchen, Robot, Muesli, Milk, Cup, Bowl, Fork and 3 Axis @@ -155,39 +185,52 @@ objects for debugging." (roslisp-utilities:startup-ros) (when urdf-new-kitchen? - (unless btr-belief:*kitchen-urdf* - (let ((kitchen-urdf-string - (roslisp:get-param btr-belief:*kitchen-parameter* nil))) - (when kitchen-urdf-string - (setf btr-belief:*kitchen-urdf* - (cl-urdf:parse-urdf kitchen-urdf-string))))) - (btr-belief:vary-kitchen-urdf)) + (let ((kitchen-urdf-string + (roslisp:get-param rob-int:*environment-description-parameter* nil))) + (when kitchen-urdf-string + (setf rob-int:*environment-urdf* + (cl-urdf:parse-urdf kitchen-urdf-string)))) + (btr-belief:vary-kitchen-urdf *furniture-offsets-realistic-kitchen-variation*)) (coe:clear-belief) (when urdf-new-kitchen? - (setf (btr:pose (btr:object btr:*current-bullet-world* (btr:get-robot-name))) - (cram-tf:list->pose '((-1 1.5 0) (0 0 0 1))))) + (setf (btr:pose (btr:object btr:*current-bullet-world* (rob-int:get-robot-name))) + (cram-tf:list->pose *robot-starting-pose-in-realistic-kitchen-variation*))) (cram-bullet-reasoning:clear-costmap-vis-object) (spawn-urdf-items) - (init-episode (or namedir - ;; (loop for i from 1 to 18 collecting (format nil "ep~a" i)) - '( - "original1" "original2" "original3" "original4" "original5" - "original6" "original7" "original8" "original9" "original10" - "original11" "original12" "original13" "original14" "original15" - "original16" "original17" "original18" "original19" "original20" - "original21" "original22" "original23" "original24" "original25" - "original26" "original27" - ;; "exp1_t_1" "exp1_t_2" "exp1_t_3" "exp1_t_4" "exp1_t_5" - ;; "exp1_tc_1" "exp1_tc_2" "exp1_tc_3" "exp1_tc_4" "exp1_tc_5" - ;; "exp1_tr_1" "exp1_tr_2" "exp1_tr_3" "exp1_tr_4" "exp1_tr_5" - ))) + (init-episode + (or namedir + ;; (loop for i from 1 to 18 collecting (format nil "ep~a" i)) + '( + ;; "original1" "original2" "original3" "original4" "original5" + ;; "original6" "original7" "original8" "original9" "original10" + ;; "original11" "original12" "original13" "original14" "original15" + ;; "original16" "original17" "original18" "original19" "original20" + ;; "original21" "original22" "original23" "original24" "original25" + ;; "original26" "original27" + ;; "exp1_t_1" "exp1_t_2" "exp1_t_3" "exp1_t_4" "exp1_t_5" + ;; "exp1_tc_1" "exp1_tc_2" "exp1_tc_3" "exp1_tc_4" "exp1_tc_5" + ;; "exp1_tr_1" "exp1_tr_2" "exp1_tr_3" "exp1_tr_4" "exp1_tr_5" + "cosy1" "cosy2" "cosy3" "cosy4" "cosy5" + "cosy6" "cosy7" + "cosy8" "cosy9" "cosy10" + "diagonal1" "diagonal2" "diagonal3" "diagonal4" "diagonal5" + "diagonal6" "diagonal7" "diagonal8" "diagonal9" "diagonal10" + ;; "spacy1" "spacy2" + ;; "spacy3" "spacy4" "spacy5" + ;; "spacy6" "spacy7" "spacy8" "spacy9" "spacy10" + "flipped_sink1" "flipped_sink2" "flipped_sink3" "flipped_sink4" + "flipped_sink5" "flipped_sink6" "flipped_sink7" "flipped_sink8" + "flipped_sink9" "flipped_sink10" + ;; "l_cosy1" "l_cosy2" "l_cosy3" + ;; "l_diagonal1" "l_diagonal2" "l_diagonal3" + ;; "l_spacy1" "l_spacy2" "l_spacy3" + ))) ;; (spawn-semantic-map) ;; (spawn-semantic-items) - - (init-location-costmap-parameters)) +) diff --git a/cram_knowrob/cram_knowrob_vr/src/mapping-urdf-semantic.lisp b/cram_knowrob/cram_knowrob_vr/src/mapping-urdf-semantic.lisp index 6a41d14d1d..1f0d63fdc9 100644 --- a/cram_knowrob/cram_knowrob_vr/src/mapping-urdf-semantic.lisp +++ b/cram_knowrob/cram_knowrob_vr/src/mapping-urdf-semantic.lisp @@ -41,8 +41,8 @@ "Used in spawning semantic map and offsetting its objects") (defparameter *semantic-to-urdf* - '((|''IslandArea''| . :|KITCHEN.kitchen_island|) - (|''SinkArea''| . :|KITCHEN.sink_area|)) + '((|''IslandArea''| . :|ENVIRONMENT.kitchen_island|) + (|''SinkArea''| . :|ENVIRONMENT.sink_area|)) "semantic map . urdf") (defun match-kitchens (name) @@ -50,7 +50,7 @@ (defun get-all-objects-urdf () (btr:rigid-body-names - (btr:object btr:*current-bullet-world* :kitchen))) + (btr:get-environment-object))) (defun get-all-objects-semantic () (btr:rigid-body-names diff --git a/cram_knowrob/cram_knowrob_vr/src/move-utils.lisp b/cram_knowrob/cram_knowrob_vr/src/move-utils.lisp index a92c5d93f2..863f387848 100644 --- a/cram_knowrob/cram_knowrob_vr/src/move-utils.lisp +++ b/cram_knowrob/cram_knowrob_vr/src/move-utils.lisp @@ -80,7 +80,7 @@ the episode. . " (move-object (cl-transforms:pose->transform (cram-tf:translate-pose (car (umap-P-uobj-through-surface-ll object "Start")) - :x-offset -0.1)) + :x -0.1)) (object-type-filter-bullet object))) (defun move-urdf-objects-to-start-pose () diff --git a/cram_knowrob/cram_knowrob_vr/src/query-based-calculations.lisp b/cram_knowrob/cram_knowrob_vr/src/query-based-calculations.lisp index f19cb0dac6..df263d8085 100644 --- a/cram_knowrob/cram_knowrob_vr/src/query-based-calculations.lisp +++ b/cram_knowrob/cram_knowrob_vr/src/query-based-calculations.lisp @@ -227,20 +227,20 @@ Formula: umap-T-uobj = umap-T-usurface * ssurface-T-obj (lambda (surface-name-dim-transform-and-object-transform) (let* ((surface-name (first surface-name-dim-transform-and-object-transform)) - (surface-dimensions - (second surface-name-dim-transform-and-object-transform)) + ;; (surface-dimensions + ;; (second surface-name-dim-transform-and-object-transform)) (smap-T-ssurface (third surface-name-dim-transform-and-object-transform)) (smap-T-sobject (fourth surface-name-dim-transform-and-object-transform)) - (closest-edge-and-distance - (get-closest-edge-and-distance - smap-T-sobject smap-T-ssurface surface-dimensions)) - (closest-edge - (first closest-edge-and-distance)) - (closest-edge-distance - (second closest-edge-and-distance)) + ;; (closest-edge-and-distance + ;; (get-closest-edge-and-distance + ;; smap-T-sobject smap-T-ssurface surface-dimensions)) + ;; (closest-edge + ;; (first closest-edge-and-distance)) + ;; (closest-edge-distance + ;; (second closest-edge-and-distance)) (ssurface-T-sobject (cl-transforms:transform* @@ -259,15 +259,16 @@ Formula: umap-T-uobj = umap-T-usurface * ssurface-T-obj (cl-transforms:transform* umap-T-usurface ssurface-T-sobject)) - (usurface-dimensions - (btr:calculate-bb-dims usurface-obj)) + ;; (usurface-dimensions + ;; (btr:calculate-bb-dims usurface-obj)) - (uclosest-edge-and-distance - (get-closest-edge-and-distance - umap-T-uobj umap-T-usurface usurface-dimensions))) + ;; (uclosest-edge-and-distance + ;; (get-closest-edge-and-distance + ;; umap-T-uobj umap-T-usurface usurface-dimensions)) + ) - (print closest-edge-and-distance) - (print uclosest-edge-and-distance) + ;; (print closest-edge-and-distance) + ;; (print uclosest-edge-and-distance) (cl-transforms-stamped:make-pose-stamped cram-tf:*fixed-frame* 0.0 diff --git a/cram_knowrob/cram_semantic_map_costmap/cram-semantic-map-costmap.asd b/cram_knowrob/cram_semantic_map_costmap/cram-semantic-map-costmap.asd index 64b4ad337f..87874b9e9a 100644 --- a/cram_knowrob/cram_semantic_map_costmap/cram-semantic-map-costmap.asd +++ b/cram_knowrob/cram_semantic_map_costmap/cram-semantic-map-costmap.asd @@ -1,20 +1,20 @@ ;;; ;;; Copyright (c) 2010, Lorenz Moesenlechner ;;; All rights reserved. -;;; +;;; ;;; Redistribution and use in source and binary forms, with or without ;;; modification, are permitted provided that the following conditions are met: -;;; +;;; ;;; * Redistributions of source code must retain the above copyright ;;; notice, this list of conditions and the following disclaimer. ;;; * Redistributions in binary form must reproduce the above copyright ;;; notice, this list of conditions and the following disclaimer in the ;;; documentation and/or other materials provided with the distribution. ;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software ;;; without specific prior written permission. -;;; +;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" ;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE ;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE @@ -31,7 +31,7 @@ (defsystem cram-semantic-map-costmap :author "Lorenz Moesenlechner" :license "BSD" - + :depends-on (cram-prolog cram-projection cl-transforms diff --git a/cram_knowrob/cram_semantic_map_costmap/src/facts.lisp b/cram_knowrob/cram_semantic_map_costmap/src/facts.lisp index 8ea3fffd94..f9b26ba429 100644 --- a/cram_knowrob/cram_semantic_map_costmap/src/facts.lisp +++ b/cram_knowrob/cram_semantic_map_costmap/src/facts.lisp @@ -92,18 +92,19 @@ ?cm)) (<- (desig-costmap ?desig ?cm) - (or (cram-robot-interfaces:visibility-designator ?desig) - (cram-robot-interfaces:reachability-designator ?desig)) - (costmap ?cm) + (or (rob-int:visibility-designator ?desig) + (rob-int:reachability-designator ?desig)) + (costmap:costmap ?cm) (semantic-map-objects ?objects) - (costmap-padding ?padding) - (costmap-add-function semantic-map-free-space - (make-semantic-map-costmap - ?objects :invert t :padding ?padding) - ?cm) + (rob-int:robot ?robot-name) + (costmap:costmap-padding ?robot-name ?padding) + (costmap:costmap-add-function semantic-map-free-space + (make-semantic-map-costmap + ?objects :invert t :padding ?padding) + ?cm) ;; Locations to see and to reach are on the floor, so we can use a ;; constant height of 0 - (costmap-add-cached-height-generator + (costmap:costmap-add-cached-height-generator (make-constant-height-function 0.0) ?cm)) diff --git a/cram_learning/cram_sim_log_generator/CMakeLists.txt b/cram_learning/cram_sim_log_generator/CMakeLists.txt index aa1feb9618..cbcd892121 100644 --- a/cram_learning/cram_sim_log_generator/CMakeLists.txt +++ b/cram_learning/cram_sim_log_generator/CMakeLists.txt @@ -197,4 +197,4 @@ include_directories( ## Add folders to be run by python nosetests # catkin_add_nosetests(test) -add_lisp_executable(cram-sim-log-generator cram-sim-log-generator cram-sim-log-generator::generate-neem) +add_lisp_executable(cram-sim-log-generator cram-sim-log-generator cram-sim-log-generator::main) diff --git a/cram_learning/cram_sim_log_generator/launch/neem-generation.launch b/cram_learning/cram_sim_log_generator/launch/neem-generation.launch index 924a70bed1..5a4e1e1021 100644 --- a/cram_learning/cram_sim_log_generator/launch/neem-generation.launch +++ b/cram_learning/cram_sim_log_generator/launch/neem-generation.launch @@ -1,7 +1,11 @@ - + + + + + diff --git a/cram_learning/cram_sim_log_generator/scripts/lol_launcher.py b/cram_learning/cram_sim_log_generator/scripts/lol_launcher.py new file mode 100644 index 0000000000..16d0518068 --- /dev/null +++ b/cram_learning/cram_sim_log_generator/scripts/lol_launcher.py @@ -0,0 +1,26 @@ +import subprocess +import rosnode +import time + +bashCommand = 'roslaunch json_prolog json_prolog_single.launch' +killCommand = 'pkill -f json_prolog' + +isStarted = False + +print "Killing JSON Prolog ...." +killProcess = subprocess.Popen(killCommand.split(), stdout=subprocess.PIPE) +time.sleep(5) +print 'Start json prolog ...' +subprocess.Popen(bashCommand.split(), stdout=subprocess.PIPE) + +while not isStarted: + isStarted = rosnode.rosnode_ping('/json_prolog', 1) + +time.sleep(5) +print 'Started' +#output, error = process.communicate() +#print output + + + + diff --git a/cram_learning/cram_sim_log_generator/scripts/neem_generation.py b/cram_learning/cram_sim_log_generator/scripts/neem_generation.py new file mode 100644 index 0000000000..6eab878ac6 --- /dev/null +++ b/cram_learning/cram_sim_log_generator/scripts/neem_generation.py @@ -0,0 +1,39 @@ +import subprocess +import rosnode +import time +import select +import threading + +killCommand = 'roslaunch cram_sim_log_generator neem-generation.launch' +#killCommand = 'python blocker.py' + + + +def start_neem_process(): + killProcess = subprocess.Popen(killCommand.split(),bufsize=1, stdout=subprocess.PIPE, universal_newlines=True) + nice = threading.Timer(360, killProcess.terminate) + nice.start() + + for line in iter(killProcess.stdout.readline,''): + nice.cancel() + print line.rstrip() + nice = threading.Timer(360, killProcess.terminate) + nice.start() + + +while True: + try: + print "start neem process" + start_neem_process() + except: + print "Error occurred" + + +print "Finished" + +#output, error = process.communicate() +#print output + + + + diff --git a/cram_learning/cram_sim_log_generator/src/main.lisp b/cram_learning/cram_sim_log_generator/src/main.lisp index 4b13ad535f..e40e11d8e3 100644 --- a/cram_learning/cram_sim_log_generator/src/main.lisp +++ b/cram_learning/cram_sim_log_generator/src/main.lisp @@ -1,33 +1,48 @@ (in-package :cslg) +(defparameter *mongo-logger* nil) +(defparameter num-experiments 1) +(defparameter connection-retries 0) +(defparameter *start-time* 0) +(defparameter *global-timer* 0) -(defun main (num-experiments) - (setf cram-bullet-reasoning-belief-state:*spawn-debug-window* nil) - (setf cram-tf:*tf-broadcasting-enabled* t) - (roslisp-utilities:startup-ros :name "cram" :anonymous nil) +(defun prepare-logging () + (setf connection-retries 0) + (print "Cleaning old ros nodes ...") + ;;(asdf-utils:run-program (concatenate 'string "echo 'y' | rosnode cleanup")) + (print "Cleaning old ros nodes done") + (print "Waiting for JSON Prolog to start ...") + ;;(asdf-utils:run-program (concatenate 'string "python ~/Desktop/lol_launcher.py")) + (print "JSON Prolog started") + (setf ccl::*is-client-connected* nil) (setf ccl::*is-logging-enabled* t) (setf ccl::*host* "'https://localhost'") (setf ccl::*cert-path* "'/home/koralewski/Desktop/localhost.pem'") - (setf ccl::*api-key* "'K103jdr40Rp8UX4egmRf42VbdB1b5PW7qYOOVvTDAoiNG6lcQoaDHONf5KaFcefs'") - (ccl::connect-to-cloud-logger) + ;;(setf ccl::*api-key* "'K103jdr40Rp8UX4egmRf42VbdB1b5PW7qYOOVvTDAoiNG6lcQoaDHONf5KaFcefs'") + (setf ccl::*api-key* "'uWZv7X1cQkdlZkx4R4uYSIQGyCr4zgyrYEgorw7XjICK0JyLQrmitf48hMCC4pYg'") + (loop while (and (not ccl::*is-client-connected*) (< connection-retries 10)) do + (progn + (ccl::connect-to-cloud-logger) + (setf connection-retries (+ connection-retries 1)))) + (when (not ccl::*is-client-connected*) + (/ 1 0))) + + +(defun main () + (ros-load:load-system "cram_pr2_description" :cram-pr2-description) + ;;(ros-load:load-system "cram_boxy_description" :cram-boxy-description) + ;;(setf cram-bullet-reasoning-belief-state:*spawn-debug-window* nil) + (setf cram-tf:*tf-broadcasting-enabled* t) + (roslisp-utilities:startup-ros :name "cram" :anonymous nil) ;;(setq roslisp::*debug-stream* nil) - (loop for x from 1 to num-experiments - do (let ((experiment-id (format nil "~d" (truncate (* 1000000 (cram-utilities:current-timestamp)))))) - (let ((experiment-save-path - (concatenate 'string - "~/projection-experiments/" experiment-id "/"))) - (ensure-directories-exist experiment-save-path) - (setq ccl::*prolog-query-save-path* experiment-save-path) - (format t "Starting experiment ~a~%" experiment-id) - (asdf-utils:run-program (concatenate 'string "rosrun mongodb_log mongodb_log -c " experiment-id " &")) - (unwind-protect -;; (urdf-proj:with-simulated-robot (demo::demo-random nil '(:bowl :spoon))) -;; (urdf-proj:with-simulated-robot (demo::demo-random)) - ;;(demo::generate-training-data nil '(:cup)) - (urdf-proj:with-simulated-robot (demo::evaluation-there-and-back-again)) - - (ccl::export-log-to-owl (concatenate 'string experiment-id ".owl")) - (format t "Done with experiment ~a~%" experiment-id) - (asdf-utils:run-program (concatenate 'string "docker cp seba:/home/ros/user_data/" experiment-id ".owl " experiment-save-path)) - (unwind-protect (asdf-utils:run-program "killall -r 'mongodb_log'")) - (unwind-protect (asdf-utils:run-program "killall -r 'mongod'")) - (ccl::reset-logged-owl)))))) + (print "Init bullet world") + (setf ccl::*is-logging-enabled* t) + (ccl::init-logging) + (loop for x from 0 to (- num-experiments 1) + do (progn + (print "Start") + (ccl::start-episode) + ;;(urdf-proj:with-simulated-robot (demo::demo-random nil )) + (urdf-proj:with-simulated-robot (demo::setting-demo)) + (ccl::stop-episode) + (print "End"))) + (ccl::finish-logging)) diff --git a/cram_pr2/.gitignore b/cram_pr2/.gitignore deleted file mode 100644 index 485790d6db..0000000000 --- a/cram_pr2/.gitignore +++ /dev/null @@ -1,5 +0,0 @@ -*.fasl -build/ -bin/ -*~ -*#* diff --git a/cram_pr2/cram_pr2_arm_kinematics/launch/arm_kinematics.launch b/cram_pr2/cram_pr2_arm_kinematics/launch/arm_kinematics.launch deleted file mode 100644 index 98ed468205..0000000000 --- a/cram_pr2/cram_pr2_arm_kinematics/launch/arm_kinematics.launch +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/cram_pr2/cram_pr2_arm_kinematics/src/fk.lisp b/cram_pr2/cram_pr2_arm_kinematics/src/fk.lisp deleted file mode 100644 index cca6b82c59..0000000000 --- a/cram_pr2/cram_pr2_arm_kinematics/src/fk.lisp +++ /dev/null @@ -1,93 +0,0 @@ -;;; -;;; Copyright (c) 2016, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Institute for Artificial Intelligence/ -;;; Universitaet Bremen nor the names of its contributors may be used to -;;; endorse or promote products derived from this software without -;;; specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :pr2-ik-fk) - -(defparameter *fk-service-names* '(:moveit "moveit/compute_fk" - :left "pr2_left_arm_kinematics/get_fk" - :right "pr2_right_arm_kinematics/get_fk")) - -(defvar *fk-solver-infos* '(:left nil :right nil) - "fk solver infos for the left and right arm fk solvers") - -(defparameter *fk-info-service-names* '(:left "pr2_left_arm_kinematics/get_fk_solver_info" - :right "pr2_right_arm_kinematics/get_fk_solver_info")) - -(defun get-fk-solver-info (left-or-right) - (or (getf *fk-solver-infos* left-or-right) - (setf (getf *fk-solver-infos* left-or-right) - (roslisp:with-fields (kinematic_solver_info) - (roslisp:call-service - (getf *fk-info-service-names* left-or-right) - 'moveit_msgs-srv:getkinematicsolverinfo) - kinematic_solver_info)))) - -(defun get-fk-solver-joints (left-or-right) - (roslisp:with-fields (joint_names) - (get-fk-solver-info left-or-right) - joint_names)) - -(defun get-fk-links (left-or-right) - (ecase left-or-right - (:left (vector "l_wrist_roll_link" "l_elbow_flex_link")) - (:right (vector "r_wrist_roll_link" "r_elbow_flex_link")))) - -(defun call-fk-service (left-or-right link-names-vector - &optional (fk-base-frame "torso_lift_link")) - (declare (type keyword left-or-right)) - (handler-case - (roslisp:with-fields ((response-error-code (val error_code)) - pose_stamped fk_link_names) - (progn - (roslisp:wait-for-service (getf *fk-info-service-names* left-or-right) 10.0) - (roslisp:call-service - (getf *fk-service-names* left-or-right) - "moveit_msgs/GetPositionFK" - (roslisp:make-request - "moveit_msgs/GetPositionFK" - (:frame_id :header) fk-base-frame - :fk_link_names (or link-names-vector (get-fk-links left-or-right)) - (:joint_state :robot_state) (make-zero-seed-state left-or-right)))) - (cond ((eql response-error-code - (roslisp-msg-protocol:symbol-code - 'moveit_msgs-msg:moveiterrorcodes - :success)) - (map 'list - (lambda (name pose-stamped-msg) - (list name (cl-transforms-stamped:from-msg pose-stamped-msg))) - fk_link_names - pose_stamped)) - (t (error 'simple-error - :format-control "FK service failed: ~a" - :format-arguments (list - (roslisp-msg-protocol:code-symbol - 'moveit_msgs-msg:moveiterrorcodes - response-error-code)))))) - (simple-error (e) - (format t "~a~%FK service call freaked out. Hmmm...~%" e)))) diff --git a/cram_pr2/cram_pr2_arm_kinematics/src/ik.lisp b/cram_pr2/cram_pr2_arm_kinematics/src/ik.lisp deleted file mode 100644 index 7b0b68b28a..0000000000 --- a/cram_pr2/cram_pr2_arm_kinematics/src/ik.lisp +++ /dev/null @@ -1,305 +0,0 @@ -;;; -;;; Copyright (c) 2016, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Institute for Artificial Intelligence/ -;;; Universitaet Bremen nor the names of its contributors may be used to -;;; endorse or promote products derived from this software without -;;; specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :pr2-ik-fk) - -(defparameter *use-arm-kinematics-interface* nil - "The default interface is moveit interface with one compute_ik for both arms. -When `*use-arm-kinematics-interface*' is set, use separate services for each arm.") - - -(defparameter *ik-service-names* '(:moveit "moveit/compute_ik" - :left "pr2_left_arm_kinematics/get_ik" - :right "pr2_right_arm_kinematics/get_ik")) - -(defvar *ik-persistent-services* '(:moveit nil :left nil :right nil) - "a persistent service for ik requests") - -(defun init-ik-persistent-service (moveit-or-left-or-right) - (declare (type keyword moveit-or-left-or-right)) - "Initializes one of the corresponding *ik-persistent-services*" - (let ((service-name (getf *ik-service-names* moveit-or-left-or-right))) - (loop until (roslisp:wait-for-service service-name 5) - do (roslisp:ros-info (ik-service) "Waiting for ~a." service-name)) - (prog1 (setf (getf *ik-persistent-services* moveit-or-left-or-right) - (make-instance 'roslisp:persistent-service - :service-name service-name - :service-type 'moveit_msgs-srv:getpositionik)) - (roslisp:ros-info (ik-service) "~a client created." service-name)))) - -(defun get-ik-persistent-service (moveit-or-left-or-right) - (declare (type keyword moveit-or-left-or-right)) - (let ((service (getf *ik-persistent-services* moveit-or-left-or-right))) - (if (and service (roslisp:persistent-service-ok service)) - service - (init-ik-persistent-service moveit-or-left-or-right)))) - -(defun destroy-ik-persistent-services () - (mapcar (lambda (moveit-or-left-or-right) - (let ((service (getf *ik-persistent-services* moveit-or-left-or-right))) - (when service (roslisp:close-persistent-service service))) - (setf (getf *ik-persistent-services* moveit-or-left-or-right) nil)) - '(:moveit :left :right))) - -(roslisp-utilities:register-ros-cleanup-function destroy-ik-persistent-services) - - -(defun get-pr2-arm-joints-list (arm) - (cut:var-value '?joints - (car (prolog:prolog `(cram-robot-interfaces:arm-joints - cram-pr2-description:pr2 ,arm ?joints))))) - -(defun get-pr2-ee-link (arm) - (cut:var-value '?link - (car (prolog:prolog `(cram-robot-interfaces:end-effector-link - cram-pr2-description:pr2 ,arm ?link))))) - -(defun get-pr2-planning-group (arm) - (cut:var-value '?group - (car (prolog:prolog `(cram-robot-interfaces:planning-group - cram-pr2-description:pr2 ,arm ?group))))) - - -(defun make-zero-seed-state (left-or-right) - (let* ((joint-names (map 'vector #'identity (get-pr2-arm-joints-list left-or-right))) - (zero-vector (apply #'vector (make-list - (length joint-names) - :initial-element 0.0)))) - (roslisp:make-message - "sensor_msgs/JointState" - name joint-names - position zero-vector - velocity zero-vector - effort zero-vector))) - -;; (defun make-bullet-current-seed-state (left-or-right) -;; (let* ((joint-names-vector (get-ik-solver-joints left-or-right)) -;; (joint-names (map 'list #'identity joint-names-vector)) -;; (joint-states (map 'vector #'joint-state-position (joint-states joint-names))) -;; (zero-vector (apply #'vector (make-list -;; (length joint-names) -;; :initial-element 0.0)))) -;; (roslisp:make-message -;; "sensor_msgs/JointState" -;; name joint-names-vector -;; position joint-states -;; velocity zero-vector -;; effort zero-vector))) - - -;; (defun make-bullet-seed-states (robot-OBJECT robot-urdf joint-names &optional (steps 3)) -;; "Returns a sequence of possible seed states. The first seed state is -;; the current state represented by `robot' the other states are -;; generated by dividing the interval between the lower and the upper -;; limit of the joint into 1 + `steps' segments and using the corresponding -;; joint positions as seeds. `joint-names' is a list of strings" -;; (declare (type robot-object robot-OBJECT) (type urdf robot-urdf)) -;; (flet ((init-limits (urdf lower upper joint-name) -;; (let* ((joint (or (gethash joint-name (cl-urdf:joints urdf)) -;; (error 'simple-error -;; :format-control "Unknown joint `~a'" -;; :format-arguments (list joint-name)))) -;; (joint-limits (and (slot-boundp joint 'cl-urdf:limits) -;; (cl-urdf:limits joint)))) -;; (case (cl-urdf:joint-type joint) -;; ((:revolute :prismatic) -;; (setf (gethash joint-name lower) -;; (cl-urdf:lower joint-limits)) -;; (setf (gethash joint-name upper) -;; (cl-urdf:upper joint-limits))) -;; (:continuous -;; (setf (gethash joint-name lower) -;; (cl-urdf:lower joint-limits)) -;; (setf (gethash joint-name upper) -;; (* pi 2))) -;; (t (setf (gethash joint-name lower) 0.0) -;; (setf (gethash joint-name upper) 0.0)))))) -;; (let ((lower-limits (make-hash-table :test 'equal)) -;; (upper-limits (make-hash-table :test 'equal)) -;; (joint-names (map 'vector #'identity joint-names))) -;; (map 'nil (curry #'init-limits robot-urdf lower-limits upper-limits) joint-names) -;; (cons -;; (btr:make-robot-joint-state-msg robot-OBJECT :joint-names joint-names) -;; (cut:lazy-mapcar (lambda (joint-states) -;; (roslisp:make-msg -;; "sensor_msgs/JointState" -;; (stamp header) 0 -;; name joint-names -;; position (reverse -;; (map 'vector #'identity joint-states)) -;; velocity (make-array (length joint-names) -;; :element-type 'float -;; :initial-element 0.0) -;; effort (make-array (length joint-names) -;; :element-type 'float -;; :initial-element 0.0))) -;; (apply #'lazy-cross-product -;; (reverse -;; (loop for name across joint-names collecting -;; (loop for i from 0 below steps collecting -;; (+ (gethash name lower-limits) -;; (* i (/ (- (gethash name upper-limits) -;; (gethash name lower-limits)) -;; (- steps 1))))))))))))) - -(defun get-ee-pose-from-tcp-pose (tcp-pose - &optional (tcp-in-ee-pose (cl-transforms:make-identity-pose))) - (declare (type cl-transforms-stamped:pose-stamped tcp-pose) - (type cl-transforms:pose tcp-in-ee-pose)) - (let ((goal-trans (cl-transforms:transform* - (cl-transforms:reference-transform tcp-pose) - (cl-transforms:transform-inv - (cl-transforms:reference-transform tcp-in-ee-pose))))) - (cl-transforms-stamped:make-pose-stamped - (cl-transforms-stamped:frame-id tcp-pose) - (cl-transforms-stamped:stamp tcp-pose) - (cl-transforms:translation goal-trans) - (cl-transforms:rotation goal-trans)))) - - -(defun call-kinematics-ik-service (cartesian-pose - &key left-or-right seed-state - (ik-base-frame cram-tf:*robot-torso-frame*) - (tcp-in-ee-pose (cl-transforms:make-identity-pose))) - (declare (type keyword left-or-right) - (type cl-transforms-stamped:pose-stamped cartesian-pose)) - (let ((ik-link (get-pr2-ee-link left-or-right))) - (handler-case - (roslisp:with-fields ((error-code (val error_code)) - (joint-state (joint_state solution))) - (roslisp:call-persistent-service - (get-ik-persistent-service left-or-right) - (roslisp:make-request - "moveit_msgs/GetPositionIK" - (:ik_link_name :ik_request) ik-link - (:pose_stamped :ik_request) (cl-transforms-stamped:to-msg - (get-ee-pose-from-tcp-pose - (cl-transforms-stamped:transform-pose-stamped - cram-tf:*transformer* - :pose (cl-transforms-stamped:copy-pose-stamped - cartesian-pose :stamp 0.0) - :target-frame ik-base-frame - :timeout cram-tf:*tf-default-timeout*) - tcp-in-ee-pose)) - (:joint_state :robot_state :ik_request) (or seed-state - (make-zero-seed-state left-or-right)) - (:timeout :ik_request) 1.0)) - (if (eql error-code - (roslisp-msg-protocol:symbol-code - 'moveit_msgs-msg:moveiterrorcodes - :success)) - joint-state - (and (roslisp:ros-warn (call-kinematics-ik-service) - "IK service failed: ~a" - (roslisp-msg-protocol:code-symbol - 'moveit_msgs-msg:moveiterrorcodes - error-code)) - nil))) - (roslisp:service-call-error () - (roslisp:ros-warn (call-kinematics-ik-service) "No IK solution found.") - nil)))) - - -(defun strip-joint-state (joint-state-msg left-or-right) - "From the joint state message of a full robot extracts only the arm joints. -Uses SIDE EFFECTS!" - (flet ((take-indexed-elems-from-list-into-vector (the-list indices) - (map 'vector #'(lambda (a-position) (elt the-list a-position)) indices))) - - (let* ((joints (slot-value joint-state-msg 'sensor_msgs-msg:name)) - (indices (mapcar #'(lambda (item) (position item joints :test #'equal)) - (get-pr2-arm-joints-list left-or-right)))) - (roslisp:with-fields (header name position) - joint-state-msg - (roslisp:make-message - "sensor_msgs/JointState" - :header header - :name (take-indexed-elems-from-list-into-vector name indices) - :position (take-indexed-elems-from-list-into-vector position indices)))))) - -(defun call-moveit-ik-service (cartesian-pose - &key left-or-right - (ik-base-frame cram-tf:*robot-torso-frame*) - (tcp-in-ee-pose (cl-transforms:make-identity-pose))) - (declare (type cl-transforms-stamped:pose-stamped cartesian-pose) - (type keyword left-or-right)) - (let* ((pose (cl-transforms-stamped:transform-pose-stamped - cram-tf:*transformer* - :pose (cl-transforms-stamped:copy-pose-stamped - cartesian-pose :stamp 0.0) - :target-frame ik-base-frame - :timeout cram-tf:*tf-default-timeout*))) - (roslisp:with-fields ((solution (joint_state solution)) - (error-code (val error_code))) - (roslisp:call-persistent-service - (get-ik-persistent-service :moveit) - :ik_request - (roslisp:make-msg - "moveit_msgs/PositionIKRequest" - ;; we assume that the last joint in JOINT-NAMES is the end - ;; of the chain which is what we want for ik_link_name. - ;; :ik_link_name (elt link-names 0) <- moveit per default takes - ;; the last link in the chain - :pose_stamped (cl-transforms-stamped:to-msg - (get-ee-pose-from-tcp-pose pose tcp-in-ee-pose)) - ;; something is wrong with the seed state atm, so this will stay - ;; disabled for now - ;; :robot_state (roslisp:make-msg - ;; "moveit_msgs/RobotState" - ;; :joint_state (or seed-state - ;; (btr:make-robot-joint-state-msg robot))) - :group_name (get-pr2-planning-group left-or-right) - :timeout 1.0)) - (if (eql error-code (roslisp-msg-protocol:symbol-code - 'moveit_msgs-msg:moveiterrorcodes - :success)) - (strip-joint-state solution left-or-right) - (progn (roslisp:ros-warn (compute-iks) "IK moveit solver failed.") - nil))))) - -(defmethod cram-robot-interfaces:compute-iks (pose-stamped - &key link-name arm robot-state seed-state - (pose-stamped-frame - cram-tf:*robot-torso-frame*) - (tcp-in-ee-pose - (cl-transforms:make-identity-pose))) - (declare (ignore link-name robot-state)) - (let ((solution - (if *use-arm-kinematics-interface* - (call-kinematics-ik-service pose-stamped - :left-or-right arm - :seed-state seed-state - :ik-base-frame pose-stamped-frame - :tcp-in-ee-pose tcp-in-ee-pose) - (call-moveit-ik-service pose-stamped - :left-or-right arm - :ik-base-frame pose-stamped-frame - :tcp-in-ee-pose tcp-in-ee-pose)))) - (when solution - (list solution)))) diff --git a/cram_pr2/cram_pr2_cloud/cram-pr2-cloud.asd b/cram_pr2/cram_pr2_cloud/cram-pr2-cloud.asd deleted file mode 100644 index 6e4fe4d9ea..0000000000 --- a/cram_pr2/cram_pr2_cloud/cram-pr2-cloud.asd +++ /dev/null @@ -1,97 +0,0 @@ -;;; Copyright (c) 2017, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software -;;; without specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(defsystem cram-pr2-cloud - :author "Gayane Kazhoyan" - :maintainer "Gayane Kazhoyan" - :license "BSD" - - :depends-on (cl-transforms - cl-transforms-stamped - cl-tf2 - cram-tf - - cram-language - cram-prolog - cram-designators - cram-process-modules - cram-math - cram-occasions-events - cram-executive - cram-utilities ; for cut:var-value of prolog stuff - - cram-plan-occasions-events - ;; cram-bullet-reasoning-belief-state ; for event handling ; using own stuff for now - - giskard_msgs-msg - giskard_msgs-srv - - cram-common-failures - cram-robot-interfaces - cram-pr2-low-level - cram-pr2-process-modules - cram-mobile-pick-place-plans - - cram-knowrob-cloud - - cram-urdf-projection - cram-pr2-description - cram-bullet-reasoning-belief-state - cram-bullet-reasoning-utilities - - cram-location-costmap - cram-semantic-map-costmap - cram-robot-pose-gaussian-costmap - ;; pr2-reachability-costmap - ) - - :components - ((:module "src" - :components - ((:file "package") - (:file "tf-utilities" :depends-on ("package")) - (:file "geometry-calculations" :depends-on ("package" "tf-utilities")) - (:file "cloud-data" :depends-on ("package" "tf-utilities" "geometry-calculations")) - (:file "local-data" :depends-on ("package" - "tf-utilities" - "geometry-calculations" - "cloud-data")) - (:file "costmaps" :depends-on ("package" "local-data" "tf-utilities")) - (:file "projection-plans" :depends-on ("package")) - (:file "real-world-plans" :depends-on ("package" - "tf-utilities" - "local-data" - "projection-plans" - "costmaps")))))) - -;; tf-utilities -;; geometry-calculations -;; cloud-data -;; local-data -;; projection-plans -;; real-world-plans diff --git a/cram_pr2/cram_pr2_cloud/package.xml b/cram_pr2/cram_pr2_cloud/package.xml deleted file mode 100644 index 5d9fdaf25f..0000000000 --- a/cram_pr2/cram_pr2_cloud/package.xml +++ /dev/null @@ -1,41 +0,0 @@ - - cram_pr2_cloud - 0.7.0 - - cram_pr2_plans - - Gayane Kazhoyan - Gayane Kazhoyan - BSD - - catkin - - cl_transforms - cl_transforms_stamped - cl_tf2 - cram_tf - cram_language - cram_prolog - cram_designators - cram_process_modules - cram_math - cram_occasions_events - cram_executive - cram_utilities - cram_plan_occasions_events - giskard_msgs - cram_common_failures - cram_robot_interfaces - cram_pr2_low_level - cram_pr2_process_modules - cram_mobile_pick_place_plans - cram_knowrob_cloud - cram_urdf_projection - cram_pr2_description - cram_bullet_reasoning_belief_state - cram_bullet_reasoning_utilities - cram_location_costmap - cram_semantic_map_costmap - cram_robot_pose_gaussian_costmap - - diff --git a/cram_pr2/cram_pr2_cloud/src/cloud-data.lisp b/cram_pr2/cram_pr2_cloud/src/cloud-data.lisp deleted file mode 100644 index 043685acb9..0000000000 --- a/cram_pr2/cram_pr2_cloud/src/cloud-data.lisp +++ /dev/null @@ -1,106 +0,0 @@ -;;; -;;; Copyright (c) 2017, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Institute for Artificial Intelligence/ -;;; Universitaet Bremen nor the names of its contributors may be used to -;;; endorse or promote products derived from this software without -;;; specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :pr2-cloud) - -(defvar *cloud-handle-transform* nil) -(defvar *cloud-joint-transform* nil) - -(defun init-connection () - (kr-cloud::initialize-iai-cloud-connection) - (cpl:sleep 5)) - -(defun load-trajectory-episode () - (kr-cloud:load-episodes '(11) :old-db-or-new :new)) - -(defun load-gaussian-episodes () - (kr-cloud:load-episodes '(1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 - 20 21 22 23 24 25 26 27) - :old-db-or-new :old)) - -(defun cloud-handle-transform () - (or *cloud-handle-transform* - (multiple-value-bind (handle joint) - (robust-cloud-handle-and-joint-transform) - (setf *cloud-joint-transform* joint) - (setf *cloud-handle-transform* handle)))) - -(defun cloud-joint-transform () - (or *cloud-joint-transform* - (multiple-value-bind (handle joint) - (robust-cloud-handle-and-joint-transform) - (setf *cloud-handle-transform* handle) - (setf *cloud-joint-transform* joint)))) - -(defun robust-cloud-handle-and-joint-transform () - (calculate-robust-handle-and-joint-transform - (kr-cloud:semantic-map-object-transform "IAIFridgeDoorHandle") - (kr-cloud:semantic-map-object-transform "HingedJoint"))) - - -(defun cloud-handle-to-robot-transform (&optional (before-action "MoveFridgeHandle")) - (let ((cloud-map-to-handle (cloud-handle-transform)) - (cloud-map-to-robot (kr-cloud:robot-pose-before-action before-action))) - (apply-transform (cram-tf:transform-stamped-inv cloud-map-to-handle) - cloud-map-to-robot))) - -(defun cloud-joint-to-robot-transform (&optional (before-action "MoveFridgeHandle")) - (let ((cloud-map-to-joint (cloud-joint-transform)) - (cloud-map-to-robot (kr-cloud:robot-pose-before-action before-action))) - (apply-transform (cram-tf:transform-stamped-inv cloud-map-to-joint) - cloud-map-to-robot))) - -(defun cloud-handle-to-gripper-transforms (&optional (action "MoveFridgeHandle")) - (let ((cloud-map-to-handle (cloud-handle-transform)) - (cloud-map-to-gripper-list - (kr-cloud::gripper-trajectory-during-action :right action))) - (mapcar (lambda (cloud-map-to-gripper) - (apply-transform (cram-tf:transform-stamped-inv cloud-map-to-handle) - cloud-map-to-gripper)) - cloud-map-to-gripper-list))) - -(defun cloud-joint-to-gripper-transforms (&optional (action "MoveFridgeHandle")) - (let ((cloud-map-to-joint (cloud-joint-transform)) - (cloud-map-to-gripper-list - (kr-cloud::gripper-projected-trajectory-during-action :right action))) - (mapcar (lambda (cloud-map-to-gripper) - (apply-transform (cram-tf:transform-stamped-inv cloud-map-to-joint) - cloud-map-to-gripper)) - cloud-map-to-gripper-list))) - -(defun cloud-handle-to-robot-transform-distribution () - (let ((cloud-map-to-handle (cloud-handle-transform))) - (multiple-value-bind (cloud-map-to-robot-transform-mean covariance) - (kr-cloud::robot-pose-distribution) - (values (apply-transform - (cram-tf:transform-stamped-inv cloud-map-to-handle) - cloud-map-to-robot-transform-mean) - (apply-transform-to-covariance-matrix - (cram-tf:transform-stamped-inv cloud-map-to-handle) - covariance))))) diff --git a/cram_pr2/cram_pr2_cloud/src/costmaps.lisp b/cram_pr2/cram_pr2_cloud/src/costmaps.lisp deleted file mode 100644 index 3ebb589342..0000000000 --- a/cram_pr2/cram_pr2_cloud/src/costmaps.lisp +++ /dev/null @@ -1,99 +0,0 @@ -;;; -;;; Copyright (c) 2016, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Institute for Artificial Intelligence/ -;;; Universitaet Bremen nor the names of its contributors may be used to -;;; endorse or promote products derived from this software without -;;; specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :pr2-cloud) - -;; (defun init-stuff () -;; ;; (def-fact-group costmap-metadata () -;; ;; (<- (location-costmap:costmap-size 12 12)) -;; ;; (<- (location-costmap:costmap-origin -6 -6)) -;; ;; (<- (location-costmap:costmap-resolution 0.05)) - -;; ;; (<- (location-costmap:costmap-padding 0.2)) -;; ;; (<- (location-costmap:costmap-manipulation-padding 0.2)) -;; ;; (<- (location-costmap:costmap-in-reach-distance 0.9)) -;; ;; (<- (location-costmap:costmap-reach-minimal-distance 0.1))) - -;; (def-fact-group semantic-map-data () -;; (<- (semantic-map-object-name :kitchen))) - -;; ;; (setf pr2-reachability-costmap::*ik-reference-frame* cram-tf:*fixed-frame*) -;; ;; should be torso-frame if tf is running - -;; (sem-map:get-semantic-map) - -;; (setf prolog:*break-on-lisp-errors* t)) - -;; (roslisp-utilities:register-ros-init-function init-stuff) - -(defmethod location-costmap:costmap-generator-name->score ((name (eql 'reachability-cm))) 4) - -(defun make-mean-orientation-generator (mean-transform) - (lambda (x y previous-orientations) - (declare (ignore x y previous-orientations)) - (list (cl-transforms:rotation mean-transform)))) - -;; (defun make-first-pose-designator (trajectory) -;; (let ((?pose (strip-transform-stamped (first trajectory)))) -;; (desig:a location (pose ?pose)))) - -(def-fact-group robot-pose-cloud-reachability-costmap (location-costmap:desig-costmap) - (<- (location-costmap:desig-costmap ?designator ?cm) - (desig:desig-prop ?designator (:my-reachable-for ?robot)) - (cram-robot-interfaces:robot ?robot) - ;; (desig:desig-prop ?designator (:arm ?arm)) - (desig:desig-prop ?designator (:location ?location)) - (desig:desig-prop ?designator (:context ?context)) - (equal ?context "OpenFridge") - ;; (desig:desig-prop ?designator (:trajectory ?trajectory-in-map)) - ;; (lisp-fun make-first-pose-designator ?trajectory-in-map ?location) - ;; (desig:desig-prop ?designator (:target ?location)) - ;; (desig:current-designator ?location ?current-location-designator) - ;; (once (desig:designator-groundings ?current-location-designator ?poses) - ;; (member ?to-reach-pose ?poses)) - (location-costmap:costmap ?cm) - (location-costmap:costmap-resolution ?x) - (lisp-fun local-handle-to-robot-transform-distribution (?mean-transform ?covariance)) - (lisp-fun cl-transforms:translation ?mean-transform ?mean) - (location-costmap:costmap-add-function - reachability-cm - (location-costmap:make-gauss-cost-function ?mean ?covariance) - ?cm) - (location-costmap:costmap-add-orientation-generator - (make-mean-orientation-generator ?mean-transform) - ?cm))) - -(defun pose-to-reach-fridge () - (let ((?transform-to-reach (cram-tf:strip-transform-stamped (local-handle-transform))) - (?robot 'cram-pr2-description:pr2)) - (desig:reference (desig:a location - (my-reachable-for ?robot) - (location (desig:a location (pose ?transform-to-reach))) - (context "OpenFridge"))))) - diff --git a/cram_pr2/cram_pr2_cloud/src/geometry-calculations.lisp b/cram_pr2/cram_pr2_cloud/src/geometry-calculations.lisp deleted file mode 100644 index 9974854b9e..0000000000 --- a/cram_pr2/cram_pr2_cloud/src/geometry-calculations.lisp +++ /dev/null @@ -1,150 +0,0 @@ -;;; -;;; Copyright (c) 2017, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Institute for Artificial Intelligence/ -;;; Universitaet Bremen nor the names of its contributors may be used to -;;; endorse or promote products derived from this software without -;;; specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :pr2-cloud) - -(defun calculate-robust-handle-and-joint-transform (handle-transform joint-transform) - (return-from calculate-robust-handle-and-joint-transform - (values handle-transform joint-transform)) - (let* ((handle->joint-vector - (cl-transforms:v- - (cl-transforms-stamped:translation joint-transform) - (cl-transforms-stamped:translation handle-transform))) - (handle->joint-vector-projected-onto-xy - (cl-transforms:copy-3d-vector handle->joint-vector :z 0)) - (y-axis handle->joint-vector-projected-onto-xy) - (z-axis (cl-transforms:make-3d-vector 0 0 1)) - (x-axis (cl-transforms:cross-product y-axis z-axis)) - (orientation (cl-transforms:column-vectors->quaternion x-axis y-axis z-axis))) - (values - (copy-transform-stamped - handle-transform - :rotation orientation) - (copy-transform-stamped - joint-transform - :rotation orientation)))) - -(defun calculate-handle-to-gripper-transforms (map-to-handle map-to-joint - &optional (theta-max - (cma:degrees->radians 60))) - (let* ((joint-to-handle - (apply-transform (cram-tf:transform-stamped-inv map-to-joint) - map-to-handle)) - (handle-to-joint (cram-tf:transform-stamped-inv joint-to-handle))) - (mapcar (lambda (joint-to-circle-point) - (pose-stamped->transform-stamped - (cram-tf:rotate-pose - (strip-transform-stamped - (apply-transform handle-to-joint joint-to-circle-point)) - :z - (cram-math:degrees->radians 180)) - (cl-transforms-stamped:child-frame-id joint-to-circle-point))) - (loop for theta = 0.0 then (+ 0.1 theta) - while (< theta theta-max) - collect - (let ((rotation - (cl-tf:axis-angle->quaternion - (cl-transforms:make-3d-vector 0 0 1) theta))) - (cl-transforms-stamped:make-transform-stamped - (cl-transforms-stamped:frame-id joint-to-handle) - cram-tf:*robot-right-tool-frame* - (cl-transforms-stamped:stamp joint-to-handle) - (cl-transforms:rotate rotation (cl-transforms:translation joint-to-handle)) - (cl-transforms:rotation joint-to-handle))))))) - -(defun filter-trajectory-of-big-rotations (transforms-list &optional (rotation-threshold 0.1)) - (remove NIL - (remove-duplicates - (maplist (lambda (x) - (when (>= (length x) 2) - (let* ((quaternion-diff - (cl-transforms:quaternion->axis-angle - (cl-transforms:q- (cl-transforms:rotation (second x)) - (cl-transforms:rotation (first x))))) - (max-val - (with-slots (cl-transforms:x cl-transforms:y cl-transforms:z) - quaternion-diff - (max (abs cl-transforms:x) - (abs cl-transforms:y) - (abs cl-transforms:z))))) - (if (< max-val rotation-threshold) - (first x) - NIL)))) - transforms-list)))) - -(defun array-to-list (array) - (let* ((dimensions (array-dimensions array)) - (depth (1- (length dimensions))) - (indices (make-list (1+ depth) :initial-element 0))) - (labels ((recurse (n) - (loop for j below (nth n dimensions) - do (setf (nth n indices) j) - collect (if (= n depth) - (apply #'aref array indices) - (recurse (1+ n)))))) - (recurse 0)))) - -(defun apply-transform-to-covariance-matrix (transform 2d-covariance-matrix) - "Cnew = R * C * R-1" - (let* ((covariance-list-double - (mapcar (lambda (x-list) - (mapcar (lambda (x) (* x 1.0d0)) x-list)) - (array-to-list 2d-covariance-matrix))) - (cov-matrix - (make-array '(3 3) - :element-type 'double-float - :initial-contents - (list (append (first covariance-list-double) '(0.0d0)) - (append (second covariance-list-double) '(0.0d0)) - '(0.0d0 0.0d0 1.0d0)))) - (rotation-matrix - (cl-transforms:quaternion->matrix (cl-transforms:rotation transform))) - (rotation-matrix-double - (make-array '(3 3) - :element-type 'double-float - :initial-contents (array-to-list rotation-matrix))) - (rotation-matrix-inv - (cl-transforms:invert-rot-matrix rotation-matrix)) - (rotation-matrix-inv-double - (make-array '(3 3) - :element-type 'double-float - :initial-contents (array-to-list rotation-matrix-inv))) - (new-cov-matrix - (cma:double-matrix-product - (cma:double-matrix-product rotation-matrix-double cov-matrix) - rotation-matrix-inv-double)) - (new-cov-list - (array-to-list new-cov-matrix) - ;; (array-to-list cov-matrix) - )) - (make-array '(2 2) - :initial-contents - (list - (subseq (first new-cov-list) 0 2) - (subseq (second new-cov-list) 0 2))))) diff --git a/cram_pr2/cram_pr2_cloud/src/local-data.lisp b/cram_pr2/cram_pr2_cloud/src/local-data.lisp deleted file mode 100644 index 0b4c39a537..0000000000 --- a/cram_pr2/cram_pr2_cloud/src/local-data.lisp +++ /dev/null @@ -1,154 +0,0 @@ -;;; -;;; Copyright (c) 2017, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Institute for Artificial Intelligence/ -;;; Universitaet Bremen nor the names of its contributors may be used to -;;; endorse or promote products derived from this software without -;;; specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :pr2-cloud) - -(defvar *local-handle-transform* nil) -(defvar *local-joint-transform* nil) - -(defparameter *offset* 0.0d0) - -(defun local-handle-transform () - (or *local-handle-transform* - (multiple-value-bind (handle joint) - (robust-local-handle-and-joint-transform) - (setf *local-joint-transform* joint) - (setf *local-handle-transform* (translate-transform-stamped - handle :x-offset *offset*))))) - -(defun local-joint-transform () - (or *local-joint-transform* - (multiple-value-bind (handle joint) - (robust-local-handle-and-joint-transform) - (setf *local-handle-transform* (translate-transform-stamped - handle :x-offset *offset*)) - (setf *local-joint-transform* joint)))) - -(defun robust-local-handle-and-joint-transform () - (calculate-robust-handle-and-joint-transform - (kr-cloud:local-semantic-map-object-transform "IAIFridgeDoorHandle") - (kr-cloud:local-semantic-map-object-transform "HingedJoint"))) - -;; direct robot pose - -(defun local-robot-pose-in-map-from-joint (&optional (before-action "MoveFridgeHandle")) - (let ((local-map-to-joint (local-joint-transform)) - (cloud-joint-to-robot (cloud-joint-to-robot-transform before-action))) - (apply-transform local-map-to-joint cloud-joint-to-robot))) - -(defun local-robot-pose-in-map-from-handle (&optional (before-action "MoveFridgeHandle")) - (let ((local-map-to-handle (local-handle-transform)) - (cloud-handle-to-robot (cloud-handle-to-robot-transform before-action))) - (apply-transform local-map-to-handle cloud-handle-to-robot))) - -;; trajectory - -(defun filter-trajectory (trajectory-in-base) - (filter-trajectory-of-big-rotations - (subseq trajectory-in-base 26 42) - 0.1)) - -(defun adjust-trajectory (trajectory transform-to-invert) - (let ((gripper-to-adjusted-gripper - (cram-tf:copy-transform-stamped - (cram-tf:transform-stamped-inv transform-to-invert) - :child-frame-id (cl-transforms-stamped:child-frame-id transform-to-invert)))) - (mapcar (lambda (map-to-gripper-transform) - (cram-tf:apply-transform map-to-gripper-transform gripper-to-adjusted-gripper)) - trajectory))) - -(defun local-gripper-trajectory-in-map (&optional (action "MoveFridgeHandle")) - (let ((local-map-to-handle (local-handle-transform)) - (cloud-handle-to-gripper-list - (let ((filtered-trajectory - (filter-trajectory - (cloud-handle-to-gripper-transforms action)))) - (adjust-trajectory filtered-trajectory (car filtered-trajectory))))) - (mapcar (lambda (cloud-handle-to-gripper) - (apply-transform local-map-to-handle cloud-handle-to-gripper)) - cloud-handle-to-gripper-list))) - -(defun gripper-trajectory-in-map->in-base (trajectory-in-map) - (let ((local-map-to-gripper-list trajectory-in-map) - (local-map-to-robot (current-robot-transform))) - (visualize-trajectory (mapcar #'strip-transform-stamped local-map-to-gripper-list)) - (mapcar (lambda (local-map-to-gripper) - (apply-transform (cram-tf:transform-stamped-inv local-map-to-robot) - local-map-to-gripper)) - local-map-to-gripper-list))) - -;; (defun original-trajectory-in-base-filtered () -;; (filter-trajectory -;; (gripper-trajectory-in-map->in-base -;; (local-gripper-trajectory-in-map)))) - -;; projected trajectory - -(defun local-gripper-projected-trajectory-in-map (&optional (action "MoveFridgeHandle")) - (let ((local-map-to-joint (local-joint-transform)) - (cloud-joint-to-gripper-list (cloud-joint-to-gripper-transforms action))) - (let ((map-to-gripper-trajectory - (filter-trajectory - (mapcar (lambda (cloud-joint-to-gripper) - (apply-transform local-map-to-joint cloud-joint-to-gripper)) - cloud-joint-to-gripper-list)))) - (let* ((local-map-to-handle (local-handle-transform)) - (handle-to-gripper-transform - (cram-tf:apply-transform - (cram-tf:transform-stamped-inv local-map-to-handle) - (car map-to-gripper-trajectory)))) - (adjust-trajectory map-to-gripper-trajectory handle-to-gripper-transform))))) - -;; (defun local-gripper-projected-trajectory-in-base (&optional (action "MoveFridgeHandle")) -;; (let ((local-map-to-gripper-list (local-gripper-projected-trajectory-in-map action)) -;; (local-map-to-robot (current-robot-transform))) -;; (visualize-trajectory (subseq (mapcar (lambda (trans) -;; (strip-transform-stamped -;; (translate-transform-stamped trans :z-offset 0.1))) -;; local-map-to-gripper-list) -;; 26 42)) -;; (mapcar (lambda (local-map-to-gripper) -;; (apply-transform (cram-tf:transform-stamped-inv local-map-to-robot) -;; local-map-to-gripper)) -;; local-map-to-gripper-list))) - -;; (defun local-gripper-projected-trajectory-in-base-filtered (&optional (action "MoveFridgeHandle")) -;; (filter-trajectory-in-base -;; (local-gripper-projected-trajectory-in-base))) - - - -;; distribution - -(defun local-handle-to-robot-transform-distribution () - (let ((local-map-to-handle (local-handle-transform))) - (multiple-value-bind (cloud-handle-to-robot-transform-mean covariance) - (cloud-handle-to-robot-transform-distribution) - (list (apply-transform local-map-to-handle cloud-handle-to-robot-transform-mean) - (apply-transform-to-covariance-matrix local-map-to-handle covariance))))) diff --git a/cram_pr2/cram_pr2_cloud/src/projection-plans.lisp b/cram_pr2/cram_pr2_cloud/src/projection-plans.lisp deleted file mode 100644 index 0bbb989a86..0000000000 --- a/cram_pr2/cram_pr2_cloud/src/projection-plans.lisp +++ /dev/null @@ -1,125 +0,0 @@ -;;; -;;; Copyright (c) 2017, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Institute for Artificial Intelligence/ -;;; Universitaet Bremen nor the names of its contributors may be used to -;;; endorse or promote products derived from this software without -;;; specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :pr2-cloud) - -(defun init () - (setf *cloud-handle-transform* nil) - (setf *cloud-joint-transform* nil) - (setf *local-handle-transform* nil) - (setf *local-joint-transform* nil) - (init-connection) - (load-trajectory-episode)) - - - - -(defmacro with-simulated-robot (&body body) - `(let ((results - (proj:with-projection-environment urdf-proj:urdf-bullet-projection-environment - (cpl:top-level - ,@body)))) - (car (cram-projection::projection-environment-result-result results)))) - -(defun visualize-cloud-handle-and-joint () - (btr-utils:spawn-object 'cloud-handle-original :mug - :pose (strip-transform-stamped - (kr-cloud:semantic-map-object-transform "IAIFridgeDoorHandle")) - :color '(1 0 0)) - (btr-utils:spawn-object 'cloud-handle :mug - :pose (strip-transform-stamped (cloud-handle-transform))) - (btr-utils:spawn-object 'cloud-joint-original :mondamin - :pose (strip-transform-stamped - (kr-cloud:semantic-map-object-transform "HingedJoint")) - :color '(1 0 0)) - (btr-utils:spawn-object 'cloud-joint :mondamin - :pose (strip-transform-stamped (cloud-joint-transform)))) - -(defun visualize-trajectory (poses) - (btr-utils:kill-all-objects) - (let ((i 0)) - (dolist (pose poses) - ;; (btr-utils:spawn-object - ;; (intern (format nil "fork-~a" i) :keyword) - ;; :fork - ;; :pose pose) - (btr-utils:spawn-object - (intern (format nil "cereal-~a" i) :keyword) - :visualization-box - :pose pose) - (cram-tf:visualize-marker pose :id (+ i 0) :r-g-b-list '(0.5 0 1)) - (incf i)))) - - -(defun local-gripper-trajectory-in-map-from-radius () - (let* ((local-map-to-handle (local-handle-transform)) - (local-handle-to-gripper-list - (calculate-handle-to-gripper-transforms local-map-to-handle - (local-joint-transform)))) - (mapcar (lambda (local-handle-to-gripper) - (apply-transform local-map-to-handle local-handle-to-gripper)) - local-handle-to-gripper-list))) - -(defun local-gripper-trajectory-in-base-from-radius () - (let* ((local-map-to-gripper-list (local-gripper-trajectory-in-map-from-radius)) - (local-map-to-robot (cram-tf:pose->transform-stamped - cram-tf:*fixed-frame* - cram-tf:*robot-base-frame* - 0.0 - (btr:object-pose 'cram-pr2-description:pr2)))) - (mapcar (lambda (local-map-to-gripper) - (apply-transform (cram-tf:transform-stamped-inv local-map-to-robot) - local-map-to-gripper)) - local-map-to-gripper-list))) - - -(defun move-in-projection-to-fridge () - (proj:with-projection-environment urdf-proj:urdf-bullet-projection-environment - (cpl:top-level - (exe:perform - (let ((?pose (cl-transforms-stamped:make-pose-stamped - "map" 0.0 - (cl-transforms:make-3d-vector 0.5 -0.8 0) - (cl-transforms:make-identity-rotation)))) - (desig:a motion (type going) (pose ?pose)))) - (exe:perform - (desig:a motion (type moving-torso) (joint-angle 0.3)))))) - -(defun execute-trajectory-in-projection () - (move-in-projection-to-fridge) - (let ((trajectory-in-base (local-gripper-trajectory-in-base-from-radius))) - (proj:with-projection-environment urdf-proj:urdf-bullet-projection-environment - (cpl:top-level - (mapc (lambda (via-point-transform) - (let ((?pose (strip-transform-stamped via-point-transform))) - (exe:perform - (desig:a motion - (type moving-tcp) - (right-pose ?pose))))) - trajectory-in-base))))) diff --git a/cram_pr2/cram_pr2_cloud/src/real-world-plans.lisp b/cram_pr2/cram_pr2_cloud/src/real-world-plans.lisp deleted file mode 100644 index b334d397d0..0000000000 --- a/cram_pr2/cram_pr2_cloud/src/real-world-plans.lisp +++ /dev/null @@ -1,201 +0,0 @@ -;;; -;;; Copyright (c) 2017, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Institute for Artificial Intelligence/ -;;; Universitaet Bremen nor the names of its contributors may be used to -;;; endorse or promote products derived from this software without -;;; specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :pr2-cloud) - -(defmacro with-real-robot (&body body) - `(cram-process-modules:with-process-modules-running - (pr2-pms::pr2-base-pm pr2-pms::pr2-arms-pm - pr2-pms::pr2-grippers-pm pr2-pms::pr2-ptu-pm) - (cpl:top-level - ,@body))) - -(defun test-gripper () - (with-real-robot - (exe:perform - (desig:a motion (type opening-gripper) (gripper left))))) - -(defun test-navigation () - (with-real-robot - (exe:perform - (let ((?pose (cl-transforms-stamped:make-pose-stamped - "map" 0.0 - (cl-transforms:make-3d-vector 0.5 -0.8 0) - (cl-transforms:make-identity-rotation)))) - (desig:a motion (type going) (pose ?pose)))))) - -;; (defun test-manipulation () -;; (with-real-robot -;; (let ((?pose (local-robot-pose-in-map-from-handle))) -;; (exe:perform -;; (desig:an action (type going) (target (desig:a location (pose ?pose)))))) -;; (let ((?pose (strip-transform-stamped -;; (car (subseq (local-gripper-trajectory-in-base "MoveFridgeHandle") 23))))) -;; (exe:perform -;; (desig:a motion (type moving-tcp) (left-pose ?pose)))))) - -(defun test-manipulation () - (with-real-robot - (let ((?pose (strip-transform-stamped - (car (local-gripper-trajectory-in-base-from-radius))))) - (exe:perform - (desig:a motion (type moving-tcp) (left-pose ?pose)))))) - -(defun move-projected-pr2-away () - (btr-utils:move-object 'cram-pr2-description:pr2 - (cl-transforms:make-pose - (cl-transforms:make-3d-vector 0 0 0) - (cl-transforms:make-identity-rotation)))) - -(defun environment-articulation-plan (&key (projected-or-original :original) - (location-designator)) - (let* ((?handle-pose (strip-transform-stamped (local-handle-transform))) - (?arm (kr-cloud::arm-used-in-action "OpenFridge")) - (?robot 'cram-pr2-description:pr2) - (?location-for-robot (or location-designator - (desig:a location - (my-reachable-for ?robot) - (location (desig:a location (pose ?handle-pose))) - (context "OpenFridge")))) - (?target (ecase ?arm (:left :left-pose) (:right :right-pose)))) - - (btr-utils:kill-all-objects) - (move-projected-pr2-away) - (cram-bullet-reasoning::clear-costmap-vis-object) - (exe:perform (desig:an action - (type positioning-arm) - (left-configuration park) - (right-configuration park))) - ;; (exe:perform (desig:a motion (type moving-torso) (joint-angle 0.15))) - - (cpl:with-failure-handling - (((or common-fail:actionlib-action-timed-out - common-fail:manipulation-low-level-failure) (e) - (roslisp:ros-warn (pr2-cloud open-fridge) "Plan failed: ~a. Retrying.~%" e) - (btr-utils:spawn-object 'red-dot :pancake-maker :color '(1 0 0 0.5) - :pose '((1.5 -1.05 1.6) (0 0 0 1))) - (cpl:sleep 0.5) - (exe:perform (desig:an action (type opening-gripper) (gripper right))) - (exe:perform (desig:an action - (type positioning-arm) - (left-configuration park) - (right-configuration park))) - (move-projected-pr2-away) - (unless location-designator - (setf ?location-for-robot (desig:next-solution ?location-for-robot))) - (cpl:sleep 0.5) - (btr-utils:kill-object 'red-dot) - (cpl:retry))) - - (cpl:par - (exe:perform - (desig:an action (type going) (target ?location-for-robot))) - (exe:perform - (desig:an action (type opening-gripper) (gripper ?arm)))) - - (let ((?right-arm-init-config '(-0.6177226607749531d0 0.8595855682477204d0 - -0.22685404643554485d0 -2.1215879821638572d0 - -27.55566886200435d0 -1.9241091851082714d0 - 9.343508274913418d0))) - (exe:perform - (desig:a motion - (type moving-arm-joints) - (right-joint-states ?right-arm-init-config)))) - - (let ((?trajectory - (gripper-trajectory-in-map->in-base - (ecase projected-or-original - (:original - (local-gripper-trajectory-in-map - "MoveFridgeHandle")) - (:projected - (local-gripper-projected-trajectory-in-map - "MoveFridgeHandle")))))) - - (cpl:with-retry-counters ((reach-retry 2)) - (cpl:with-failure-handling - ((common-fail:low-level-failure (e) - (roslisp:ros-warn (pr2-cloud open-fridge) "~a" e) - (cpl:do-retry reach-retry - (cpl:retry)) - (return))) - (let ((?pose (strip-transform-stamped (first ?trajectory)))) - (cram-tf:visualize-marker ?pose) - (exe:perform - (desig:a motion - (type moving-tcp) - (?target ?pose)))))) - (exe:perform - (desig:an action (type gripping) (gripper ?arm) (effort 100))) - - (mapcar (lambda (transform) - (let ((?pose (strip-transform-stamped transform))) - (cpl:with-failure-handling - ((common-fail:manipulation-goal-not-reached (e) - (when location-designator - (roslisp:ros-warn (pr2-cloud execute-traj) "~a" e) - (roslisp:ros-warn (pr2-cloud execute-traj) "Ignoring.") - (return)))) - (exe:perform - (desig:a motion - (type moving-tcp) - (?target ?pose)))))) - (cdr ?trajectory)) - - (exe:perform - (desig:an action (type opening-gripper) (gripper ?arm))) - - (btr-utils:spawn-object 'green-dot :pancake-maker :color '(0 1 0 0.5) - :pose '((1.5 -1.05 1.6) (0 0 0 1))) - - (let ((?right-arm-init-config '(-2.040980560942328d0 0.2712278780562381d0 - -0.6460215625664274d0 -2.028500414744249d0 - -26.026134035944583d0 -1.1912449349507037d0 - 12.292977968464921d0))) - (exe:perform - (desig:a motion - (type moving-arm-joints) - (right-joint-states ?right-arm-init-config)))) - - ?location-for-robot)))) - - - -(defun main (&optional (real? t)) - (pr2-cloud::init) - (let ((location (with-simulated-robot - (pr2-cloud::environment-articulation-plan - :projected-or-original :projected)))) - (sleep 3.0) - (when real? - (with-real-robot - (pr2-cloud::environment-articulation-plan - :projected-or-original :projected - :location-designator location))))) - diff --git a/cram_pr2/cram_pr2_cloud/src/tf-utilities.lisp b/cram_pr2/cram_pr2_cloud/src/tf-utilities.lisp deleted file mode 100644 index d693be55ee..0000000000 --- a/cram_pr2/cram_pr2_cloud/src/tf-utilities.lisp +++ /dev/null @@ -1,45 +0,0 @@ -;;; -;;; Copyright (c) 2017, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Institute for Artificial Intelligence/ -;;; Universitaet Bremen nor the names of its contributors may be used to -;;; endorse or promote products derived from this software without -;;; specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :pr2-cloud) - -(defun current-robot-transform () - (if (eql cram-projection:*projection-environment* - 'urdf-proj:urdf-bullet-projection-environment) - (cram-tf:pose->transform-stamped - cram-tf:*fixed-frame* - cram-tf:*robot-base-frame* - 0.0 - (btr:object-pose 'cram-pr2-description:pr2)) - (cl-transforms-stamped:lookup-transform - cram-tf:*transformer* - cram-tf:*fixed-frame* - cram-tf:*robot-base-frame* - :timeout cram-tf:*tf-default-timeout* - :time 0.0))) diff --git a/cram_pr2/cram_pr2_description/src/arm-kinematics.lisp b/cram_pr2/cram_pr2_description/src/arm-kinematics.lisp index 9eba6fce78..6ffbd1b079 100644 --- a/cram_pr2/cram_pr2_description/src/arm-kinematics.lisp +++ b/cram_pr2/cram_pr2_description/src/arm-kinematics.lisp @@ -1,19 +1,19 @@ ;;; Copyright (c) 2012, CRAM team ;;; All rights reserved. -;;; +;;; ;;; Redistribution and use in source and binary forms, with or without ;;; modification, are permitted provided that the following conditions are met: -;;; +;;; ;;; * Redistributions of source code must retain the above copyright ;;; notice, this list of conditions and the following disclaimer. ;;; * Redistributions in binary form must reproduce the above copyright ;;; notice, this list of conditions and the following disclaimer in the ;;; documentation and/or other materials provided with the distribution. ;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software ;;; without specific prior written permission. -;;; +;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" ;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE ;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE @@ -34,7 +34,7 @@ (cl-transforms-stamped:make-identity-rotation))) (defparameter *standard-to-pr2-gripper-transform* - (cl-transforms-stamped:make-transform + (cl-transforms:make-transform (cl-transforms:make-identity-vector) (cl-transforms:matrix->quaternion #2A((0 1 0) @@ -69,75 +69,9 @@ ;; (cl-transforms:make-quaternion 0.9215513103717499d0 -0.387996037470125d0 ;; -0.014188589447636247d0 -9.701489976338351d-4))) -;; (defparameter *right-parking-joint-states* -;; '(("r_shoulder_pan_joint" -1.3810115229719555d0) -;; ("r_shoulder_lift_joint" 1.1282870348994702d0) -;; ("r_upper_arm_roll_joint" -1.7100000000000002d0) -;; ("r_elbow_flex_joint" -2.105735087282934d0) -;; ("r_forearm_roll_joint" -2.658135473603226d0) -;; ("r_wrist_flex_joint" -1.9927790883777252d0) -;; ("r_wrist_roll_joint" -2.5861844605475843d0))) -;; (defparameter *left-parking-joint-states* -;; '(("l_shoulder_pan_joint" 1.3810115229719555d0) -;; ("l_shoulder_lift_joint" 1.1282870348994702d0) -;; ("l_upper_arm_roll_joint" 1.71d0) -;; ("l_elbow_flex_joint" -2.105735087282934d0) -;; ("l_forearm_roll_joint" 2.6581354736032257d0) -;; ("l_wrist_flex_joint" -1.9927790883777252d0) -;; ("l_wrist_roll_joint" 2.586184460547585d0))) -(defparameter *left-carrying-joint-states* - '(("l_shoulder_pan_joint" 1.9652919379395388d0) - ("l_shoulder_lift_joint" -0.26499816732737785d0) - ("l_upper_arm_roll_joint" 1.3837617139225473d0) - ("l_elbow_flex_joint" -2.1224566064321584d0) - ("l_forearm_roll_joint" 16.99646118944817d0) - ("l_wrist_flex_joint" -0.07350789589924167d0) - ("l_wrist_roll_joint" 0.0))) -(defparameter *left-tucked-joint-states* - '(("l_shoulder_pan_joint" 0.1709440184822959d0) - ("l_shoulder_lift_joint" 1.1472294789783886d0) - ("l_upper_arm_roll_joint" 1.9124515764640622d0) - ("l_elbow_flex_joint" -1.66700794841958d0) - ("l_forearm_roll_joint" 6.255471931555043d0) - ("l_wrist_flex_joint" -0.07476630774212056d0) - ("l_wrist_roll_joint" -14.7079336142174d0))) - -(defparameter *right-carrying-joint-states* - '(("r_shoulder_pan_joint" -1.712587449591307d0) - ("r_shoulder_lift_joint" -0.2567290370386635d0) - ("r_upper_arm_roll_joint" -1.4633501125737374d0) - ("r_elbow_flex_joint" -2.1221670650093913d0) - ("r_forearm_roll_joint" 1.7663253481913623d0) - ("r_wrist_flex_joint" -0.07942669250968948d0) - ("r_wrist_roll_joint" 0.05106258161229582d0))) - -(defparameter *right-tucked-joint-states* - '(("r_shoulder_pan_joint" -0.08181428617939712d0) - ("r_shoulder_lift_joint" 0.9781030555170612d0) - ("r_upper_arm_roll_joint" -1.4665572091011352d0) - ("r_elbow_flex_joint" -1.6859729116108224d0) - ("r_forearm_roll_joint" -27.72481374424779d0) - ("r_wrist_flex_joint" -0.10621948550701799d0) - ("r_wrist_roll_joint" 7.662671673625887d0))) - - -(defun get-arm-base-joint-names (arm) - (declare (ignore arm)) - (list "torso_lift_joint")) - -(defun get-arm-tool-joint-names (arm) - (case arm - (:left - (list "l_gripper_palm_joint" "l_gripper_tool_joint")) - (:right - (list "r_gripper_palm_joint" "r_gripper_tool_joint")))) - -(defun get-arm-base-link-names (arm) - (declare (ignore arm)) - (list "torso_lift_link")) (defun get-arm-joint-names (arm) ;; TODO: the proper way to do this is to read them out of the srdl, @@ -221,130 +155,163 @@ "r_gripper_palm_link")))) (def-fact-group pr2-arm-kinematics-facts (arm - end-effector-link robot-tool-frame - gripper-link gripper-joint + arm-links arm-joints + hand-links hand-link hand-finger-link + gripper-joint gripper-meter-to-joint-multiplier - planning-group - robot-joint-states - ;; robot-arms-parking-joint-states - ;; robot-arms-carrying-joint-states - ;; end-effector-parking-pose - ;; robot-pre-grasp-joint-states - arm-joints arm-base-joints arm-tool-joints - arm-links arm-base-links - hand-links - standard-to-particular-gripper-transform - tcp-in-ee-pose) + standard<-particular-gripper-transform + end-effector-link robot-tool-frame + tcp-in-ee-pose + robot-joint-states) - (<- (arm pr2 :right)) - (<- (arm pr2 :left)) + (<- (arm :pr2 :right)) + (<- (arm :pr2 :left)) - (<- (end-effector-link pr2 :left "l_wrist_roll_link")) - (<- (end-effector-link pr2 :right "r_wrist_roll_link")) + (<- (arm-links :pr2 ?arm ?links) + (lisp-fun get-arm-link-names ?arm ?links)) - (<- (robot-tool-frame pr2 :left "l_gripper_tool_frame")) - (<- (robot-tool-frame pr2 :right "r_gripper_tool_frame")) + (<- (arm-joints :pr2 ?arm ?joints) + (lisp-fun get-arm-joint-names ?arm ?joints)) - (<- (gripper-link pr2 :left ?link) + (<- (hand-links :pr2 ?arm ?links) + (lisp-fun get-hand-link-names ?arm ?links)) + + (<- (hand-link :pr2 :left ?link) (bound ?link) (lisp-fun search "l_gripper" ?link ?pos) (lisp-pred identity ?pos)) - (<- (gripper-link pr2 :right ?link) + (<- (hand-link :pr2 :right ?link) (bound ?link) (lisp-fun search "r_gripper" ?link ?pos) (lisp-pred identity ?pos)) - (<- (gripper-joint pr2 :left "l_gripper_l_finger_joint")) - (<- (gripper-joint pr2 :left "l_gripper_r_finger_joint")) - (<- (gripper-joint pr2 :right "r_gripper_l_finger_joint")) - (<- (gripper-joint pr2 :right "r_gripper_r_finger_joint")) - - (<- (gripper-meter-to-joint-multiplier pr2 5.0)) - - (<- (planning-group pr2 :left "left_arm")) - (<- (planning-group pr2 :right "right_arm")) - (<- (planning-group pr2 (:left :right) "both_arms")) - (<- (planning-group pr2 (:right :left) "both_arms")) - - (<- (robot-joint-states pr2 :arm :left :carry ?joint-states) - (symbol-value *left-carrying-joint-states* ?joint-states)) - - (<- (robot-joint-states pr2 :arm :right :carry ?joint-states) - (symbol-value *right-carrying-joint-states* ?joint-states)) - - (<- (robot-joint-states pr2 :arm :left :park ?joint-states) - (symbol-value *left-carrying-joint-states* ?joint-states)) - - (<- (robot-joint-states pr2 :arm :right :park ?joint-states) - (symbol-value *right-carrying-joint-states* ?joint-states)) - - (<- (robot-joint-states pr2 :arm :left :tucked ?joint-states) - (symbol-value *left-tucked-joint-states* ?joint-states)) - - (<- (robot-joint-states pr2 :arm :right :tucked ?joint-states) - (symbol-value *right-tucked-joint-states* ?joint-states)) + (<- (hand-finger-link :pr2 ?arm ?link) + (bound ?link) + (hand-link :pr2 ?arm ?link) + (lisp-fun search "finger" ?link ?pos) + (lisp-pred identity ?pos)) - ;; (<- (robot-arms-carrying-joint-states pr2 ?joint-states) - ;; (symbol-value *right-carrying-joint-states* ?right-joint-states) - ;; (symbol-value *left-carrying-joint-states* ?left-joint-states) - ;; (append ?right-joint-states ?left-joint-states ?joint-states)) + (<- (gripper-joint :pr2 :left "l_gripper_l_finger_joint")) + (<- (gripper-joint :pr2 :left "l_gripper_r_finger_joint")) + (<- (gripper-joint :pr2 :right "r_gripper_l_finger_joint")) + (<- (gripper-joint :pr2 :right "r_gripper_r_finger_joint")) - ;; (<- (robot-arms-carrying-joint-states pr2 ?joint-states :left) - ;; (symbol-value *left-carrying-joint-states* ?joint-states)) + (<- (gripper-meter-to-joint-multiplier :pr2 5.0)) - ;; (<- (robot-arms-carrying-joint-states pr2 ?joint-states :right) - ;; (symbol-value *right-carrying-joint-states* ?joint-states)) + (<- (standard<-particular-gripper-transform :pr2 ?transform) + (symbol-value *standard-to-pr2-gripper-transform* ?transform)) - ;; (<- (robot-arms-parking-joint-states pr2 ?joint-states) - ;; (symbol-value *right-parking-joint-states* ?right-joint-states) - ;; (symbol-value *left-parking-joint-states* ?left-joint-states) - ;; (append ?right-joint-states ?left-joint-states ?joint-states)) + (<- (end-effector-link :pr2 :left "l_wrist_roll_link")) + (<- (end-effector-link :pr2 :right "r_wrist_roll_link")) - ;; (<- (robot-arms-parking-joint-states pr2 ?joint-states :left) - ;; (symbol-value *left-parking-joint-states* ?joint-states)) + (<- (robot-tool-frame :pr2 :left "l_gripper_tool_frame")) + (<- (robot-tool-frame :pr2 :right "r_gripper_tool_frame")) - ;; (<- (robot-arms-parking-joint-states pr2 ?joint-states :right) - ;; (symbol-value *right-parking-joint-states* ?joint-states)) + (<- (tcp-in-ee-pose :pr2 ?transform) + (symbol-value *tcp-in-ee-pose* ?transform)) - ;; (<- (end-effector-parking-pose pr2 ?pose :left) + ;; (<- (end-effector-parking-pose :pr2 ?pose :left) ;; (symbol-value *left-parking-end-effector-pose* ?pose)) - - ;; (<- (end-effector-parking-pose pr2 ?pose :right) + ;; (<- (end-effector-parking-pose :pr2 ?pose :right) ;; (symbol-value *right-parking-end-effector-pose* ?pose)) - ;; (<- (robot-pre-grasp-joint-states - ;; pr2 (("torso_lift_joint" 0.33) . ?parking-joint-states)) - ;; (robot-arms-parking-joint-states pr2 ?parking-joint-states)) - - ;; (<- (robot-pre-grasp-joint-states - ;; pr2 (("torso_lift_joint" 0.165) . ?parking-joint-states)) - ;; (robot-arms-parking-joint-states pr2 ?parking-joint-states)) - - ;; (<- (robot-pre-grasp-joint-states - ;; pr2 (("torso_lift_joint" 0.00) . ?parking-joint-states)) - ;; (robot-arms-parking-joint-states pr2 ?parking-joint-states)) - - (<- (arm-joints pr2 ?arm ?joints) - (lisp-fun get-arm-joint-names ?arm ?joints)) - - (<- (arm-base-joints pr2 ?arm ?joints) - (lisp-fun get-arm-base-joint-names ?arm ?joints)) - - (<- (arm-tool-joints pr2 ?arm ?joints) - (lisp-fun get-arm-tool-joint-names ?arm ?joints)) - - (<- (arm-links pr2 ?arm ?links) - (lisp-fun get-arm-link-names ?arm ?links)) - - (<- (arm-base-links pr2 ?arm ?links) - (lisp-fun get-arm-base-link-names ?arm ?links)) - - (<- (hand-links pr2 ?arm ?links) - (lisp-fun get-hand-link-names ?arm ?links)) - - (<- (standard-to-particular-gripper-transform pr2 ?transform) - (symbol-value *standard-to-pr2-gripper-transform* ?transform)) - - (<- (tcp-in-ee-pose pr2 ?transform) - (symbol-value *tcp-in-ee-pose* ?transform))) + (<- (robot-joint-states :pr2 :arm :left :carry + (("l_shoulder_pan_joint" 1.9652919379395388d0) + ("l_shoulder_lift_joint" -0.26499816732737785d0) + ("l_upper_arm_roll_joint" 1.3837617139225473d0) + ("l_elbow_flex_joint" -2.1224566064321584d0) + ("l_forearm_roll_joint" 16.99646118944817d0) + ("l_wrist_flex_joint" -0.07350789589924167d0) + ("l_wrist_roll_joint" 0.0)))) + (<- (robot-joint-states :pr2 :arm :left :park ?joint-states) + (robot-joint-states :pr2 :arm :left :carry ?joint-states)) + (<- (robot-joint-states :pr2 :arm :left :carry-top + ;; arm low -- collision avoidance hard atm + ;; (("l_shoulder_pan_joint" 1.3810115229719555d0) + ;; ("l_shoulder_lift_joint" 1.1282870348994702d0) + ;; ("l_upper_arm_roll_joint" 1.71d0) + ;; ("l_elbow_flex_joint" -2.105735087282934d0) + ;; ("l_forearm_roll_joint" 2.6581354736032257d0) + ;; ("l_wrist_flex_joint" -1.9927790883777252d0) + ;; ("l_wrist_roll_joint" 2.586184460547585d0)) + (("l_shoulder_pan_joint" 1.0252138037286773d0) + ("l_shoulder_lift_joint" -0.06966848987919201d0) + ("l_upper_arm_roll_joint" 1.1765832782526544d0) + ("l_elbow_flex_joint" -1.9323726623855864d0) + ("l_forearm_roll_joint" 1.3824994377973336d0) + ("l_wrist_flex_joint" -1.8416233909065576d0) + ("l_wrist_roll_joint" 2.907373693068033d0)))) + (<- (robot-joint-states :pr2 :arm :left :carry-top-basket + (("l_shoulder_pan_joint" 1.0) + ("l_shoulder_lift_joint" -0.5) + ("l_upper_arm_roll_joint" 3.14) + ("l_elbow_flex_joint" -1.5) + ("l_forearm_roll_joint" -0.2) + ("l_wrist_flex_joint" -0.55)))) + (<- (robot-joint-states :pr2 :arm :left :hand-over + (("l_shoulder_pan_joint" -0.3) + ("l_shoulder_lift_joint" -0.5) + ("l_upper_arm_roll_joint" 3.14) + ("l_elbow_flex_joint" -1.3) + ("l_forearm_roll_joint" 0) + ("l_wrist_flex_joint" -0.75)))) + (<- (robot-joint-states :pr2 :arm :left :carry-side-gripper-vertical + (("l_shoulder_pan_joint" 1.2469064067488675d0) + ("l_shoulder_lift_joint" 0.013567714247075813d0) + ("l_upper_arm_roll_joint" 1.3837617139225473d0) + ("l_elbow_flex_joint" -2.105735087282934d0) + ("l_forearm_roll_joint" 0.8809236347313467d0) + ("l_wrist_flex_joint" -0.9276887874976607d0) + ("l_wrist_roll_joint" 2.3644392879261957d0)))) + (<- (robot-joint-states :pr2 :arm :left :tucked + (("l_shoulder_pan_joint" 0.1709440184822959d0) + ("l_shoulder_lift_joint" 1.1472294789783886d0) + ("l_upper_arm_roll_joint" 1.9124515764640622d0) + ("l_elbow_flex_joint" -1.66700794841958d0) + ("l_forearm_roll_joint" 6.255471931555043d0) + ("l_wrist_flex_joint" -0.07476630774212056d0) + ("l_wrist_roll_joint" -14.7079336142174d0)))) + + (<- (robot-joint-states :pr2 :arm :right :carry + (("r_shoulder_pan_joint" -1.712587449591307d0) + ("r_shoulder_lift_joint" -0.2567290370386635d0) + ("r_upper_arm_roll_joint" -1.4633501125737374d0) + ("r_elbow_flex_joint" -2.1221670650093913d0) + ("r_forearm_roll_joint" 1.7663253481913623d0) + ("r_wrist_flex_joint" -0.07942669250968948d0) + ("r_wrist_roll_joint" 0.05106258161229582d0)))) + (<- (robot-joint-states :pr2 :arm :right :park ?joint-states) + (robot-joint-states :pr2 :arm :right :carry ?joint-states)) + (<- (robot-joint-states :pr2 :arm :right :carry-top + ;; arm low -- collision avoidance hard atm + ;; (("r_shoulder_pan_joint" -1.3810115229719555d0) + ;; ("r_shoulder_lift_joint" 1.1282870348994702d0) + ;; ("r_upper_arm_roll_joint" -1.7100000000000002d0) + ;; ("r_elbow_flex_joint" -2.105735087282934d0) + ;; ("r_forearm_roll_joint" -2.658135473603226d0) + ;; ("r_wrist_flex_joint" -1.9927790883777252d0) + ;; ("r_wrist_roll_joint" -2.5861844605475843d0)) + (("r_shoulder_pan_joint" -1.183809044088452d0) + ("r_shoulder_lift_joint" -0.30680923151650064d0) + ("r_upper_arm_roll_joint" -1.6439096470662296d0) + ("r_elbow_flex_joint" -2.0632453854762955d0) + ("r_forearm_roll_joint" -1.3016362275774522d0) + ("r_wrist_flex_joint" -1.284945123721191d0) + ("r_wrist_roll_joint" -1.974782974061931d0)))) + (<- (robot-joint-states :pr2 :arm :right :carry-side-gripper-vertical + (("r_shoulder_pan_joint" -0.7524126363048715d0) + ("r_shoulder_lift_joint" -0.2d0) + ("r_upper_arm_roll_joint" -1.7100000000000002d0) + ("r_elbow_flex_joint" -2.1221670650093913d0) + ("r_forearm_roll_joint" -0.5d0) + ("r_wrist_flex_joint" -0.7163017685583473d0) + ("r_wrist_roll_joint" 0.37943005734078916d0)))) + (<- (robot-joint-states :pr2 :arm :right :tucked + (("r_shoulder_pan_joint" -0.08181428617939712d0) + ("r_shoulder_lift_joint" 0.9781030555170612d0) + ("r_upper_arm_roll_joint" -1.4665572091011352d0) + ("r_elbow_flex_joint" -1.6859729116108224d0) + ("r_forearm_roll_joint" -27.72481374424779d0) + ("r_wrist_flex_joint" -0.10621948550701799d0) + ("r_wrist_roll_joint" 7.662671673625887d0))))) diff --git a/cram_pr2/cram_pr2_description/src/package.lisp b/cram_pr2/cram_pr2_description/src/package.lisp index 03ab1a0b83..7a4c5d8d33 100644 --- a/cram_pr2/cram_pr2_description/src/package.lisp +++ b/cram_pr2/cram_pr2_description/src/package.lisp @@ -1,19 +1,19 @@ ;;; Copyright (c) 2012, Lorenz Moesenlechner ;;; All rights reserved. -;;; +;;; ;;; Redistribution and use in source and binary forms, with or without ;;; modification, are permitted provided that the following conditions are met: -;;; +;;; ;;; * Redistributions of source code must retain the above copyright ;;; notice, this list of conditions and the following disclaimer. ;;; * Redistributions in binary form must reproduce the above copyright ;;; notice, this list of conditions and the following disclaimer in the ;;; documentation and/or other materials provided with the distribution. ;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software ;;; without specific prior written permission. -;;; +;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" ;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE ;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE @@ -31,7 +31,4 @@ (defpackage cram-pr2-description (:use #:common-lisp #:cram-prolog - #:cram-robot-interfaces) - (:export - ;; pr2-knowledge - #:pr2)) + #:cram-robot-interfaces)) diff --git a/cram_pr2/cram_pr2_description/src/pr2-knowledge.lisp b/cram_pr2/cram_pr2_description/src/pr2-knowledge.lisp index 4bf5fa7ac0..c2d4705d7c 100644 --- a/cram_pr2/cram_pr2_description/src/pr2-knowledge.lisp +++ b/cram_pr2/cram_pr2_description/src/pr2-knowledge.lisp @@ -1,19 +1,19 @@ ;;; Copyright (c) 2012, Lorenz Moesenlechner ;;; All rights reserved. -;;; +;;; ;;; Redistribution and use in source and binary forms, with or without ;;; modification, are permitted provided that the following conditions are met: -;;; +;;; ;;; * Redistributions of source code must retain the above copyright ;;; notice, this list of conditions and the following disclaimer. ;;; * Redistributions in binary form must reproduce the above copyright ;;; notice, this list of conditions and the following disclaimer in the ;;; documentation and/or other materials provided with the distribution. ;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software +;;; Technische Universitaet Muenchen nor the names of its contributors +;;; may be used to endorse or promote products derived from this software ;;; without specific prior written permission. -;;; +;;; ;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" ;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE ;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE @@ -28,37 +28,40 @@ (in-package :cram-pr2-description) -;; (def-tool (cl-transforms:make-3d-vector 1 0 0) 0.20) - (defparameter *forward-looking-position-in-base-frame* (cl-transforms:make-3d-vector 10.0 0.0 1.5)) -(def-fact-group pr2-metadata (robot - robot-base-frame robot-torso-link-joint +(def-fact-group pr2-metadata (robot-base-frame robot-torso-link-joint robot-odom-frame camera-frame camera-minimal-height camera-maximal-height + camera-horizontal-angle camera-vertical-angle robot-neck-links robot-neck-joints robot-joint-states robot-pose) - (<- (robot pr2)) - (<- (robot-odom-frame pr2 "odom_combined")) + (<- (robot-odom-frame :pr2 "odom_combined")) + + (<- (robot-base-frame :pr2 "base_footprint")) + (<- (robot-torso-link-joint :pr2 "torso_lift_link" "torso_lift_joint")) + + (<- (camera-frame :pr2 "head_mount_kinect_rgb_optical_frame")) + (<- (camera-frame :pr2 "openni_rgb_optical_frame")) + (<- (camera-frame :pr2 "narrow_stereo_optical_frame")) + + (<- (camera-minimal-height :pr2 1.27)) + (<- (camera-maximal-height :pr2 1.60)) - (<- (robot-base-frame pr2 "base_footprint")) - (<- (robot-torso-link-joint pr2 "torso_lift_link" "torso_lift_joint")) + ;; These are values taken from the Kinect's wikipedia page for the 360 variant + (<- (camera-horizontal-angle :pr2 0.99483)) ; ca 57 degrees + (<- (camera-vertical-angle :pr2 0.75049)) ; ca 43 degrees - (<- (camera-frame pr2 "head_mount_kinect_rgb_optical_frame")) - (<- (camera-frame pr2 "openni_rgb_optical_frame")) - (<- (camera-frame pr2 "narrow_stereo_optical_frame")) - (<- (camera-minimal-height pr2 1.27)) - (<- (camera-maximal-height pr2 1.60)) - (<- (robot-neck-links pr2 "head_pan_link" "head_tilt_link")) - (<- (robot-neck-joints pr2 "head_pan_joint" "head_tilt_joint")) + (<- (robot-neck-links :pr2 "head_pan_link" "head_tilt_link")) + (<- (robot-neck-joints :pr2 "head_pan_joint" "head_tilt_joint")) - (<- (robot-joint-states pr2 :neck ?_ :forward ((?pan_joint 0.0) (?tilt_joint 0.0))) - (robot-neck-joints pr2 ?pan_joint ?tilt_joint)) + (<- (robot-joint-states :pr2 :neck ?_ :forward ((?pan_joint 0.0) (?tilt_joint 0.0))) + (robot-neck-joints :pr2 ?pan_joint ?tilt_joint)) - (<- (robot-pose pr2 :neck ?_ :forward ?pose-stamped) - (robot-base-frame pr2 ?base-frame) + (<- (robot-pose :pr2 :neck ?_ :forward ?pose-stamped) + (robot-base-frame :pr2 ?base-frame) (lisp-fun cl-transforms:make-identity-rotation ?identity-quaternion) (symbol-value *forward-looking-position-in-base-frame* ?forward-point) (lisp-fun cl-transforms-stamped:make-pose-stamped @@ -69,9 +72,13 @@ costmap:costmap-manipulation-padding costmap:costmap-in-reach-distance costmap:costmap-reach-minimal-distance + costmap:orientation-samples + costmap:orientation-sample-step costmap:visibility-costmap-size) - (<- (costmap:costmap-padding 0.3)) - (<- (costmap:costmap-manipulation-padding 0.4)) - (<- (costmap:costmap-in-reach-distance 0.9)) - (<- (costmap:costmap-reach-minimal-distance 0.2)) - (<- (costmap:visibility-costmap-size 2))) + (<- (costmap:costmap-padding :pr2 0.3)) + (<- (costmap:costmap-manipulation-padding :pr2 0.4)) + (<- (costmap:costmap-in-reach-distance :pr2 1.0)) + (<- (costmap:costmap-reach-minimal-distance :pr2 0.2)) + (<- (costmap:orientation-samples :pr2 1)) + (<- (costmap:orientation-sample-step :pr2 0.3)) + (<- (costmap:visibility-costmap-size :pr2 2))) diff --git a/cram_pr2/cram_pr2_launch_files/CATKIN_IGNORE b/cram_pr2/cram_pr2_launch_files/CATKIN_IGNORE deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/cram_pr2/cram_pr2_launch_files/CMakeLists.txt b/cram_pr2/cram_pr2_launch_files/CMakeLists.txt deleted file mode 100644 index 0e07af6cf1..0000000000 --- a/cram_pr2/cram_pr2_launch_files/CMakeLists.txt +++ /dev/null @@ -1,5 +0,0 @@ -cmake_minimum_required(VERSION 2.8.3) -project(cram_pr2_launch_files) -find_package(catkin REQUIRED) -catkin_package() - diff --git a/cram_pr2/cram_pr2_launch_files/launch/gazebo_kitchen_and_pr2.launch b/cram_pr2/cram_pr2_launch_files/launch/gazebo_kitchen_and_pr2.launch deleted file mode 100644 index ddc1dcd4c7..0000000000 --- a/cram_pr2/cram_pr2_launch_files/launch/gazebo_kitchen_and_pr2.launch +++ /dev/null @@ -1,29 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/cram_pr2/cram_pr2_launch_files/launch/gazebo_localization.launch b/cram_pr2/cram_pr2_launch_files/launch/gazebo_localization.launch deleted file mode 100644 index 7c46052753..0000000000 --- a/cram_pr2/cram_pr2_launch_files/launch/gazebo_localization.launch +++ /dev/null @@ -1,45 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/cram_pr2/cram_pr2_launch_files/launch/nav_p_pr2.launch b/cram_pr2/cram_pr2_launch_files/launch/nav_p_pr2.launch deleted file mode 100644 index 934f43593f..0000000000 --- a/cram_pr2/cram_pr2_launch_files/launch/nav_p_pr2.launch +++ /dev/null @@ -1,39 +0,0 @@ - - - - - - slowdown_far: 0.20 - slowdown_near: 0.08 - safety_dist: 0.06 - repelling_dist: 0.10 - repelling_gain: 0.5 - repelling_gain_max: 0.015 - - vel_ang_max: 0.6 - vel_lin_max: 0.1 - acc_ang_max: 0.4 - acc_lin_max: 0.4 - loop_rate: 30 - p: 1.2 - - xy_tolerance: 0.05 - th_tolerance: 0.1 - - n_lasers: 1 - complete_blind_spots: false - - global_frame: map - odom_frame: odom_combined - base_link_frame: base_link - - speed_filter_name: /nav_pcontroller - footprint: - front: 0.33 - rear: -0.33 - right: -0.33 - left: 0.33 - tolerance: 0.0 - - - diff --git a/cram_pr2/cram_pr2_launch_files/launch/pr2_static_localization.launch b/cram_pr2/cram_pr2_launch_files/launch/pr2_static_localization.launch deleted file mode 100644 index 4814cc2a3a..0000000000 --- a/cram_pr2/cram_pr2_launch_files/launch/pr2_static_localization.launch +++ /dev/null @@ -1,6 +0,0 @@ - - - - - diff --git a/cram_pr2/cram_pr2_launch_files/launch/upload_maps_and_lowres_robot.launch b/cram_pr2/cram_pr2_launch_files/launch/upload_maps_and_lowres_robot.launch deleted file mode 100644 index 48e9756271..0000000000 --- a/cram_pr2/cram_pr2_launch_files/launch/upload_maps_and_lowres_robot.launch +++ /dev/null @@ -1,32 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/cram_pr2/cram_pr2_launch_files/package.xml b/cram_pr2/cram_pr2_launch_files/package.xml deleted file mode 100644 index 43587d978f..0000000000 --- a/cram_pr2/cram_pr2_launch_files/package.xml +++ /dev/null @@ -1,17 +0,0 @@ - - cram_pr2_launch_files - 0.7.0 - - cram_pr2_launch_files - - Gayane Kazhoyan - Gayane Kazhoyan - BSD - - catkin - - giskard_examples - nav_pcontroller - joint_trajectory_action - pr2_arm_kinematics - diff --git a/cram_pr2/cram_pr2_low_level/src/base-controller.lisp b/cram_pr2/cram_pr2_low_level/src/base-controller.lisp index 27c233c7b8..8bfd97bc50 100644 --- a/cram_pr2/cram_pr2_low_level/src/base-controller.lisp +++ b/cram_pr2/cram_pr2_low_level/src/base-controller.lisp @@ -304,7 +304,7 @@ with goal accuracy of 0.1 [m] navigation will have 12 [cm] error max.") (declare (type cl-transforms:point goal-point)) "Uses the current robot pose and calculates the angular velocity command to turn towards the `goal-point'. Clips the signal with certain maximal value." - (let* ((angle (cl-tf:normalize-angle + (let* ((angle (cl-transforms:normalize-angle (relative-angle-to goal-point (cpl:value *robot-base-frame-pose*)))) (direction (if (> angle 0) 1 -1))) (if (> (abs angle) *navigation-angular-velocity-max*) diff --git a/cram_pr2/cram_pr2_low_level/src/kinematics-trajectory.lisp b/cram_pr2/cram_pr2_low_level/src/kinematics-trajectory.lisp index 43034963d2..5fd6a3fce7 100644 --- a/cram_pr2/cram_pr2_low_level/src/kinematics-trajectory.lisp +++ b/cram_pr2/cram_pr2_low_level/src/kinematics-trajectory.lisp @@ -134,8 +134,9 @@ (roslisp:make-request "moveit_msgs/GetPositionIK" (:ik_link_name :ik_request) ik-link - (:pose_stamped :ik_request) (cl-tf:to-msg - (cl-tf:pose->pose-stamped ik-base-frame 0.0 cartesian-pose)) + (:pose_stamped :ik_request) (cl-transforms-stamped:to-msg + (cl-transforms-stamped:pose->pose-stamped + ik-base-frame 0.0 cartesian-pose)) (:joint_state :robot_state :ik_request) (make-zero-seed-state left-or-right) (:timeout :ik_request) 1.0)) (cond ((eql error-code @@ -170,8 +171,9 @@ (roslisp:make-request "moveit_msgs/GetPositionIK" (:ik_link_name :ik_request) ik-link - (:pose_stamped :ik_request) (cl-tf:to-msg - (cl-tf:pose->pose-stamped ik-base-frame 0.0 cartesian-pose)) + (:pose_stamped :ik_request) (cl-transforms-stamped:to-msg + (cl-transforms-stamped:pose->pose-stamped + ik-base-frame 0.0 cartesian-pose)) (:joint_state :robot_state :ik_request) (make-current-seed-state left-or-right) (:timeout :ik_request) 1.0))) (cond ((eql response-error-code diff --git a/cram_pr2/cram_pr2_low_level/src/ptu.lisp b/cram_pr2/cram_pr2_low_level/src/ptu.lisp index 16d540345b..5cc36ed262 100644 --- a/cram_pr2/cram_pr2_low_level/src/ptu.lisp +++ b/cram_pr2/cram_pr2_low_level/src/ptu.lisp @@ -118,7 +118,7 @@ (defun look-at-gripper (left-or-right) (call-ptu-action :pose - (cl-tf:make-pose-stamped + (cl-transforms-stamped:make-pose-stamped (ecase left-or-right (:left "l_gripper_tool_frame") (:right "r_gripper_tool_frame")) diff --git a/cram_pr2/cram_pr2_pick_place_demo/resource/bowl.dae b/cram_pr2/cram_pr2_pick_place_demo/resource/bowl.dae deleted file mode 100644 index 6aa795759c..0000000000 --- a/cram_pr2/cram_pr2_pick_place_demo/resource/bowl.dae +++ /dev/null @@ -1,63 +0,0 @@ - - - - - Blender User - Blender 2.79.0 commit date:2017-09-11, commit time:10:43, hash:5bd8ac9abfa - - 2017-10-25T18:06:46 - 2017-10-25T18:06:46 - - Z_UP - - - - - - - 0.06953394 0.03718966 0.0278238 0.0691601 0.03039228 0.02527147 0.07407033 0.02616602 0.02833718 0.07684761 0.02172911 0.02802979 0.0728181 0.03214913 0.02770376 0.0632326 0.04208612 0.02548915 0.06465184 0.04413431 0.02769911 0.0684939 0.03845155 0.02603691 0.06467711 0.04599577 0.02744853 0.07115334 0.02304655 0.02444523 0.07775086 0.01701629 0.02865159 0.07460933 0.01594746 0.02646762 0.07769441 0.01198869 0.02865999 0.07857304 0.01027983 0.02776193 0.05741274 0.05278813 0.0272445 0.06223839 0.03870415 0.02206528 0.06411194 0.03052461 0.01793742 0.07868921 0.006395578 0.0291171 0.07484829 0.003801703 0.02449953 0.06847399 0.01686799 0.01629936 0.05495142 0.05715727 0.02704381 0.05136436 0.05876177 0.02732294 0.04512435 0.05871683 0.02407699 0.05275779 0.05269539 0.02436709 0.05284637 0.04740905 0.01864773 0.08000588 0.003240823 0.0286858 0.07597756 -0.008265137 0.02669352 0.0792157 -0.008371829 0.02955216 0.04751265 0.0631178 0.02699488 0.04064595 0.06606495 0.02706986 0.03821665 0.06531602 0.02588582 0.05655604 0.04002952 0.01477587 0.0441693 0.05308771 0.01535284 0.05668509 0.02694678 -4.10885e-4 0.06050735 0.01985818 0.001124083 0.07278501 -0.01206773 0.02268344 0.07149004 -0.00332725 0.01840209 0.07022589 0.005331516 0.01600664 0.04700499 0.04181438 0.001156687 0.03478354 0.07090586 0.02682232 0.02920556 0.07222342 0.0269649 0.0316804 0.0651502 0.02177226 0.03651273 0.05891358 0.01623064 0.07403564 -0.02109748 0.02755808 0.07882803 -0.00699979 0.02760887 0.07811337 -0.01863741 0.0295614 0.05017787 0.03101658 -0.007394969 0.06276345 0.01031368 2.8429e-4 0.02815783 0.07016694 0.02580499 0.06933856 -0.03339546 0.02763777 0.0726791 -0.03391522 0.03028285 0.06853997 -0.02273589 0.01997733 0.06575351 -0.03127604 0.02107429 0.07407146 -0.03219968 0.0296806 0.0743556 -0.01545035 0.02228891 0.02644515 0.07304698 0.02547597 0.01819258 0.0754593 0.02580225 0.01612895 0.07481783 0.02655261 0.03232598 0.05135881 -0.002433896 0.03703451 0.04780304 -0.003139436 0.06383907 -0.001852333 1.85575e-4 0.06370484 -0.0140478 0.002869188 0.07015037 -0.0148046 0.0185824 0.0181148 0.07149797 0.02371424 0.05438196 0.02050387 -0.009458124 0.02681839 0.06272673 0.01430088 0.06384736 -0.04646378 0.03045809 0.06853264 -0.0426104 0.03029793 0.04182672 0.04037469 -0.007976412 0.05502808 0.01365494 -0.01213967 0.05800634 0.005897164 -0.009907305 0.06292134 -0.04173046 0.02613693 0.05815124 -0.00276643 -0.01041167 0.05763006 -0.010971 -0.01002192 0.06077575 -0.02345895 0.002391874 0.01553684 0.06888914 0.01928728 0.001768231 0.0746259 0.02482175 0.005929887 0.06983637 0.01851117 0.009326815 0.07788646 0.02664113 0.004071831 0.07744681 0.02685654 0.04485696 0.0289421 -0.01554638 0.02346271 0.05719709 4.83677e-4 0.01434087 0.06408184 0.009134769 0.05744028 -0.01879602 -0.007297337 0.04732906 0.0207014 -0.01795315 0.03403645 0.04357475 -0.01208633 0.02322554 0.04960852 -0.01234704 0.05710148 -0.03059035 0.001307845 0.05962955 -0.04006212 0.01885724 0.03769236 0.03487271 -0.01750165 0.04473942 0.01390576 -0.02306878 0.05113261 0.00414139 -0.01911729 0.05744707 -0.05541503 0.03109395 0.06024646 -0.05359256 0.03045117 0.05737763 -0.05076998 0.02790182 0.01471394 0.05717611 -0.004775464 0.05277293 -0.003568649 -0.01742202 0.003565132 0.05979806 -0.003014862 0.003024458 0.07748788 0.02555865 -0.004177033 0.07644087 0.02664184 -0.005632698 0.07876211 0.02640765 0.03870046 0.02389675 -0.02376514 -0.004540264 0.06914407 0.01702409 -0.009399831 0.07084196 0.02058327 0.02701157 0.04042565 -0.02010571 0.04956614 -0.01312196 -0.01955199 0.0510503 -0.03043317 -0.009252905 0.04853779 -0.02316397 -0.01685661 0.05179888 -0.03777772 -4.15714e-4 0.05414533 -0.04774659 0.01979076 0.04635691 -0.05543828 0.0201317 0.04937463 -0.05841207 0.02812027 0.04683393 -0.06383895 0.03100258 0.03317242 0.02911204 -0.02459692 -0.009725689 0.07997167 0.02723562 -0.01599627 0.07581216 0.02667403 -0.02193748 0.07129645 0.02445989 0.05258494 -0.06107747 0.03095406 0.04694819 -0.002247214 -0.02342689 0.01490473 0.05223864 -0.01256918 0.01209235 0.04708361 -0.01983207 0.04094731 0.008585393 -0.02672809 0.03416568 0.01811563 -0.02823495 0.006482839 0.05388677 -0.01246851 -0.008739531 0.05936127 -0.003023743 -0.01543599 0.06801682 0.0177114 0.04728972 -0.04481434 0.002219915 0.04257303 -0.04268527 -0.007671117 0.04222869 -0.05128026 0.005250334 -0.01536244 0.07716488 0.02651095 -0.009564936 0.07697743 0.02461379 0.02481251 0.0346896 -0.02540874 0.01621615 0.04026591 -0.0245859 -0.003258109 0.05786436 -0.006562054 -0.02206265 0.07587319 0.02694374 -0.02598446 0.07322204 0.02675473 0.03920543 -0.06568974 0.02842032 0.03651231 -0.06220608 0.02022308 0.02565938 0.0271719 -0.02879643 0.04114151 -0.01453584 -0.02608096 0.04153496 -0.02224063 -0.02362257 0.04277771 -0.03384035 -0.01614987 0.04426968 -0.06756746 0.03145033 0.04678785 -0.06499952 0.03044062 0.02992242 -0.07290428 0.03137844 0.03744828 0.004589855 -0.02872401 0.04084241 -0.00491321 -0.02735161 0.0374369 -0.04868131 -0.005784571 0.01555901 0.03315299 -0.02901089 0.0298748 0.0112254 -0.02999931 -5.45622e-4 0.04714 -0.02125328 0.006221592 0.03938949 -0.02722829 -0.01834124 0.05944645 0.001390814 -0.01884591 0.05353903 -0.00893557 -0.01073837 0.05230462 -0.0138424 -0.03334408 0.07077306 0.02713626 -0.03683596 0.06574535 0.02493578 -0.0243631 0.06484287 0.01649194 -0.002446472 0.05338597 -0.01364231 -0.02610695 0.0739668 0.02599889 0.03245812 -0.05464088 -0.001463651 0.02691417 -0.07108032 0.02805936 0.03496986 -0.07228201 0.03107392 0.04360437 -0.06074845 0.0212264 0.0362451 -0.06722742 0.02442669 0.01932448 0.02682554 -0.03018003 0.03471243 -0.01048135 -0.02891951 0.03468334 -0.02222061 -0.02730745 0.03159749 -0.03207206 -0.02494388 0.0365861 -0.03714567 -0.01888847 -0.03181141 0.07309293 0.0271787 0.03544735 -0.04503369 -0.01238161 0.02567476 -0.05984139 0.002226054 0.02545142 -0.06727707 0.02003312 0.01803338 0.01881712 -0.03064042 0.02797275 -0.001962423 -0.02964633 -0.02786934 0.05398255 -0.002267181 0.01634925 -0.07488393 0.02906382 0.0152536 -0.07814782 0.03182047 0.02006858 -0.07755643 0.03140169 0.02256029 -0.07645565 0.03035473 0.00230211 0.03397494 -0.03014415 1.4959e-4 0.0298286 -0.03093165 -0.01101797 0.04537457 -0.02158468 -0.007080137 0.03768366 -0.02814656 -0.03378552 0.06006616 0.01519155 -0.04047453 0.06133723 0.02281808 0.02753174 -0.05050742 -0.01200801 -0.03563493 0.07019686 0.02639746 -0.04132413 0.06640535 0.02723085 0.0290113 -0.01775723 -0.028943 0.00932902 -0.003438949 -0.02927041 -0.006738781 0.02001619 -0.03084695 -0.001453101 0.005738139 -0.02983164 0.02391928 -0.0316565 -0.02757954 0.02883344 -0.04196476 -0.02019977 0.02178305 -0.05529111 -0.009019136 -0.04924404 0.05729794 0.02527791 0.01787775 -0.07056313 0.0221247 -0.01818257 0.04773473 -0.0169357 -0.0132575 0.03053057 -0.03022038 0.01133918 -0.02964907 -0.02858126 -0.04370242 0.05490523 0.0172339 -0.05051451 0.06022411 0.02740764 -0.0459876 0.06463772 0.02695798 0.0165112 -0.0619542 -4.39693e-5 0.0207743 -0.03829485 -0.02570772 -0.02095043 0.02045989 -0.03087323 -0.02620083 0.04754519 -0.01316303 0.01788681 -0.04530215 -0.02217972 0.01771456 -0.05092388 -0.01676523 -0.03646683 0.04827409 -0.003513813 -0.01547008 0.03644263 -0.02752113 -0.02223747 0.04224622 -0.02089571 -0.008789956 -0.01042771 -0.02937567 0.009715318 -0.03966206 -0.02703958 0.0108022 -0.07312172 0.0245285 0.004414379 -0.07119137 0.01863193 0.009576737 -0.06519365 0.004537463 0.003512799 -0.07526278 0.02724325 4.66009e-4 -0.07875961 0.03156381 0.01057857 -0.07957887 0.03133386 -0.007365942 -0.08002823 0.03142863 -0.01811766 0.00484538 -0.03031617 0.0105763 -0.05485528 -0.01434719 0.006743729 -0.05850887 -0.0100584 -0.05878585 0.0563963 0.02778357 -0.05793017 0.05400675 0.02805256 -0.05271786 0.05979263 0.02694064 -0.05721563 0.04851067 0.02463936 -0.05248987 0.04641777 0.01632958 -0.02569943 0.03524744 -0.02475917 -0.02977091 0.02554702 -0.0280708 -0.03291249 0.04148006 -0.01554578 -0.04499757 0.04358416 2.87177e-4 0.001842737 -0.06416863 1.8597e-4 0.00679785 -0.04779589 -0.02236086 -0.04373705 0.03713285 -0.009882628 -0.0302847 0.003477454 -0.03035145 -0.03076928 0.01571202 -0.02998119 1.76659e-4 -0.03378969 -0.0284956 -0.01431411 -0.02579683 -0.029127 -0.009710967 -0.07572269 0.02864539 -0.004257082 -0.07196718 0.02064239 -0.04243165 0.03158599 -0.01621651 -0.03448635 0.03098875 -0.02268069 -0.05987489 0.05122727 0.02656763 -0.06240844 0.04686552 0.02764064 -0.01438105 -0.07854872 0.03189063 -0.00481677 -0.03813499 -0.0278576 -0.001188278 -0.04547506 -0.02435535 -2.65996e-4 -0.05246937 -0.01821696 -0.05949676 0.03786849 0.01678347 -0.05103844 0.03615403 -6.86531e-4 -0.06423318 0.03889518 0.0247634 -0.006942689 -0.05530548 -0.01439601 -0.007756173 -0.06235241 -0.002807497 -0.06854474 0.03871101 0.0281769 -0.027121 -0.009916543 -0.02991664 -0.01372706 -0.07018548 0.01908004 -0.02039188 -0.0747776 0.03012263 -0.02867454 -0.07039803 0.02775722 -0.02523952 -0.06747341 0.02002048 -0.04061818 0.02198547 -0.02331548 -0.03859078 0.01195734 -0.02764117 -0.05380624 0.024971 -0.007692515 -0.06720042 0.04301834 0.02781528 -0.05590975 0.03220427 0.00315839 -0.06637561 0.02847313 0.01981413 -0.07325625 0.02338135 0.02653819 -0.07250285 0.03248798 0.02770817 -0.0221849 -0.07716548 0.031174 -0.03085124 -0.07433164 0.03155821 -0.01350349 -0.04190927 -0.02546191 -0.01950925 -0.03000009 -0.02864676 -0.02200418 -0.03712272 -0.02619886 -0.04793721 0.02364271 -0.01601707 -0.03564816 -0.001473188 -0.02944809 -0.009134352 -0.04910445 -0.0207681 -0.0188049 -0.06269943 0.003208875 -0.0596975 0.02140855 -2.84615e-4 -0.01232844 -0.05907893 -0.007390439 -0.02864515 -0.022237 -0.02875339 -0.01667737 -0.05300992 -0.01465821 -0.06917101 0.0203588 0.01924318 -0.02922564 -0.07311153 0.03115648 -0.04753035 0.01288706 -0.02116328 -0.01920509 -0.04506254 -0.02170509 -0.05378049 0.01597732 -0.0131033 -0.0784406 0.01377832 0.02890872 -0.07582306 0.008234858 0.02606815 -0.07167673 0.007273077 0.01865053 -0.03737074 -0.06246405 0.021299 -0.04338008 -0.06132328 0.02570152 -0.04490035 0.001739621 -0.0249629 -0.04102873 -0.004156231 -0.0272578 -0.06131714 0.01324677 -0.002340435 -0.02050894 -0.05737495 -0.006378054 -0.02522587 -0.0605393 0.003268003 -0.07830083 0.01785075 0.02846848 -0.06904399 0.02636247 0.0185098 -0.06380546 0.0364995 0.01819568 -0.03927749 -0.06850665 0.03129112 -0.05146503 0.003423571 -0.01918423 -0.02782255 -0.05205637 -0.01004141 -0.02686709 -0.04570204 -0.0179674 -0.06540411 0.008831262 0.004658699 -0.0375626 -0.01844376 -0.02689474 -0.04034131 -0.0678007 0.028337 -0.03562039 -0.0655232 0.02076476 -0.02662765 -0.07167506 0.02456068 -0.04683637 -0.06556046 0.03121221 -0.03476005 -0.05540788 0.002385973 -0.07999408 0.003974497 0.02865225 -0.07904857 -0.003527104 0.02897739 -0.07632046 -0.004544973 0.02640908 -0.03283935 -0.0290277 -0.02582573 -0.03357571 -0.03673374 -0.02121764 -0.05775213 0.006406545 -0.01073437 -0.04731309 -0.05378741 0.01828449 -0.0502035 -0.06104826 0.0306549 -0.05029308 -0.01032847 -0.01966965 -0.04442983 -0.01386982 -0.02386248 -0.03847384 -0.04175627 -0.01339787 -0.06190288 0.002845585 -0.004293799 -0.03650462 -0.05016481 -0.004837393 -0.07219564 -0.00553584 0.01929372 -0.06379622 -0.005139768 -7.48972e-4 -0.05387735 -0.05398452 0.02737593 -0.04459112 -0.04636734 -5.12193e-4 -0.04447156 -0.02304208 -0.0210343 -0.04086565 -0.0322104 -0.01900321 -0.05428814 -0.003232598 -0.01603949 -0.05822271 -0.004428267 -0.01084375 -0.05628967 -0.05646204 0.03081363 -0.0538789 -0.0594235 0.0302301 -0.07922101 -0.007713258 0.02951288 -0.07580608 -0.01649051 0.02854222 -0.05427932 -0.04724061 0.01878762 -0.05728751 -0.01488554 -0.009884178 -0.04956269 -0.02373027 -0.01595312 -0.04592251 -0.03701519 -0.0103932 -0.06336098 -0.01366227 8.68164e-4 -0.07013767 -0.01834404 0.01944565 -0.07966578 -0.004171013 0.02829581 -0.06210625 -0.04588663 0.02839624 -0.05170357 -0.03941035 0.001073658 -0.06104266 -0.03923636 0.01979601 -0.07873207 -0.01451635 0.02916753 -0.07393121 -0.02275532 0.02864098 -0.06152981 -0.0518698 0.03035819 -0.05253273 -0.03074645 -0.007300078 -0.05634403 -0.02372348 -0.006653904 -0.0621795 -0.02077311 0.00241661 -0.05885148 -0.02949666 0.002886712 -0.06587368 -0.03397274 0.02348446 -0.06814599 -0.03523874 0.02763777 -0.06712549 -0.04161483 0.0303198 -0.06613075 -0.04578679 0.03069168 -0.07329767 -0.03367215 0.03045815 -0.06994301 -0.03863978 0.03020292 -0.07452565 -0.02401572 0.02850705 -0.06670266 -0.0413559 0.02658361 -0.06714415 -0.03546714 0.02238541 -0.07288604 -0.02605456 0.02552509 0.07127112 0.01849555 0.01826286 0.06142348 0.03963619 0.01792627 0.05438721 0.04997569 0.01959931 0.04765868 0.05561536 0.0190491 0.04132008 0.06132429 0.02023601 0.03099334 0.06669682 0.01980829 0.07122415 -0.02709513 0.02301299 0.06766849 -0.03286284 0.02148342 0.008519411 0.07328808 0.02047699 0.05809754 -0.04763549 0.02129095 0.06302094 -0.04057079 0.02086657 -3.26097e-4 0.07291287 0.01917964 -0.03510725 0.0658639 0.02095478 -0.02263915 0.06977266 0.0195021 -0.04612636 0.0580967 0.02009481 -0.05569779 0.05511283 0.02532809 -0.06013405 0.04376405 0.0197826 -0.07413429 0.003341376 0.0184139 -0.07433199 -0.006726026 0.01920479 -0.04217505 -0.06173813 0.02090919 -0.05036509 -0.05543249 0.02075195 -0.0728026 -0.01565092 0.01894855 -0.05952864 -0.04509621 0.01990526 0.02344477 -0.07112413 0.02183091 -0.07276678 0.01358073 0.01845693 0.04952073 -0.05547201 0.01984947 -0.01718419 -0.07268255 0.02161943 -0.002843499 -0.07479113 0.02198863 0.06790596 0.02734172 0.01779478 0.07354956 0.0068506 0.01852756 0.07368373 -0.005577743 0.01853513 0.0628131 0.03481966 0.01510912 0.05705982 0.0303604 -0.001061856 0.05146837 0.0351817 -0.005210161 0.05095952 0.04785674 0.01170754 0.06175661 0.02248215 6.72711e-4 0.06500709 0.01045805 1.72292e-4 0.06599038 -7.26266e-4 1.29753e-4 0.03966981 0.04906654 -0.002468585 0.03460919 0.06050384 0.01234126 0.07099425 -0.01870417 0.01737332 0.06381136 -0.01016634 -0.003441095 0.04656052 0.0425527 -0.003169 0.05596321 0.02115249 -0.0105865 0.05004274 0.02825295 -0.01360976 0.06038951 0.009785115 -0.009123623 0.01959794 0.07058626 0.01955944 0.02578371 0.06455999 0.01254999 0.01743966 0.06800466 0.01418125 0.03344732 0.05158954 -0.005307435 0.02500247 0.05533427 -0.006236374 0.06374275 -0.01949149 8.39898e-4 0.06053078 -0.02653652 -7.12526e-4 0.04513508 0.03567111 -0.01294976 0.03503185 0.04486596 -0.01330137 0.05984413 -0.002809286 -0.01157605 0.05786794 -0.01563805 -0.01197206 0.05125534 0.01361113 -0.01987403 0.04869961 0.02134054 -0.01934128 0.05672013 0.00847733 -0.01480376 0.01674711 0.05963963 -0.003640413 0.04277366 0.02736705 -0.0216121 0.005160689 0.06323337 -3.6177e-4 0.00605297 0.06962209 0.01358628 0.0387938 0.03535139 -0.01935428 0.0510748 -0.007056117 -0.02215152 0.05389833 0.001525104 -0.01927191 0.05737847 -0.0318765 -0.001695275 0.05376511 -0.02739191 -0.01140058 0.05384218 -0.04245543 0.004868209 0.02721679 0.04191768 -0.02164852 0.02268624 0.0506947 -0.01463299 0.004637897 0.05873799 -0.008819699 0.01262372 0.05535614 -0.0124576 0.04536271 -0.04933267 0.001416146 0.03138422 0.03220629 -0.02641284 0.04309105 0.0129233 -0.02729171 0.04744857 0.00695765 -0.02502959 -0.005422234 0.06907445 0.01243388 0.03585678 0.02177941 -0.02893745 0.05224418 -0.01994502 -0.01740926 -0.01195889 0.07248491 0.01992094 -0.006411314 0.06138795 -0.003990828 0.05151575 -0.03745311 -0.005808889 0.0442453 -0.002111017 -0.02789252 0.03792375 0.006255745 -0.03068917 0.02078765 0.03709965 -0.02793991 0.01824218 0.04689514 -0.02087372 0.0124405 0.04106754 -0.02757745 0.008645892 0.05211412 -0.01799792 0.04761958 -0.01847153 -0.02268296 0.04406911 -0.01231771 -0.02699792 0.02712839 0.02923315 -0.02978575 0.02595126 0.01796364 -0.03233444 0.02382153 0.02594149 -0.03166782 0.0466367 -0.03643423 -0.01327842 0.04604077 -0.02647 -0.0207628 -0.0160371 0.06831645 0.01408684 0.0416224 -0.04509776 -0.01002728 0.03776371 -0.05475038 1.78409e-4 0.03260809 -0.06530469 0.0169816 0.005365192 0.04561179 -0.02509117 0.03815352 -0.008053779 -0.0304383 -0.002616763 0.05465078 -0.01535743 -0.004713952 0.04820042 -0.02270108 0.03950405 -0.0188452 -0.02831506 -0.01735937 0.05979609 -0.003157317 -0.01103174 0.05385076 -0.01511538 0.01351022 0.03244102 -0.03185582 0.0422784 -0.03349035 -0.01992553 0.03810429 -0.02868789 -0.0256223 -0.02834439 0.06423646 0.0135895 0.02945333 0.0054304 -0.03207188 0.03157436 -0.004903554 -0.03155809 0.03518289 -0.04358828 -0.01756513 0.004698574 0.03637921 -0.03118759 -0.003730595 0.04072141 -0.02896326 0.002465307 0.02570658 -0.0331093 0.002992689 0.02959984 -0.03299909 0.03220742 -0.02498811 -0.02959573 0.02918624 -0.01824462 -0.03097039 0.03139346 -0.03533822 -0.02594673 0.03028625 -0.051081 -0.0130769 0.01126003 -0.004031419 -0.03132498 0.02752864 -0.05825233 -0.004315733 -0.01939004 0.055157 -0.01001083 -0.02847129 0.05545657 -0.003588259 -0.03763657 0.06020265 0.01485574 0.02100992 -0.06400066 0.002607762 -0.01617914 0.04242265 -0.02571684 -0.01655018 0.04922688 -0.01907908 0.02142828 -0.03780895 -0.02818083 0.01707488 -0.03388786 -0.02992194 0.02575075 -0.04470896 -0.02228003 -0.00711131 0.03191214 -0.03257745 0.01249122 -0.02959996 -0.03063321 0.01675522 -0.07183778 0.01948261 0.008111834 -0.07421571 0.0216059 -0.01607441 0.0357654 -0.03004658 -0.003394067 0.002179145 -0.03173714 -0.01428484 0.01995277 -0.0330224 0.01786339 -0.0530498 -0.01749885 0.01358062 -0.06104606 -0.007798016 -0.0272836 0.04855042 -0.01472288 -0.03681957 0.05104094 -0.002994298 -0.0358619 0.04731899 -0.009487807 -0.002864837 -0.01584255 -0.03117716 -0.02512186 0.04162716 -0.02291339 -0.04366576 0.05507844 0.01278132 0.01602727 -0.04640758 -0.02429884 -0.0504148 0.05218017 0.01706218 0.009030759 -0.06603807 8.15659e-4 -0.02526813 0.02050751 -0.03249037 -0.02006697 0.02835279 -0.03190308 -0.02784067 0.03202068 -0.02828365 -0.007850289 -0.03038084 -0.03090977 0.003678917 -0.03698247 -0.03008985 0.009924352 -0.04130005 -0.02846473 -0.03484261 0.04111474 -0.01758146 -0.04499119 0.03827416 -0.01101261 -0.04625159 0.04483085 -7.18411e-4 -0.02781563 -0.005949854 -0.03220951 -0.02643603 0.008533775 -0.03273183 -0.01939511 -0.02065294 -0.03145527 0.005132734 -0.05181527 -0.02163028 0.006194531 -0.05680233 -0.01590251 -0.00120151 -0.0591734 -0.01311743 8.95446e-5 -0.06495225 -0.002795636 -0.05631291 0.04253911 0.01241672 -0.03179788 0.03494769 -0.02447032 0.002389252 -0.04774606 -0.02530372 -0.00838375 -0.06674736 0.002305567 -0.03120356 0.02212357 -0.03076636 -0.04458647 0.03333169 -0.01595377 -0.04157179 0.02607482 -0.02347993 -0.0371235 0.02107352 -0.02851116 -0.006647765 -0.04440778 -0.02730959 -0.05257016 0.03679758 -0.002000749 -0.008398711 -0.07307457 0.01884782 -0.03485405 0.008227467 -0.03168767 -0.008729338 -0.03780472 -0.02979975 -0.02231144 -0.02833384 -0.03078562 -0.007327556 -0.052356 -0.02079063 -0.05536627 0.02572757 -0.008778214 -0.00699824 -0.06181317 -0.008152484 -0.03354406 -0.01785916 -0.03053033 -0.03569322 -0.005769014 -0.03124588 -0.04932594 0.02434968 -0.01734739 -0.05956298 0.02915942 0.001795053 -0.01508426 -0.05659776 -0.01398366 -0.01932859 -0.06446355 0.00241506 -0.0185067 -0.06039828 -0.006592988 -0.04739809 0.0150392 -0.0233255 -0.01747876 -0.03886938 -0.02861332 -0.02306246 -0.04094856 -0.02606254 -0.01633197 -0.04981708 -0.02128493 -0.02787637 -0.06775766 0.01777523 -0.04036682 0.009170532 -0.0294016 -0.04203408 -0.003543615 -0.02908694 -0.06260854 0.01807337 -0.001696109 -0.05537664 0.01648592 -0.01429027 -0.06983661 0.02081406 0.01605069 -0.03015828 -0.03079986 -0.02849072 -0.06074297 0.009920597 -0.009027302 -0.02735573 -0.05346006 -0.01203197 -0.02810287 -0.04708158 -0.01902371 -0.03107261 -0.05613416 -0.004961967 -0.02833998 -0.06121677 0.002359926 -0.04688072 0.002693176 -0.02597224 -0.05236256 0.008366346 -0.02036774 -0.06495469 0.005243837 -0.002628743 -0.03452372 -0.03769344 -0.02275615 -0.04142987 -0.05380392 0.002892792 -0.05486953 0.001663267 -0.0186668 -0.04681575 -0.009101212 -0.02547276 -0.05214095 -0.01061332 -0.02068966 -0.03810727 -0.04435676 -0.01450037 -0.03673154 -0.05241334 -0.005455672 -0.04126918 -0.01769655 -0.02758324 -0.03955256 -0.02810949 -0.02510005 -0.06548649 -0.005358517 -0.001934885 -0.05983322 -0.005319535 -0.01210433 -0.05392885 -0.05002593 0.01746588 -0.05043584 -0.04463291 0.001416981 -0.04590034 -0.04329222 -0.007518231 -0.04760837 -0.01997154 -0.02232313 -0.04563599 -0.03526085 -0.01574128 -0.04859489 -0.02830106 -0.01738882 -0.05493277 -0.01944082 -0.01483386 -0.06528943 -0.01341044 -6.38537e-5 -0.05993914 -0.01525878 -0.009398519 -0.05313807 -0.0378459 -0.003296196 -0.06332987 -0.03775459 0.01728922 -0.05637317 -0.02678442 -0.008738517 -0.06407517 -0.02140939 0.001853466 -0.07028043 -0.02582883 0.02033585 -0.05841082 -0.03100401 -0.001532912 - - - - - - - - - - -0.6521345 -0.2347947 0.7208274 0.2024679 0.1087474 0.9732322 0.4625782 0.2302312 0.856163 -0.5152622 -0.2762853 0.8112776 -0.5696126 -0.3874288 0.7248728 0.8325726 0.5448499 -0.09980803 0.865701 0.4701376 -0.1718502 0.1593804 0.1296095 0.9786722 -0.6619215 -0.2587342 0.7035032 0.4122294 0.1963958 0.8896604 -0.5193969 -0.1802205 0.8353128 -0.7234955 -0.1609793 0.6712973 -0.5725858 0.00779587 0.8198078 0.7082921 -0.00678122 0.7058869 0.9560127 0.1499759 -0.2520854 0.09530985 0.1315612 0.9867157 -0.5412899 -0.4143631 0.7316479 -0.7482751 -0.4274295 0.5073347 -0.7213466 -0.3764675 0.5813186 -0.7939729 -0.2763468 0.541516 -0.616792 -0.04548007 0.7858113 -0.7276461 -0.1236456 0.674717 -0.8559415 -0.09907376 0.5074923 -0.8350414 -0.2699444 0.4794121 0.8585972 0.1915786 0.4755087 0.1294664 0.1181626 0.9845182 -0.440496 -0.5232751 0.7294837 -0.4142128 -0.429929 0.80224 0.03135323 0.06348633 0.9974901 -0.4786734 -0.389379 0.7869281 -0.6404095 -0.4452759 0.6257836 -0.6350746 -0.5721365 0.5189799 -0.8030456 -0.317021 0.5045944 0.75994 0.2342644 0.6063097 -0.6618323 -0.00151056 0.7496504 0.3988397 0.04120606 0.9160944 -0.7792993 0.04076862 0.6253243 0.06888061 0.1353425 0.9884017 -0.2965493 -0.405259 0.864768 -0.3707355 -0.585641 0.7208189 0.1766078 0.2282689 0.9574462 -0.6921516 -0.576079 0.4348096 -0.749141 -0.4271159 0.5063199 -0.5946894 -0.5949636 0.5407059 -0.5498036 -0.6731649 0.4945353 -0.8370941 -0.3626844 0.4095529 -0.8628161 -0.3223021 0.3894482 -0.7759496 -0.4811605 0.4079053 -0.7976999 0.03481549 0.6020488 -0.9061363 0.07007479 0.4171409 -0.8780056 0.004229724 0.4786319 -0.8797789 -0.1450889 0.452701 -0.6032406 -0.6788753 0.418604 -0.704103 -0.5735883 0.4186114 0.05231094 0.1140833 0.9920931 -0.263133 -0.4744981 0.8400075 0.06767189 0.1325205 0.9888675 -0.4453114 -0.7623323 0.4696244 -0.409379 -0.6135926 0.6752133 -0.4823793 -0.7110424 0.5115944 -0.6516866 0.1487259 0.7437643 -0.8411342 0.1620493 0.5159782 0.9640654 -0.08438938 -0.2519058 -0.4648542 0.05071133 0.8839339 0.9589381 -0.1032098 -0.2641693 -0.7156517 -0.5506204 0.4297208 -0.7605189 -0.4951292 0.4200694 -0.8776407 -0.2437645 0.4127054 -0.9107998 -0.1480911 0.3853739 -0.2008652 -0.4016215 0.8935062 -0.3540267 -0.7242438 0.591723 -0.582485 0.2275327 0.7803462 -0.5371616 0.2293989 0.8116856 -0.8142552 0.1843806 0.5504474 -0.7975844 0.3254654 0.5078695 -0.7907218 0.3054478 0.5305287 0.5477684 -0.156024 0.8219528 0.8544046 -0.1365813 -0.5013366 0.8125715 -0.2468104 -0.5280267 0.2809173 0.95968 0.009987592 0.2311575 0.9670868 0.1063454 0.09626191 0.6101751 0.7863969 -0.1158365 -0.4425368 0.8892374 -0.5088924 -0.7556721 0.4122962 -0.5935739 -0.6837674 0.42442 -0.5192055 -0.7453636 0.4181613 -0.9224282 -0.02812033 0.3851435 -0.9102505 -0.08376753 0.4054961 -0.9173308 0.1130712 0.3817319 -0.8678027 0.1089093 0.4848271 -0.9148843 0.09634172 0.3920522 -0.8818787 0.2494272 0.4000951 -0.2325924 -0.7086479 0.6661223 -0.2330177 -0.7034075 0.6715062 -0.8214443 -0.3445202 0.4544614 -0.7746146 -0.4050869 0.4856715 -0.4009669 -0.7622247 0.5081725 -0.3169824 -0.8220999 0.4729416 0.05379688 -0.02392387 0.9982653 -0.534706 0.3868201 0.7513054 0.6829253 -0.324532 0.6544402 -0.5941327 -0.6715685 0.4427214 -0.6724218 -0.5707871 0.471223 -0.8416907 -0.2638556 0.4711021 -0.85152 -0.242195 0.4650328 -0.8555637 -0.1898673 0.4816235 -0.8889448 -0.08225119 0.4505688 -0.4033705 -0.8131514 0.4196158 -0.8921345 0.2476001 0.377876 -0.68144 0.4162495 0.6019768 -0.7130141 0.4525157 0.5355749 -0.8787915 -0.04237025 0.4753213 -0.8812093 0.07812756 0.4662255 -0.8891837 0.107645 0.4447079 -0.8682571 0.3307853 0.3697442 -0.8879356 0.2570093 0.3814663 -0.1812409 -0.7974686 0.5754961 -0.1212146 -0.8275523 0.5481462 -0.1259398 -0.8208562 0.5570766 -0.07941365 -0.6748026 0.7337132 0.03654199 0.05221724 0.9979671 -0.09444123 -0.5305165 0.8423973 0.1964821 0.4098401 0.8907447 -0.6384256 -0.5353693 0.5529851 -0.7180269 -0.3990563 0.5702556 -0.3974656 -0.8145571 0.4225139 -0.2742369 -0.8562544 0.4377472 -0.2656481 -0.8710714 0.413117 -0.8727509 0.1792678 0.4540582 -0.8721041 0.2500967 0.4205783 -0.7144755 -0.3849645 0.5842321 -0.7359953 -0.3058936 0.6039371 -0.541537 -0.6753513 0.500638 -0.4724968 -0.7250798 0.5010052 -0.3677706 -0.7974112 0.4784143 -0.4254713 -0.7398043 0.5212138 -0.8437694 0.376603 0.3823918 -0.8038011 0.4673821 0.3680462 -0.7812801 0.4305142 0.4519501 -0.5523854 -0.5952323 0.5835828 -0.6080923 -0.5440058 0.5781708 -0.7113735 -0.229083 0.6644313 -0.7159852 -0.1978611 0.6694896 -0.7834319 -0.1256222 0.6086491 -0.1231383 -0.8912329 0.43651 0.3201892 -0.1626427 0.9332879 0.05971091 -0.0311318 0.9977302 -0.5733416 0.4581981 0.6792158 -0.5807651 0.4839735 0.654585 -0.7960195 -0.04843848 0.6033298 -0.7208615 0.5294184 0.4472972 -0.2930239 -0.8205638 0.4907262 -0.2532268 -0.8691906 0.4247163 -0.7910603 -0.03399407 0.6107929 -0.7952668 0.07907301 0.6010808 -0.1398735 -0.8883796 0.4372837 -0.1307115 -0.8929465 0.4307683 -0.07911831 0.9923023 0.09526997 0.05422598 -0.6128999 0.7882978 -0.03547561 0.07826972 0.9963008 0.1374962 0.9872915 -0.07968914 -0.6094219 -0.3852096 0.692978 -0.561127 -0.4485288 0.6956713 -0.8190749 0.3533005 0.4519901 -0.030707 -0.8058319 0.5913478 -1.03966e-4 -0.9062952 0.4226455 0.0880233 -0.8470088 0.5242404 -0.01289522 -0.7287906 0.6846153 -0.4698653 -0.6002072 0.6472851 -0.3956956 -0.6824197 0.6145961 -0.7710497 0.1193648 0.6254875 -0.7681152 0.2270869 0.5986907 -0.8058025 0.363967 0.46713 -0.7616121 0.3238775 0.5612936 -0.7626566 0.2393823 0.6008753 -0.786116 0.489467 0.3774176 -0.7677616 0.4592986 0.4467515 -0.7357276 0.569584 0.366441 -0.6865367 0.5480133 0.4778587 -0.6035091 0.6453954 0.4682323 -0.6063556 0.6351899 0.4784002 -0.534943 0.5778256 0.6164038 -0.4126427 0.5117046 0.7535811 -0.4508234 -0.5304768 0.7178806 -0.5362098 -0.4549712 0.7109714 -0.6077814 -0.3166072 0.7282595 0.0106467 -0.1495344 0.9886992 0.264602 0.2596347 0.9287495 0.02734333 -0.4688526 0.8828531 0.1553506 -0.7886494 0.5948937 0.03446042 -0.054246 0.9979329 0.4455764 -0.402354 0.799733 -0.6325193 -0.103509 0.7675971 -0.7177462 4.04909e-4 0.6963047 -0.2715512 -0.8159976 0.5103019 -0.2508256 -0.7409099 0.6230081 -0.2933081 -0.684674 0.667227 -0.6135999 -0.1012657 0.7830967 -0.4979158 -0.221751 0.8383951 -0.5028476 -0.2461889 0.8285744 -0.1573094 -0.8359681 0.5257481 -0.1230684 -0.8580725 0.4985639 0.03166955 -0.9008564 0.4329604 0.1201567 -0.8222452 0.5563049 0.11949 -0.9019055 0.4150768 -0.7096277 0.5956828 0.3762854 -0.6679192 0.595309 0.4466446 -0.6794642 0.5349537 0.5021484 -0.6432913 0.6738558 0.3634483 -0.6456608 0.6700225 0.3663223 -0.427762 -0.3184974 0.845919 -0.7065632 0.0804221 0.7030653 -0.2328127 0.2231749 0.9465681 0.04307532 0.6594669 -0.7504984 -0.2214524 0.6356571 -0.7395261 -0.4211245 -0.5233851 0.7407578 -0.2805323 -0.6573678 0.6994064 -0.3046332 -0.5809847 0.7547553 0.03170984 -0.9019465 0.4306821 -0.03058636 -0.8517054 0.5231276 0.1353617 -0.8336054 0.5355178 0.04267501 -0.1337187 0.9901001 0.1612502 -0.5973476 0.7856044 0.04519146 0.09865182 0.9940953 -0.506982 0.7274785 0.462325 -0.5260145 0.7700229 0.361073 -0.4962854 0.7282843 0.4725493 -0.3842036 0.5669004 0.7287055 -0.3591442 -0.4167608 0.8350605 -0.3978199 -0.3203572 0.8597155 -0.1452407 -0.7794077 0.6094495 -0.6206984 0.2093828 0.7555742 -0.653527 0.2579275 0.711601 -0.6208136 0.1262435 0.7737268 -0.678018 0.4063487 0.6125132 -0.6617425 0.5267415 0.5335171 0.637247 -0.35618 0.6834121 0.2150509 -0.4324911 0.8756167 -0.3728398 0.7198142 0.5855409 -0.06571769 0.163415 0.9843662 -0.5201206 -0.0627591 0.8517841 -0.4902887 -0.006004035 0.8715395 -0.5661865 0.09059143 0.8192839 -0.6168558 0.3784857 0.6900997 -0.6071767 0.6731198 0.422192 -0.6121122 0.660929 0.4341562 -0.2675616 -0.4207555 0.8668192 -0.2421317 -0.4962856 0.8337103 -0.3797464 -0.1253027 0.9165653 -0.2451756 -0.09439051 0.9648727 -0.1979516 -0.1256564 0.9721243 -0.07590889 -0.7605426 0.6448355 -0.1480284 -0.6243475 0.7669928 -0.08733391 -0.654927 0.7506287 0.1897697 -0.8827647 0.4297839 0.1829096 -0.8385682 0.5131738 0.2119528 -0.852711 0.4774516 0.1112673 -0.8416575 0.5284243 0.2181823 -0.5144826 0.8292793 0.2172217 -0.5245372 0.8232106 0.2019314 -0.7902362 0.5785762 0.3089485 -0.7828833 0.5400415 -0.02255684 -0.8460791 0.5325801 -0.03897213 -0.777185 0.6280643 0.2542763 -0.8741475 0.4137749 -0.4397556 0.6030724 0.6655214 -0.1875157 0.725817 -0.6618365 -0.185153 0.7461484 -0.6395164 -0.5342837 0.7411177 0.4065535 -0.5177321 0.7730817 0.3664674 -0.3672978 0.8064498 0.463391 -0.3175005 0.6796566 0.6612567 0.08933067 -0.2531319 0.9632986 0.5122933 -0.6987117 -0.4993571 0.4248872 -0.7400987 -0.5212723 0.4071204 -0.7629984 -0.5020821 -0.1894776 -0.2862979 0.9392188 -0.2049855 -0.1273887 0.9704397 -0.1782879 -0.5078394 0.8428004 -0.2802348 0.03842568 0.9591621 -0.1532417 0.01499801 0.988075 -0.3410297 0.1126427 0.9332794 -0.3312169 0.1291748 0.9346707 -0.4581876 0.2488653 0.8533054 -0.5057653 0.4091503 0.7594718 -0.5435769 0.4126383 0.7309268 -0.4449566 0.3383173 0.8291894 0.09602111 -0.836214 0.5399318 0.07387876 -0.06699812 0.9950142 0.03499341 0.7146977 0.6985576 -0.5749194 0.5730999 0.5839729 -0.5673093 0.5712179 0.5931866 -0.4313482 0.8237267 0.3679854 -0.3781911 0.8079925 0.4517963 -0.3953927 0.8493385 0.3496983 -0.08211421 -0.04399979 0.9956513 -0.06243282 0.03570067 0.9974105 -0.03381508 0.03161388 0.998928 -0.5583639 0.643157 0.5240029 0.3195893 -0.8447241 0.4293063 0.3007576 -0.8340761 0.4624523 -0.2186735 0.6714268 0.7080734 0.1127267 -0.2339537 0.9656906 0.4261325 -0.9022833 0.06554591 0.1118963 -0.4824064 0.8687711 -0.2154001 0.7601798 0.6129677 -0.1029552 -0.4128209 0.9049747 -0.09730505 -0.236531 0.9667393 -0.06286686 -0.1546316 0.9859701 -0.04690551 -0.04979127 0.9976576 0.08355534 -0.7599823 0.6445507 0.1043135 -0.7429159 0.661207 0.08036547 -0.6228263 0.7782216 0.02148079 -0.5985774 0.800777 0.3654052 -0.8335738 0.414287 0.3544075 -0.8209674 0.4476695 0.3971114 -0.642589 0.6552725 -0.4646006 0.7081529 0.5316632 -0.4506717 0.7392802 0.5003597 -0.3480422 0.2132451 0.9129037 0.3127248 -0.5546662 0.7710698 -0.3730471 0.6948981 0.6147785 2.56881e-5 -0.4741557 0.8804411 -0.1754886 0.1343641 0.9752692 -0.05609089 0.04073458 0.9975944 0.01575261 0.05529493 0.9983458 -0.007659196 0.01400744 0.9998726 -0.004973709 0.06909817 0.9975975 2.53572e-4 0.06134265 0.9981167 -0.1598154 0.1541941 0.9750298 -0.2937712 0.3090382 0.9045408 -0.4303736 0.4852516 0.7611237 -0.4803923 0.5983313 0.6412666 -0.4264906 0.6590368 0.6194969 -0.3935264 0.7784581 0.4890193 -0.3719239 0.8085934 0.4559049 0.4693835 -0.6659783 0.5797863 0.3447786 -0.4736108 0.8104447 -0.2473538 0.8573783 0.4513521 -0.2594527 0.8444265 0.468645 0.01653289 0.04556441 0.9988246 0.2347864 -0.7774277 0.583508 0.180804 -0.7360675 0.6523148 0.04102128 -0.2069534 0.9774905 0.06893938 -0.3322574 0.940666 -0.05990111 0.1191633 0.9910662 0.002639293 0.02648478 0.9996458 0.4849064 -0.7617031 0.4297376 0.4744029 -0.7007078 0.5328702 0.325311 -0.4600497 0.826152 -0.1518216 0.2530567 0.9554646 -0.2586346 0.560944 0.7864159 -0.2941068 0.8832747 0.3651399 -0.3045313 0.8416535 0.4459597 -0.2850226 0.8874524 0.3622022 -0.3341948 0.4818324 0.8100317 -0.2815504 0.381634 0.880389 -0.001545608 0.009716391 0.9999516 0.0474506 -0.1006707 0.9937877 0.2898396 -0.7630839 0.5776644 0.3428953 -0.784834 0.5161962 -0.3039201 0.52537 0.7947447 -0.3441374 0.6766416 0.6509421 -0.3239979 0.6614175 0.6764261 0.4617716 -0.7854666 0.4120791 0.4241574 -0.7497454 0.5079098 0.4726715 -0.7009252 0.5341214 0.1471233 -0.5973226 0.7883912 0.1237685 -0.3734315 0.9193642 0.2176096 -0.6131767 0.7593816 0.2314243 -0.6758538 0.6997603 -0.02021533 0.03735476 0.9990976 -0.01548779 0.02509242 0.9995652 -0.05289906 0.160338 0.9856438 -0.1533625 0.3348134 0.9297204 -0.3158069 0.7459126 0.5864132 -0.1385374 0.8541055 0.5013096 -0.1599223 0.873771 0.4592919 -0.1331853 0.9285956 0.3463699 -0.1845909 0.9122657 0.3656467 -0.09069126 0.8858064 0.4551069 -0.1060177 0.8081716 0.5793264 -0.04012954 0.6525515 0.7566812 0.1472248 -0.7137973 0.6847031 0.01400327 -0.3626068 0.9318371 -0.01738744 8.18308e-4 0.9998486 0.3183196 -0.6979935 0.6414654 -0.03217124 0.05903959 0.9977371 -7.3923e-4 0.03552097 0.9993687 -0.03130346 0.04237371 0.9986113 -0.2401317 0.7862145 0.5693889 -0.2131546 0.8295255 0.5161904 -0.2142035 0.8402993 0.49801 -0.005661725 0.1098511 0.993932 -0.260192 0.3582186 0.8966492 -0.2772011 0.6669132 0.6916548 0.3981981 -0.4204728 0.8152552 0.4328278 -0.4343065 0.7899608 0.6210224 -0.6000168 0.5042927 0.544656 -0.623648 0.5607256 0.2759268 -0.5655215 0.7772065 0.2205019 -0.3356151 0.9158283 0.2820568 -0.4138714 0.8655371 0.4532689 -0.7121821 0.5360447 0.3719627 -0.6657441 0.6468605 -0.1640487 0.4966998 0.8522778 0.6129336 -0.6778532 0.4059897 0.5740433 -0.70046 0.4240638 -0.127605 0.8905771 0.4365654 -0.128005 0.8927513 0.4319835 0.1869555 -0.2050932 0.9607208 0.3962451 -0.5861254 0.7067157 -0.1659929 0.6867154 0.7077206 -0.132776 0.5295525 0.8378215 0.5773161 -0.6552357 0.4872088 0.5397745 -0.6547112 0.5291472 -0.153301 0.7045327 0.692916 -0.1105327 0.9029279 0.4153358 -0.00676763 0.03442776 0.9993844 0.1029145 -0.02601367 0.99435 0.1866734 -0.2055574 0.9606764 -0.05185115 0.1601805 0.9857249 -0.01291072 0.0554645 0.9983772 -0.01787233 0.02259618 0.999585 0.04202914 0.7619264 0.6462987 0.01455134 0.9013344 0.4328795 0.01864743 0.9031331 0.4289556 0.5488498 -0.5695334 0.6118788 0.4351876 -0.5500376 0.7127906 0.5085977 -0.5350564 0.6745688 -0.5195317 -0.09041398 0.8496541 -0.8434956 0.5215484 0.1284627 0.5502531 -0.3877193 0.7395238 -0.0822094 0.927533 0.3645879 -0.001089036 0.9345099 0.3559356 0.01839274 -0.2175138 0.975884 0.02535051 0.7355408 0.677006 0.4039586 -0.4428184 0.8004558 -0.03580617 0.1853261 0.9820246 -0.005864381 0.4282675 0.903633 -0.06393682 0.5147236 0.8549689 -0.08260816 0.7281658 0.6804047 -0.04978924 0.7818096 0.6215261 0.7181035 -0.5671384 0.403338 0.6754787 -0.6045134 0.4222467 0.6909465 -0.5408268 0.4796867 0.6931725 -0.4991866 0.5199276 0.03448325 0.8528427 0.5210282 0.01284843 0.8726131 0.4882432 -6.14859e-4 0.8034872 0.5953219 0.5498379 -0.3643296 0.7516264 0.576447 -0.4115972 0.7059014 0.6586922 -0.5957565 0.4595639 -0.0282365 0.04424774 0.9986215 -0.02874928 0.02650004 0.9992353 0.05962485 0.9266928 0.3710597 0.114284 0.9250551 0.3622324 0.08735316 0.8776059 0.471357 0.161116 0.6176817 0.7697474 0.1589576 0.6847624 0.7112194 0.2252622 0.8740637 0.4304295 0.2407761 0.8804011 0.4085593 0.4598325 -0.271711 0.8454154 0.4730296 -0.3782678 0.7957114 0.3725808 -0.2132573 0.9031639 -0.006376206 0.0309391 0.9995009 0.7061282 -0.4931185 0.5081507 0.6878538 -0.4698673 0.5532469 0.004144251 0.6599234 0.7513215 -0.04108321 0.09631145 0.994503 -0.2679674 0.3740713 0.8878425 0.5514395 -0.4261336 0.7171644 0.02272427 0.1196112 0.9925608 0.747648 -0.5200355 0.4130201 0.7493206 -0.4747103 0.4617022 0.7965116 -0.45457 0.3986673 0.7657151 -0.3975191 0.5056273 0.6052863 -0.2662222 0.7501696 0.7747735 -0.3940564 0.4944145 0.09476399 -0.1345635 0.9863632 -0.4315299 0.2083658 0.8777047 -0.1890442 -0.9603295 0.2050109 -0.1839895 -0.6612736 0.7272312 0.1345309 0.5882701 0.7973957 0.05025058 0.4502185 0.8915033 0.005639553 0.1066368 0.9942821 0.1088079 0.2887908 0.9511891 0.1101475 0.3394383 0.9341569 0.6006321 -0.398903 0.6929051 0.6880246 -0.4628416 0.5589273 0.1860796 -0.02235454 0.9822803 0.3120956 -0.05918806 0.9482052 0.03149348 0.07495689 0.9966894 0.03572648 0.6618566 0.7487787 0.0968064 0.5843785 0.8056863 0.08037698 0.7280183 0.6808297 0.2417925 0.9051664 0.3495858 0.1748846 0.9109127 0.3737025 0.8089849 -0.41622 0.4150956 0.7981444 -0.418309 0.4335704 0.08438611 0.848739 0.5220355 0.2042089 0.8814458 0.4258543 0.1127578 0.05883127 0.9918794 0.06168174 0.08625125 0.9943622 0.1307059 0.07715076 0.9884148 0.1744599 0.8046536 0.5675355 0.1553122 0.7341313 0.6610064 0.858004 -0.3236533 0.3988452 0.7714446 -0.3050594 0.5584015 0.2144848 0.7460952 0.6303477 0.1404076 0.1358903 0.980724 0.5547318 -0.232459 0.7988964 0.63372 -0.3142374 0.706862 0.1726726 0.6095762 0.7736932 0.2101225 0.6851962 0.6973915 0.701007 -0.2860506 0.6532719 0.7403081 -0.3450071 0.5769872 0.2340119 0.5400607 0.8084386 0.627371 -0.1500725 0.764123 0.8526707 -0.1599364 0.497366 0.8238418 -0.1820636 0.5367844 0.5953705 -0.1255245 0.7935853 0.4419796 0.8055962 0.3945488 0.3481475 0.7043092 0.6186615 0.3787951 0.7974656 0.4696414 0.5712809 -0.1408248 0.808583 0.3927797 -0.03756344 0.9188652 0.4546562 -0.04762649 0.8893928 0.8160538 -0.2962378 0.4962857 0.8121349 -0.2888599 0.5069485 0.2352205 0.8106592 0.5361931 0.2349847 0.8668693 0.4396815 0.388663 0.8512219 0.3526507 0.2998692 0.8813695 0.3650569 -0.1524019 0.1113794 0.9820226 -0.8124631 0.2957271 -0.5024433 -0.7560774 0.3860896 -0.5284712 -0.7574868 0.3748862 -0.5344848 0.3244681 0.6893281 0.6477248 0.09964489 0.1889414 0.9769198 0.2922673 0.8571558 0.4241037 0.6411923 -0.1076975 0.7597854 0.7444971 -0.1747914 0.6443384 0.8706444 -0.2754381 0.4075688 0.2942411 0.7825411 0.5486818 0.3169521 0.7209806 0.616221 0.2722378 0.6854094 0.6753522 0.8960248 -0.2052955 0.3936922 0.9035472 -0.1904014 0.3838618 0.2498852 0.1164373 0.9612491 0.3301011 0.1039214 0.9382077 0.2042886 0.253405 0.9455433 -0.382802 -0.7913573 -0.4766721 -0.2907607 -0.8230223 -0.4879474 -0.3328431 -0.7972666 -0.5035687 0.01700061 0.0703299 0.997379 -0.4427189 -0.8210571 -0.3603683 0.3684414 0.8148688 0.4474818 0.414098 0.832616 0.3677955 0.3942978 0.8078943 0.4379912 -0.2373099 0.01219236 0.9713575 0.6811443 -0.02102357 0.7318473 0.7256624 -0.009888947 0.6879799 -0.7306842 0.09810835 0.6756296 0.2286738 0.2628762 0.9373391 0.3655206 0.4517376 0.8138352 0.3483528 0.5386098 0.7671701 0.328531 0.550285 0.7676287 0.8249267 -0.2127044 0.5236916 0.7634255 -0.1620486 0.6252374 0.5501871 0.7546477 0.3574928 0.4897487 0.7279146 0.479882 0.4408718 0.6943649 0.5687614 0.05240052 0.1608397 0.9855886 0.2888998 0.2229604 0.9310347 0.6092785 0.07402253 0.7894937 0.664808 0.03030651 0.7463993 0.5899599 0.07446205 0.8039918 0.4614467 0.5864363 0.6657023 0.4581874 0.6657307 0.5889542 0.8656311 -0.1390748 0.4809792 0.8900175 -0.1320716 0.4363783 0.4412128 0.7735502 0.4549192 0.4808276 0.6782862 0.5556371 0.9222627 -0.01797324 0.3861457 0.9164083 -0.04051083 0.3981894 0.9132127 -0.0669949 0.4019383 0.8715408 -0.02085191 0.4898794 0.8645098 -0.009788095 0.5025207 0.5636468 0.7098685 0.4223613 0.499598 0.5647498 0.6568558 0.475241 0.1373757 0.8690649 0.5663963 0.7352639 0.3722665 0.5553539 0.7310175 0.3964789 0.5108364 0.3725491 0.7747603 0.4894061 0.4126406 0.768251 0.4917786 0.3019488 0.8166889 0.5249977 0.2485953 0.813989 0.705555 0.03514224 0.7077833 0.7928862 -0.04933881 0.607369 0.8502797 -0.04222357 0.5246348 0.8010451 -0.04081726 0.5972109 0.4371472 0.5556465 0.7072195 -0.09048712 0.05529636 0.9943614 -0.2769567 -0.3978156 0.8746644 0.5282585 0.5244596 0.6677464 0.5729767 0.6467224 0.5034361 0.696428 0.06275326 0.7148777 0.6327447 0.1624495 0.757129 0.8658695 0.12384 0.4846996 0.6241248 0.6284338 0.4642621 0.6530352 0.667364 0.358009 0.6520155 0.2206948 0.7253756 0.7775109 0.1221522 0.616892 0.7783511 0.1260432 0.6150469 0.7439961 0.2159072 0.6323401 0.6712979 0.2318177 0.7040027 0.8751941 0.007226884 0.4837179 0.5818119 0.5152837 0.6292676 0.5990561 0.6202732 0.5063527 0.9147839 0.1199092 0.3857362 0.8692536 0.1346511 0.4756757 0.8652296 0.1219999 0.4863063 0.9156898 0.1515487 0.3722168 0.8528017 0.1429862 0.5022792 -0.7114224 -0.05931854 0.7002567 -0.7862991 0.1101582 0.6079467 0.6548135 0.6090121 0.4475754 0.5382372 0.4577843 0.7076258 0.6218786 0.3944568 0.6765139 0.646479 0.4384423 0.6243664 0.6712178 0.5813957 0.4598324 0.6897332 0.6198252 0.3742794 0.7342673 0.5749655 0.3609241 0.6946205 0.5249695 0.491843 0.1852166 -0.03653985 0.9820182 0.2693828 0.09572702 0.9582638 0.8424711 0.2595694 0.4720871 -0.5519183 -0.5693541 0.6092801 0.2024379 0.3226897 0.9246028 0.6848468 0.4329499 0.5861223 0.7543144 0.3587663 0.5498151 0.7736685 0.2887279 0.5639799 0.8484163 0.2592495 0.4614973 0.8564136 0.2416425 0.4562506 0.7134096 0.5211007 0.4685091 0.893483 0.2321646 0.3844318 0.780633 0.4924694 0.3848194 0.7709995 0.479192 0.4194459 0.8721023 0.331055 0.3603338 0.7974677 0.3454164 0.4947047 0.7988355 0.4706632 0.3746171 0.7948742 0.4284802 0.4296276 -0.9878537 -0.07782137 0.1344953 0.5996679 0.3899282 0.6988236 0.7206232 0.4465391 0.530382 0.4760873 0.3150845 0.8210133 0.4897646 0.1925748 0.850321 0.801963 0.3938897 0.4491175 0.8369166 0.3422992 0.4270853 0.8614236 0.3485414 0.3694163 0.7858886 0.3217685 0.528057 0.3277338 0.1736035 0.9286832 0.626518 0.2305144 0.7445391 -0.4544421 0.1205396 0.882583 -0.03998041 -0.08691573 0.9954131 0.3979079 0.4090967 0.8211634 0.06978726 0.1050658 0.9920136 -0.8054059 -0.4555412 -0.3792145 -0.7926232 -0.5188114 -0.3202863 -0.7671644 -0.4095051 -0.4937251 -0.9093776 -0.1903712 -0.369853 -0.7891555 -0.3032406 -0.534115 0.787652 0.2875372 -0.5449098 0.8395256 0.13881 -0.5252891 0.7023344 0.4573916 -0.5454534 0.635336 0.524128 -0.5671315 0.6339428 0.5320389 -0.5612941 0.487322 0.6599546 -0.5718193 0.5398307 0.5850121 -0.6052632 0.4949935 0.6126941 -0.6161067 0.4312843 0.6920852 -0.5788022 0.3826433 0.6862486 -0.6185848 0.2883794 0.7442405 -0.6024479 0.8063825 -0.2501678 -0.5358762 0.7311046 -0.4208127 -0.5370315 0.7595426 -0.3177154 -0.5675843 0.05291193 0.7970799 -0.6015514 0.1568774 0.7816535 -0.6036615 0.6892902 -0.5112001 -0.5133745 0.6867238 -0.5251523 -0.5026187 0.7468898 -0.4083475 -0.5247932 -0.04813539 0.7588763 -0.6494535 0.05820941 0.7965008 -0.6018291 -0.4056523 0.695523 -0.5930379 -0.2420827 0.7511521 -0.6141389 -0.2946929 0.6970912 -0.6536207 -0.4635478 0.6460822 -0.6063838 -0.5254125 0.556379 -0.6437268 -0.3932462 0.5132624 -0.7628364 -0.5153235 0.2976241 -0.8036552 -0.6673408 0.5135404 -0.5393816 -0.6846019 0.4680537 -0.5587897 -0.8610463 0.09846538 -0.4989026 -0.8640051 -0.01280438 -0.5033202 -0.8682761 -0.02188026 -0.4955986 -0.4693911 -0.7372819 -0.4858884 -0.5335282 -0.6904343 -0.4885163 -0.5242918 -0.6933068 -0.4944128 -0.8706137 -0.1188007 -0.4774078 -0.8952413 -0.3802751 -0.232237 -0.8635241 -0.1340153 -0.4861751 -0.842971 -0.2826003 -0.4577522 -0.7201126 -0.5194457 -0.4600155 -0.711362 -0.5198132 -0.473031 -0.6247457 -0.5952552 -0.5053356 -0.6171583 -0.6168168 -0.488521 0.3042417 -0.8214961 -0.4822666 0.3435166 -0.7781527 -0.5258086 -0.8476924 0.1153863 -0.5177874 -0.8041515 0.2364715 -0.5453639 0.5458062 -0.7226688 -0.424082 0.620633 -0.5827733 -0.5245857 0.5674515 -0.6174442 -0.5447582 0.5153947 -0.6964178 -0.4993704 -0.1577243 -0.8596669 -0.4858971 -0.1108788 -0.8455676 -0.5222274 0.01946949 -0.878206 -0.4778863 0.7492654 0.3685582 -0.5502421 0.8008588 0.276545 -0.5311763 0.7223138 0.3869847 -0.5731542 0.855947 0.1078574 -0.5056892 0.8430588 0.1532359 -0.5155294 0.8657596 -0.04718017 -0.4982312 0.8453437 0.008800029 -0.5341505 0.8288487 0.4407123 -0.3446484 0.7509822 0.5086565 -0.4210634 0.7016265 0.5802169 -0.4136045 0.7856754 0.465197 -0.4078061 0.7014803 0.5505948 -0.4525162 0.8158591 0.408747 -0.4090232 0.8643321 0.3077508 -0.397768 0.8737288 0.2534703 -0.4151517 0.905921 0.1684218 -0.3885115 0.5978037 0.670336 -0.4396367 0.8529549 -0.1337937 -0.5045464 0.8223189 0.4014568 -0.403267 0.9096395 0.08152109 -0.4073211 0.9235082 0.009736061 -0.3834552 0.4988291 0.7600547 -0.416517 0.519591 0.6834917 -0.5127031 0.6103101 0.6658015 -0.4292204 0.4276903 0.7866295 -0.4453034 0.8566765 -0.1313729 -0.4988454 0.9129537 -0.1535937 -0.3780536 0.9151755 -0.06050777 -0.3984879 0.7004621 0.581117 -0.4143139 0.6004676 0.6803845 -0.4201378 0.8685854 -0.2598116 -0.4219686 0.7592006 0.4220746 -0.495447 0.8041129 0.3784543 -0.4584486 0.7483674 0.4437065 -0.4930223 0.8432893 0.2684494 -0.465616 0.8595917 0.2508991 -0.4451424 0.8904092 0.07998448 -0.448078 0.2663702 0.7409723 -0.6164471 0.2666321 0.8557904 -0.4433172 0.2885003 0.8128771 -0.5059629 0.3546552 0.7968451 -0.4891397 0.4983803 0.7602021 -0.4167852 0.3703752 0.8275831 -0.4218156 0.4047329 0.8052268 -0.4333605 0.209222 0.7931231 -0.5719982 0.9032709 -0.1844872 -0.3873839 0.8745495 -0.3129562 -0.3704345 0.8739285 -0.3173102 -0.3681895 0.7760345 -0.3370331 -0.5330846 0.6852732 0.500441 -0.5291121 0.6521658 0.571995 -0.4974952 0.5104232 0.7052623 -0.4920095 0.5686759 0.6550686 -0.4974866 0.8871949 -0.03063923 -0.4603764 0.8801307 0.05373191 -0.4716811 0.1452871 0.7955149 -0.5882583 0.583817 0.6215152 -0.522376 0.1699132 0.8600791 -0.4810339 0.8607736 -0.2175775 -0.4601401 0.8480859 -0.1146727 -0.5173013 0.7403184 0.2866948 -0.6080583 0.7722066 0.2416325 -0.5876315 0.7908237 0.2352268 -0.5650365 0.7242622 0.3512551 -0.59335 0.3076286 0.8489538 -0.4297 0.2759303 0.8659296 -0.4171672 0.8029004 -0.4531187 -0.3873427 0.830206 0.07169383 -0.5528274 0.6268372 0.4699952 -0.6214336 0.6548087 0.4029491 -0.6394198 0.3889608 0.7415643 -0.5466186 0.149108 0.8953573 -0.4196453 0.1564269 0.8917459 -0.424641 0.1471893 0.8504093 -0.5051132 0.8383398 -0.279017 -0.4683333 0.5582262 0.5911073 -0.5822163 0.6104618 0.4820131 -0.6284901 0.7779063 -0.04565554 -0.6267196 0.8045678 0.05355608 -0.5914411 0.7855219 -0.1021637 -0.6103426 0.05425316 0.7976983 -0.6006113 0.03297734 0.8774136 -0.4786002 0.8284063 -0.4210371 -0.3694196 0.8147487 -0.3082743 -0.4910719 0.7943704 -0.3820155 -0.472271 0.7757527 -0.4989862 -0.3862909 0.7525576 -0.5465222 -0.3673833 0.7364941 0.1279649 -0.6642301 0.4683102 0.5986067 -0.6498889 0.4089835 0.7462746 -0.525173 0.3912146 0.6893166 -0.609749 0.2601582 0.812963 -0.5209693 0.1367953 0.8711959 -0.4714921 0.1436773 0.8620709 -0.4859944 0.2645042 0.8130283 -0.518674 0.6602969 -0.6551439 -0.3671438 0.6712178 -0.639107 -0.3755115 0.4480286 0.5413181 -0.7115091 0.5034362 0.4581041 -0.7325931 0.6370878 0.2606495 -0.7253834 0.5953113 0.3053333 -0.7432201 0.7163396 0.1224264 -0.6869274 0.6501954 0.1966504 -0.7338764 0.00882858 0.8662334 -0.4995617 -0.001578927 0.9092033 -0.4163495 0.4949314 0.3991768 -0.7718166 0.5590173 0.3140375 -0.7673854 0.7714372 -0.2966484 -0.5629249 0.7486836 -0.168021 -0.6412814 -0.06180465 0.8868378 -0.4579289 -0.0699132 0.7381627 -0.6709904 0.6769753 0.02409577 -0.7356113 -0.01173174 0.9059357 -0.4232529 0.006494164 0.8828403 -0.4696285 0.7632024 -0.5051276 -0.4029497 0.7569956 -0.4384827 -0.4844489 0.6678019 -0.607486 -0.430118 -0.1900255 0.7558109 -0.6266102 0.5382738 0.07487183 -0.8394377 0.4815486 0.07187753 -0.8734671 0.3954825 0.1548156 -0.9053319 0.3557634 0.5302263 -0.7696055 0.3249995 0.6871371 -0.649783 0.2617567 0.6183524 -0.7410289 0.2678509 0.6002586 -0.7536216 0.2243392 0.7532171 -0.6183334 0.2225156 0.7633514 -0.6064499 0.6482449 0.01137602 -0.761347 0.712893 -0.184274 -0.676629 0.639483 -0.1585329 -0.7522824 0.6069397 -0.07978576 -0.7907328 0.5678807 -0.733973 -0.3725522 0.4010142 0.374444 -0.8360499 0.2711257 0.1435 -0.9517871 0.2680982 0.1510785 -0.9514719 0.29202 0.2364932 -0.9267122 0.6822975 -0.4125418 -0.6035557 0.7160934 -0.4545122 -0.5297442 0.7043114 -0.3530716 -0.615862 -0.1399129 0.849304 -0.5090258 -0.1288105 0.9011366 -0.4139572 -0.1992854 0.8578729 -0.4736449 -0.1751123 0.7819325 -0.5982619 0.3312482 0.4602655 -0.8236688 0.09775531 0.8267688 -0.5539832 0.6758427 -0.2955005 -0.6752157 0.6524033 -0.5665138 -0.5034204 0.6589221 -0.6094467 -0.4409042 0.5787808 -0.7277337 -0.3679899 0.4825294 -0.7616893 -0.4324291 0.4723792 -0.8043856 -0.3603078 0.171754 0.6650503 -0.7267796 0.1627838 0.6886593 -0.7065762 0.4540874 -0.08557021 -0.8868384 0.3936855 -0.009792625 -0.9191931 0.05120146 0.8202967 -0.5696418 0.02598363 0.730881 -0.6820101 0.01355332 0.7493326 -0.6620552 0.561708 -0.2326273 -0.7939575 0.553735 -0.2961344 -0.7782558 -0.01927238 0.8572492 -0.5145411 -0.1618689 0.8895826 -0.4271315 -0.1617096 0.846869 -0.5066192 -0.09533005 0.8420428 -0.5309202 0.2144581 0.3134711 -0.9250641 0.2279527 0.3927878 -0.8909295 0.178325 0.4548492 -0.8725322 0.6580528 -0.4266623 -0.620424 0.557453 -0.2919012 -0.7772 0.5577576 -0.386519 -0.7345131 -0.2491108 0.8151761 -0.5229071 -0.2721438 0.8708185 -0.4094058 0.567271 -0.6945787 -0.4424524 0.1588129 0.02369737 -0.9870243 0.1625754 -0.01567858 -0.9865716 0.1609252 -0.01471722 -0.9868569 0.4319519 -0.1217668 -0.8936389 0.5702838 -0.5444943 -0.6150629 0.5729631 -0.5571745 -0.6010575 -0.3134359 0.8250783 -0.4701104 0.1359679 0.4536669 -0.8807379 0.06000834 0.5449159 -0.8363406 0.05969017 0.5490472 -0.8336572 0.08447325 0.1053472 -0.9908413 0.04046899 0.0227859 -0.998921 0.08029049 0.1017785 -0.9915617 0.0287171 -0.01291525 -0.9995042 -0.01755148 0.6405222 -0.7677391 0.1880881 -0.1145755 -0.9754462 0.1357529 -0.0678457 -0.988417 0.2916018 -0.1493967 -0.944801 0.4817262 -0.5057752 -0.7156336 0.4887033 -0.4568974 -0.7432455 0.5067763 -0.7137531 -0.4834609 0.4996013 -0.6615163 -0.5592806 0.3394799 -0.8572137 -0.3872182 -0.008519351 -0.06240171 -0.9980148 -0.01371288 -0.0524562 -0.9985291 -0.09082722 0.7609371 -0.6424369 0.4001329 -0.2943423 -0.8679034 0.4633054 -0.7516533 -0.4694311 0.443307 -0.8140276 -0.3752839 0.0379197 0.249049 -0.9677484 -0.01325416 -0.04164093 -0.9990448 -0.1825403 0.8384702 -0.5134657 -0.3138459 0.8463807 -0.4302796 -0.3051806 0.8281498 -0.4701412 -0.4094412 0.813597 -0.4128171 -0.3973667 0.7488906 -0.5303419 0.3543493 -0.8613329 -0.3640636 0.361959 -0.8557503 -0.3696988 0.3732535 -0.3344419 -0.8653499 -0.4179537 0.6618384 -0.622322 -0.4793643 0.7334209 -0.4819789 -0.4056013 0.695542 -0.5930507 -0.1581909 0.6850706 -0.7110935 -0.139303 0.7350608 -0.6635363 -0.114616 0.6288457 -0.7690359 0.1635278 -0.2430057 -0.9561417 0.1099765 -0.1509881 -0.9823991 0.284988 -0.3385688 -0.8967459 -0.233999 0.778509 -0.5823816 0.426666 -0.5406222 -0.7250406 0.4004311 -0.6491121 -0.6467678 0.1878688 -0.8660117 -0.4633888 0.1780478 -0.8424668 -0.5084767 -0.04030865 0.3924603 -0.9188853 0.01775634 0.2539381 -0.9670575 0.05324387 -0.1077578 -0.9927505 -0.001736104 -0.02712845 -0.9996305 0.2240622 -0.90426 -0.3634695 0.1772781 -0.8421629 -0.5092486 0.1942615 -0.9440623 -0.266475 -0.03415852 0.03289371 -0.998875 -0.08282887 0.4053061 -0.9104211 -0.143109 0.5380158 -0.8306978 0.003080844 -0.05898535 -0.9982541 0.01620042 -0.06223374 -0.9979301 -0.02259647 0.05070078 -0.9984583 0.3057262 -0.5009226 -0.8096964 0.337736 -0.6877371 -0.6426135 0.3157439 -0.7805318 -0.5395146 0.2810394 -0.8516172 -0.4424535 0.2916307 -0.7973007 -0.5284536 -0.2854676 0.7587078 -0.5855516 -0.3428865 0.7814711 -0.5212792 -0.4467324 0.7874786 -0.4246266 -0.4192589 0.7508054 -0.510405 -0.4334266 0.7528014 -0.4954107 0.01168489 -0.02648085 -0.999581 0.01514035 -0.03061014 -0.9994167 -0.3109933 0.6837987 -0.6600776 -0.2769678 0.6631979 -0.6953111 -0.5032584 0.7592126 -0.4127072 -0.4736107 0.7464739 -0.4674074 0.2616202 -0.6541842 -0.7096464 0.260098 -0.5282734 -0.8082551 -0.5827277 0.6631568 -0.4697355 -0.5093241 0.6551787 -0.5579695 0.209147 -0.9059857 -0.368032 0.2117854 -0.889953 -0.4038946 -0.04505252 0.06411361 -0.9969251 -0.08766448 0.1320261 -0.9873622 -0.1336197 0.307895 -0.9419907 -0.2963908 0.5285695 -0.7954665 -0.2859321 0.5192834 -0.8053495 0.01448607 -0.02335584 -0.9996223 0.04044765 -0.121278 -0.9917942 0.01713043 -0.09371423 -0.9954518 0.07182884 -0.2586702 -0.9632914 0.1131216 -0.2956147 -0.9485861 0.1704987 -0.492418 -0.8534956 -0.3918725 0.6490491 -0.6520516 -0.4504988 0.6802535 -0.5781922 -0.5582529 0.6671176 -0.4932624 -0.5815858 0.6658071 -0.4673959 -0.5669375 0.7048051 -0.4264172 -0.5709266 0.7029116 -0.4242149 0.1660388 -0.9201586 -0.3545975 0.02875715 -0.8722662 -0.4881852 -0.249133 0.359421 -0.8993049 0.03614151 -0.9305337 -0.3644185 0.0323289 -0.03909516 -0.9987124 0.0278939 -0.05508047 -0.9980923 0.02562534 -0.03029584 -0.9992125 0.03055328 -0.03374606 -0.9989634 0.1647065 -0.6829889 -0.7116165 0.1447038 -0.7328121 -0.6648665 0.1769891 -0.7963857 -0.5783119 0.07828706 -0.8520815 -0.5175213 0.06788885 -0.8668974 -0.4938421 0.08173364 -0.8804333 -0.4670729 -0.6190997 0.5266594 -0.5825337 -0.654757 0.6133732 -0.4416636 -0.675976 0.6116151 -0.411076 -0.3509787 0.5306322 -0.7715201 -0.4154229 0.5787781 -0.7017406 -0.5369732 0.6355104 -0.554785 0.1180134 -0.620382 -0.7753704 0.1145398 -0.542123 -0.8324563 -0.6502203 0.5233098 -0.5507817 0.005209028 -0.9251586 -0.3795452 0.01175415 -0.9491897 -0.3144848 -0.2177749 0.21563 -0.9518813 -0.2716284 0.3199806 -0.9076511 -0.0471217 0.02473324 -0.998583 0.02461773 -0.02682489 -0.9993371 -0.5538295 0.5655633 -0.6110737 -0.5174291 0.5030111 -0.6922767 -0.5269821 0.504123 -0.6842149 -0.3869673 0.3459021 -0.8547562 -0.4521033 0.3999403 -0.7972768 -0.4548611 0.4129808 -0.7890172 6.47025e-4 -0.3514417 -0.9362096 0.02524513 -0.4637945 -0.8855831 -0.6810464 0.6021749 -0.4166066 -0.6612824 0.5933842 -0.4589127 -0.08625435 -0.9305031 -0.3559837 -0.1322513 -0.9493775 -0.2849419 -0.2443647 0.1279239 -0.9612083 -0.1241795 0.03211128 -0.9917401 -0.02893888 -0.1444573 -0.9890878 -0.01979184 -0.07937794 -0.9966482 -0.01343017 -0.1463029 -0.9891487 -0.01139253 -0.7551863 -0.6554113 -0.02015429 -0.6773987 -0.73534 -0.008066415 -0.7507296 -0.6605604 -0.7446349 0.4780787 -0.4657892 0.001476943 -0.3524536 -0.9358282 -0.7045353 0.4914178 -0.5119948 -0.6949144 0.4791517 -0.5361974 -0.0608024 -0.6298756 -0.7743126 -0.7424933 0.5334181 -0.4051777 -0.1221907 -0.02414286 -0.992213 -0.01904606 -0.8734094 -0.4866141 -0.07048803 -0.8985098 -0.4332571 -0.1526035 -0.9230239 -0.3531841 -0.37599 0.1592946 -0.912829 -0.1228445 -0.08037668 -0.9891658 -0.1219279 -0.02401059 -0.9922485 -0.1054362 -0.08893024 -0.9904416 -0.03755503 -0.07263362 -0.9966514 -0.6172732 0.4281253 -0.6600627 -0.6929002 0.4526939 -0.5612108 -0.7639512 0.4918146 -0.4177285 -0.7581544 0.4689167 -0.4531215 -0.1156913 -0.8146951 -0.5682319 -0.1073721 -0.7842613 -0.6110691 -0.820517 0.4117324 -0.3965204 -0.1895543 -0.8883582 -0.4181972 -0.1679845 -0.882769 -0.4387485 -0.1934816 -0.9096006 -0.3676845 -0.5599274 0.2847279 -0.778082 -0.6302479 0.3228611 -0.7060796 -0.07984125 -0.373673 -0.9241179 -0.1760534 -0.5382968 -0.8241612 -0.1809055 -0.5693243 -0.801962 -0.1329297 -0.6217133 -0.7718824 -0.2478969 -0.8206866 -0.5148016 -0.2330715 -0.8601402 -0.4536921 -0.2851427 -0.8922821 -0.3500375 -0.5350025 0.2070515 -0.8190861 -0.3535441 0.1652098 -0.920713 -0.1728598 -0.8410766 -0.5125522 -0.1009252 -0.2451044 -0.9642292 -0.1716898 -0.7363212 -0.6544874 -0.3255314 -0.01032757 -0.9454748 -0.3790008 0.02680867 -0.925008 -0.8360526 0.3600497 -0.413981 -0.8188567 0.3645766 -0.4433484 -0.6970205 0.2796279 -0.6602807 -0.7401132 0.3450887 -0.5771883 -0.8661603 0.3006671 -0.3992065 -0.9129109 0.2671695 -0.3085679 -0.3941536 -0.8254709 -0.4040308 -0.1873415 -0.2800626 -0.9415244 -0.2577288 -0.3915449 -0.8833281 -0.806486 0.2825108 -0.5193921 -0.82678 0.288835 -0.4827103 -0.2142958 -0.2065389 -0.9546827 -0.2849662 -0.7231016 -0.6292204 -0.2886216 -0.7256544 -0.6245985 -0.2880911 -0.7907876 -0.5400543 -0.3369568 -0.8082748 -0.4828583 -0.3062038 -0.8569152 -0.4146512 -0.3388996 -0.8273856 -0.4478619 -0.3138975 -0.8773891 -0.3628454 -0.6357703 0.1362359 -0.7597605 -0.5725034 0.1488597 -0.8062759 -0.7099468 0.2337157 -0.6643437 -0.2840696 -0.612831 -0.7373891 -0.888944 0.2279574 -0.3972583 -0.3822001 -0.8547469 -0.3511852 -0.4993627 0.04407066 -0.8652716 -0.8783783 0.1924344 -0.4375167 -0.8928195 0.1928607 -0.4070357 -0.9135981 0.1236388 -0.3873654 -0.7834939 0.1588231 -0.6007599 -0.3630741 -0.4491751 -0.8163449 -0.3720114 -0.5513164 -0.7467649 -0.4687992 -0.8010716 -0.3721717 -0.4701129 -0.7998609 -0.3731172 -0.4675306 -0.7982941 -0.3796601 -0.4414672 -0.7454339 -0.4994348 -0.3569931 -0.1182951 -0.9265863 -0.6780333 0.06786578 -0.7318915 -0.6622379 -0.03534364 -0.7484597 -0.6726365 -0.02765828 -0.739456 -0.5742226 -0.03779667 -0.8178263 -0.4613215 -0.5818125 -0.6698334 -0.4469336 -0.6841408 -0.5763696 -0.440727 -0.7380894 -0.5108658 -0.4629344 -0.6956924 -0.5492758 -0.3561228 -0.117738 -0.9269922 -0.3507939 -0.234669 -0.9065727 -0.4116473 -0.4144933 -0.8116292 -0.3949967 -0.2742121 -0.8768041 -0.5077428 -0.1181103 -0.8533741 -0.7867203 0.141777 -0.6008082 -0.8436279 0.02599292 -0.5362987 -0.4789839 -0.7815287 -0.3997343 -0.9170598 0.01993483 -0.3982512 -0.9221462 -0.01226317 -0.3866472 -0.5668623 -0.7450366 -0.3515504 -0.7623744 -0.06332671 -0.6440304 -0.8352055 0.08275747 -0.5436756 -0.8739851 0.01204401 -0.4858036 -0.6335768 -0.6812015 -0.3668038 -0.6465874 -0.6593608 -0.3836252 -0.6156266 -0.6710369 -0.4131749 -0.5811744 -0.6839331 -0.4409898 -0.5872183 -0.185474 -0.7878923 -0.5521716 -0.2784363 -0.7858626 -0.5855867 -0.4139401 -0.6969518 -0.5441209 -0.4575086 -0.7032912 -0.6028783 -0.3525719 -0.7157031 -0.5324595 -0.5306811 -0.6594426 -0.5468229 -0.6647759 -0.5089772 -0.7006587 -0.6459785 -0.3029677 -0.6304343 -0.173272 -0.7566568 -0.704679 -0.2237805 -0.6733126 -0.7812314 -0.1541875 -0.6049 -0.5910988 -0.5674556 -0.5732333 -0.9139742 -0.112934 -0.3897399 -0.871077 -0.1312921 -0.473273 -0.8672857 -0.122143 -0.4825937 -0.9140912 -0.1457746 -0.3784009 -0.6914159 -0.3058441 -0.6545254 -0.7833234 -0.1555016 -0.6018502 -0.6895272 -0.5777963 -0.4366964 -0.686199 -0.509238 -0.5194302 -0.6999045 -0.6170576 -0.3596854 -0.7562804 -0.5288295 -0.3852007 -0.7087044 -0.5320369 -0.4633304 -0.7264522 -0.3489226 -0.5920476 -0.70672 -0.4329201 -0.5595775 -0.7112531 -0.4666592 -0.5256885 -0.7476402 -0.5530204 -0.3676992 -0.8962066 -0.2273604 -0.3809477 -0.8622407 -0.2380552 -0.4470692 -0.8551627 -0.2720561 -0.4412284 -0.8912963 -0.2704719 -0.3639177 -0.8270919 -0.3607826 -0.4309929 -0.8504059 -0.3700464 -0.3739994 -0.8170208 -0.3613969 -0.4492987 -0.8424045 -0.3982427 -0.3629842 -0.8149195 -0.375711 -0.4413021 -0.8036651 -0.2787536 -0.5257555 -0.8382002 -0.2859243 -0.4644004 -0.7507153 -0.4551436 -0.4788224 -0.8343329 -0.339182 -0.4345621 -0.7769064 -0.5001691 -0.3824231 - - - - - - - - - - - - - - -

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

-
-
-
-
- - - - - 0.001 0 0 0 0 -4.37114e-11 -0.001 0 0 0.001 -4.37114e-11 0 0 0 0 1 - - - 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 - - - - - - - -
\ No newline at end of file diff --git a/cram_pr2/cram_pr2_pick_place_demo/resource/bowl.stl b/cram_pr2/cram_pr2_pick_place_demo/resource/bowl.stl deleted file mode 100644 index 1f33504960..0000000000 Binary files a/cram_pr2/cram_pr2_pick_place_demo/resource/bowl.stl and /dev/null differ diff --git a/cram_pr2/cram_pr2_pick_place_demo/resource/cup.dae b/cram_pr2/cram_pr2_pick_place_demo/resource/cup.dae deleted file mode 100644 index a3138bcd5b..0000000000 --- a/cram_pr2/cram_pr2_pick_place_demo/resource/cup.dae +++ /dev/null @@ -1,228 +0,0 @@ - - - - - Blender User - Blender 2.77.0 commit date:2016-04-05, commit time:18:12, hash:abf6f08 - - 2016-08-04T16:00:59 - 2016-08-04T16:00:59 - - Z_UP - - - - - - - 49.13434 - 1.777778 - 0.1 - 100 - - - - - - 0 - 0 - 0 - - - - - - - - - 1 1 1 - 1 - 0 - 0.00111109 - - - - - 0.000999987 - 1 - 0.1 - 0.1 - 1 - 1 - 1 - 2 - 0 - 1 - 1 - 1 - 1 - 1 - 0 - 2880 - 2 - 30.002 - 1.000799 - 0.04999995 - 29.99998 - 1 - 2 - 0 - 0 - 1 - 1 - 1 - 1 - 8192 - 1 - 1 - 0 - 1 - 1 - 1 - 3 - 0 - 0 - 0 - 0 - 0 - 1 - 1 - 1 - 3 - 0.15 - 75 - 1 - 1 - 0 - 1 - 1 - 0 - - - - - - - cup_eco_orange.png - - - - - - - - cup_eco_orange_png - - - - - cup_eco_orange_png-surface - - - - - - 0 0 0 1 - - - 0 0 0 1 - - - - - - 0.5 0.5 0.5 1 - - - 50 - - - 1 - - - - - - - - - - - - - - - - 0.04121112 0.001282632 0.04122036 0.04032254 0.002092301 0.04089105 0.04121881 -0.01009523 0.04124546 0.04194813 3.58745e-4 0.03791487 0.04049926 0.00854367 0.04224365 0.03957128 -0.01226919 0.04149955 0.03695958 -0.02071863 0.04013407 0.03983634 -0.01348978 0.03563654 0.04142665 -0.005996882 0.03499674 0.04095232 0.007705152 0.03582268 0.03890985 0.01481586 0.03888875 0.03766691 0.01714253 0.04219603 0.03442502 0.01998412 0.04181814 0.03687161 0.01286309 0.03966224 0.03933179 -0.004224359 0.03915637 0.03900408 0.004397213 0.0383771 0.04104793 -3.80519e-4 0.02996307 0.0382387 -0.01067101 0.03913158 0.03616821 -0.02167588 0.0416451 0.03436034 -0.02253895 0.04136705 0.03615468 -0.01668828 0.03918945 0.02597224 -0.03218019 0.04188072 0.03148138 -0.02811282 0.04111176 0.03811967 0.0138188 0.03016299 0.03886795 0.001601576 0.01943731 0.03712838 0.01119905 0.01994699 0.03214436 -0.02624136 0.03322231 0.03554451 -0.02095949 0.03162306 0.03287035 0.02467966 0.04254192 0.03394663 0.02384126 0.04045814 0.03923815 -0.006697356 0.02378344 0.03411465 0.02133899 0.02910017 0.0383796 0.002615153 0.03306543 0.03643882 -0.004104256 0.02289468 0.03759717 -0.008064687 0.03168123 0.03591722 -0.01531285 0.0195406 0.03032839 -0.02569764 0.03908854 0.03749507 0.00775206 0.03315985 0.03251183 0.01498317 0.02043819 0.03464752 0.01770544 0.03980249 0.03316414 -0.02022838 0.03329771 0.0345689 -0.01125472 0.02049279 0.0300315 -0.01863771 0.01480829 0.0352509 0.007330596 0.02066922 0.03576868 -0.001213729 0.01855534 0.03150868 -0.02335596 0.02107828 0.02792263 0.02754139 0.0424 0.02960741 0.02448093 0.03944927 0.02815419 0.029509 0.04262632 0.0309444 0.02715945 0.03921955 0.02450913 -0.03396904 0.04147124 0.02812832 -0.03036695 0.03350025 0.03640049 0.007082641 0.008945703 0.0380879 -0.003809571 0.01560068 0.03682428 0.002721011 0.007568299 0.03386914 0.02015548 0.02521765 0.03439044 -0.01546198 0.01242262 0.03715038 -0.009124696 0.01488471 0.0292862 -0.02523332 0.03253835 0.02149689 -0.03317743 0.04022043 0.02562922 -0.02889591 0.03294962 0.03358036 -0.005003631 0.006957769 0.01414948 -0.0387637 0.04206204 0.03440934 0.01460558 0.0117315 0.02813583 0.02763241 0.02778774 0.02881938 -0.02229946 0.02108019 0.02742165 0.0223031 0.01941341 0.03455084 -0.01131874 0.004308938 0.03619343 -0.004415571 0.004685103 0.03114449 -0.01516968 0.01085263 0.03062421 -0.008049011 -0.006268441 0.03266227 0.01150929 0.01285141 0.0284667 0.01912951 0.0120905 0.02995878 0.0153076 0.007268726 0.02256876 0.03219044 0.0431627 0.02097707 0.03169119 0.04133385 0.03262215 0.01822644 0.01249051 0.02868258 0.02404445 0.01449686 0.03087717 -0.02087259 0.01042401 0.03069138 -0.01765322 -8.12224e-4 0.02115857 -0.03587931 0.03656637 0.02416718 -0.03050917 0.02049839 0.02376276 0.03247177 0.04293471 0.02287697 0.03337454 0.03751689 0.03391033 0.01103472 4.36937e-4 0.03604048 0.001860082 7.39581e-4 0.03489381 0.003120899 -0.004112839 0.03284865 0.00118947 0.00122416 0.03371757 0.005972087 0.00977993 0.02651673 -0.02568364 0.008270978 0.02477663 -0.02059102 -0.002940058 0.02442437 -0.02402865 0.009108603 0.021842 0.02978581 0.03230857 0.02475243 0.02596604 0.02426815 0.01578497 -0.03862607 0.03891235 0.02041661 -0.03277093 0.03430813 0.01651877 -0.0355913 0.03979605 0.008727908 -0.03916567 0.04221093 0.02146881 -0.02807611 0.01481437 0.02433854 0.02848351 0.01550245 0.02204281 0.03264576 0.03011596 0.01880365 -0.030864 0.02030593 0.01601004 -0.03371381 0.01175004 0.01435321 -0.03574788 0.01965463 0.02008831 0.03462874 0.04234093 0.01351279 0.03638929 0.04349201 0.008757591 -0.04052227 0.03919529 0.00188148 -0.04110515 0.04008835 0.03502804 -0.008570969 -3.91072e-6 0.031017 -0.00113368 -0.009829223 0.0293681 0.0112428 -0.006565093 0.03037875 0.006032407 -0.009778201 0.03073215 0.01741415 -5.96249e-4 0.02794349 0.0220291 0.001277148 0.0292133 -0.01297533 -0.004842758 0.02545797 -0.02528375 9.8557e-4 0.02319455 0.02277159 9.44331e-4 0.02028143 0.02831673 0.01829016 0.02126991 -0.03013849 0.008701622 0.01603186 0.03316384 0.03446292 0.01278978 0.0350362 0.04150861 0.03325062 -0.01113414 -0.003560006 0.01691007 0.03601002 0.03507763 0.008081734 -0.0377255 0.02120947 0.03292566 -0.006426811 -0.01267558 0.03343725 -3.48183e-4 -0.01311421 0.03337901 0.005156338 -0.01160311 0.03074085 0.01103913 -0.01818746 0.02945911 0.01622629 -0.01200449 0.02603995 -0.02328127 -0.003166079 0.02870529 -0.01756685 -0.01104241 0.02917677 -0.004117429 -0.01892501 0.02678954 -0.009386897 -0.02440416 0.02613383 -0.01340848 -0.01941043 0.02656126 0.01737952 -0.004352152 0.02409029 0.02678704 0.004539489 0.01751947 0.03311353 0.01749664 0.01217418 0.03803449 0.04184222 0.01267719 -0.0344327 0.02513945 0.00904119 -0.0377146 0.04001277 0.02049982 -0.02609264 0.00281471 0.02990728 -0.01318299 -0.01670837 0.003233075 0.03889274 0.04429751 0.005906462 0.0366764 0.0426948 -7.10538e-4 -0.04059666 0.04309719 0.003200948 -0.03845489 0.04058194 -0.004724323 -0.03939926 0.04323011 0.02844172 0.00448513 -0.02258849 0.01463979 -0.02947437 0.001270473 0.03048509 -0.007987201 -0.02464497 0.03130584 -0.002428054 -0.02600842 0.03134429 0.002724468 -0.02533805 0.02654463 0.01143753 -0.02308279 0.02580165 -0.01696455 -0.01063585 0.01780456 -0.03051519 -4.63089e-4 0.01972019 -0.02785551 -0.008084475 0.01891124 0.0308569 0.006659984 -6.82211e-4 -0.0382775 0.02138853 0.0304917 0.008104324 -0.02554386 0.02572923 0.01573669 -0.01538616 0.02551692 0.02163732 -0.01344639 0.02049171 -0.0204038 -0.02275699 0.01707196 -0.02402794 -0.01990294 0.01035475 0.03788739 0.03367453 0.004267692 0.03936696 0.04127174 0.01814752 0.02628284 -0.00272423 0.02056401 0.02145618 -0.01891094 0.01433998 0.03105229 0.01544117 0.008977055 -0.03562259 0.009174525 0.009242177 -0.03265476 -0.00900036 0.01146894 0.03548401 0.01752346 0.01109635 0.03396081 0.02757143 0.02927559 0.01271873 -0.02472174 0.02625763 0.01812696 -0.02402949 0.02363449 -0.02380609 -0.01152962 0.02619463 -0.01685082 -0.02579206 0.005759954 -0.03617048 0.02634912 0.006439507 -0.03337645 0.00940448 0.01175761 -0.03219765 0.01026475 0.007582247 0.03575831 0.03568744 0.01932871 0.0293622 -0.001439511 0.02276396 0.02545303 -0.009145736 0.01522958 -0.02656924 -0.01245272 0.01388126 0.03318822 0.005948603 0.003780007 0.03878158 0.03376853 0.003049612 -0.0367003 0.01074856 0.03019648 -1.36525e-4 -0.03176337 0.02910661 0.003857731 -0.03793561 0.0218271 -0.01531356 -0.035501 -0.00537765 -0.04027128 0.04043245 -0.01633828 -0.03766471 0.0437498 0.02927851 -0.007157742 -0.031304 0.02696961 -0.01238471 -0.03385245 0.0279302 0.01336991 -0.02882307 0.02752834 0.008950889 -0.04192495 0.02793723 0.001021921 -0.02784359 0.02605831 -0.004997372 -0.03202825 0.02421754 -0.01126563 -0.03454464 0.02184408 0.02409034 -0.02115261 0.008453845 0.03259813 0.01199811 0.002594947 0.03445941 0.02037549 -0.001737475 -0.03622561 0.02577823 -0.002978384 -0.03813451 0.04054915 0.01657027 -0.02726852 -0.02202147 0.02009934 -0.02274358 -0.03022098 0.01358342 -0.03087615 -0.01001173 0.0118457 -0.03004705 -0.0196011 0.01612126 0.02987241 -0.01084101 0.01034015 0.03287982 -0.006946146 0.007962286 -0.02919882 -0.01565974 0.008326709 -0.03130388 -0.00139743 0.001143991 0.03627961 0.0360201 -0.003089308 0.03651779 0.0425992 -0.003814339 0.03903919 0.04480868 -0.00407499 0.03858405 0.03377646 -0.01290839 0.03477972 0.04457378 -0.004803121 -0.03956633 0.03284424 0.02701312 0.009612917 -0.02643305 0.01378697 0.028602 -0.003751754 0.01364737 0.02668941 -0.01859301 0.009544014 0.02991926 -0.006654739 0.008168816 0.03473132 0.004034817 0.005480289 0.03676277 0.01770335 0.002389907 -0.034653 0.01475375 0.02335387 -0.01788574 -0.03558814 0.002563655 -0.03237247 -6.56583e-4 -0.001532316 -0.03376674 0.009092986 -0.01033776 -0.0365374 0.04176354 -0.01902532 -0.0350759 0.04421758 0.02265429 0.01743805 -0.02599525 0.02239841 0.01623928 -0.03424894 0.02866601 -0.003515899 -0.03969109 0.02866542 -0.001339375 -0.04203253 0.02554583 -0.01281869 -0.04205304 0.02690362 -0.009137749 -0.04177343 0.02595412 0.003917872 -0.03811568 0.02615106 -0.003397464 -0.03724569 0.02134191 0.02112263 -0.03852826 0.02532565 0.01586228 -0.03789258 0.009921967 -0.02602636 -0.03043138 0.01629775 -0.02222198 -0.03067278 0.004947483 -0.03470385 -0.001664817 0.02329778 -0.01054733 -0.03889775 0.01811802 -0.01859891 -0.03849256 -0.001457571 0.03722167 0.01953125 -0.007780551 -0.03622978 0.03328174 0.02858239 0.003627121 -0.04197293 0.02753579 0.005255043 -0.04195761 0.02095079 -0.01934313 -0.04207181 0.01727116 -0.0226925 -0.04204064 0.01276862 -0.02578431 -0.04196941 0.01405417 -0.02635192 -0.03341501 0.01872843 0.02132409 -0.02919298 -0.001499593 -0.03624761 0.007468819 -0.008065879 -0.03698182 0.0203424 -0.005764424 -0.03328216 0.009421288 -0.01103574 -0.03242623 0.01347368 0.02702569 -0.006351888 -0.04203373 0.02562755 0.01283723 -0.04186296 0.02379274 0.01334953 -0.03613454 -0.007255971 0.0383802 0.04190301 -0.01481759 0.03500622 0.0451973 0.001490235 -0.03357225 -0.01124703 0.005642175 -0.03190666 -0.01883065 0.001662373 0.03287416 0.00526309 0.004434287 0.03102397 -0.007762074 -0.00400269 0.0344327 0.02189761 -0.006252825 0.03566533 0.0370807 -0.01066523 0.03461223 0.04265773 -0.01104271 -0.03845679 0.036085 0.02303075 -0.006865262 -0.04070413 0.02438259 -0.001399159 -0.04059314 0.01681113 0.02746051 -0.02467948 0.0119732 0.03070026 -0.02041429 0.001312077 0.03616333 0.008322775 0.006196022 -0.009589731 -0.04175382 0.004811406 9.62761e-4 -0.04163974 0.02283835 -0.01574945 -0.04206335 0.02245789 0.01034301 -0.04033285 0.01880586 0.02461278 -0.03322726 -0.01719844 -0.03332215 0.04197293 -0.0130648 -0.0345143 0.03352344 0.02369266 0.01709663 -0.04179656 0.008373916 -0.02911257 -0.03204804 0.005444943 0.03407055 -0.00673145 0.00643593 0.03249412 -0.01925522 0.01883721 0.01785266 -0.03922706 0.01700705 0.02152049 -0.03615909 0.02166509 1.26243e-5 -0.04110383 0.006295859 0.029428 -0.01877152 0.007594883 0.0268079 -0.03662222 0.01299101 0.02463084 -0.0351333 -0.001486063 -0.02924638 -0.02232861 -0.002369701 -0.03006559 -0.01795995 0.006496667 -0.02744662 -0.02869063 -0.00569123 -0.03514224 0.003077566 -0.006404995 -0.03337514 -0.00968486 -0.006655812 0.03652912 0.01849174 -0.01084113 0.0368281 0.03285014 -0.01170891 0.03374826 0.03561562 -0.00859332 0.03329622 0.02025884 -0.01322388 -0.03310632 0.02522832 0.01876831 -0.01376068 -0.04121136 0.001555919 0.013601 -0.04147791 0.01929545 0.02274727 -0.04167056 0.009331762 0.03011947 -0.03292363 0.01273012 0.02753853 -0.04153364 -0.003070592 -0.03119146 -0.008018732 -0.006971657 0.03222554 0.004602134 -0.01597255 0.03514903 0.0432682 -0.02376866 0.02764874 0.0449447 -0.01870954 0.03029036 0.04301673 -0.01872664 -0.03527283 0.03924489 -0.01852321 -0.03454715 0.03196734 -0.01344597 -0.03568863 0.02366876 -0.02018243 -0.03655362 0.04391342 0.0210908 0.02186757 -0.04160392 0.01136964 -0.02682453 -0.03925734 0.01959961 0.01292139 -0.04073286 0.01305478 -0.02150267 -0.03987705 0.01355248 -0.0230835 -0.03594553 0.01318711 -0.02357506 -0.03124427 0.01305222 -0.02333295 -0.03149747 0.006583452 -0.02558302 -0.03841239 -0.009644269 -0.03395825 8.90062e-4 -0.01396918 -0.03390181 0.01234221 -0.01721698 0.03069829 0.03406792 -0.0198459 -0.03074938 0.03507894 0.01417279 0.008519649 -0.04015344 0.0152114 -0.005285561 -0.04048955 0.007228016 -0.0226587 -0.04082125 -3.44989e-4 0.03473341 -0.005529403 -0.00481534 0.0354706 0.004576981 -0.02549582 0.02790182 0.04474192 -0.02429074 -0.03192657 0.04424268 -0.02615171 -0.0267778 0.0435537 0.01090884 0.02186089 -0.04013687 0.01317387 0.02295339 -0.03883719 0.009927034 -0.02528566 -0.04194802 0.001145362 -0.03146427 -0.02643293 0.007474958 -0.02778112 -0.04188716 -4.88176e-4 -0.02992701 -0.03753697 -2.5626e-4 0.03295814 -0.0230599 -0.00235325 0.03137004 -0.008675456 -0.008561074 -0.03012698 -0.009137034 -0.01455396 -0.02917212 7.7243e-4 -0.01800751 -0.02863049 0.0119065 -0.02295249 -0.02891528 0.04169631 -0.001045525 -0.03242236 -0.01963424 -3.92803e-4 -0.003444194 -0.03941637 0.006617784 -0.0149213 -0.04023253 -0.01271539 0.03478461 0.01958864 -0.011599 0.03379762 0.004024147 -0.02481412 -0.03054827 0.03957694 -0.02282845 -0.03158426 0.03153204 0.005229592 0.01803553 -0.03956568 -3.76565e-4 0.008102476 -0.03923165 4.04403e-4 -0.02771204 -0.03510433 0.002405881 0.02906972 -0.02917379 -0.01318019 0.03165918 0.02181911 -0.0137524 0.02974408 0.005256116 -0.01850563 0.03291356 0.03167778 0.005323648 0.02565932 -0.03905117 -0.005029559 0.02549445 -0.03924614 -0.00201404 -0.02353727 -0.04045927 -0.00202763 -0.02597081 -0.03920626 0.004670321 0.03059625 -0.04137396 0.004983723 0.03059875 -0.0383048 -0.005841791 0.03082489 -0.04120522 -0.01261729 0.02855193 -0.04112201 0.004086792 0.03149819 -0.03365826 -0.004921078 0.03416556 -0.008473336 -0.005091786 0.03325235 -0.01834082 -0.02200788 0.03134965 0.04091495 -0.01983511 -0.03226947 0.02371168 0.00237745 0.02791512 -0.03702729 -0.009414315 -0.02774739 -0.02475637 -0.007323563 0.03047657 -0.01100164 -0.01090061 0.0290389 -0.01487571 -0.0204463 -0.03148949 0.01711654 -0.007738351 -0.03088057 -0.02527326 -0.00415337 -0.02810221 -0.03049206 -0.01135063 0.03345215 -0.002838909 -0.01544475 -0.03063315 -0.007109999 -0.0154103 0.03229707 0.005154013 -0.02001059 0.03054195 0.01853942 -0.02459466 0.02540606 0.04334682 -0.02255398 0.02656894 0.03392195 -0.02212417 -0.02642613 0.01888084 -0.01573789 -0.0295394 -0.01524895 -0.01695114 0.02942097 0.02106082 -0.02860158 -0.02221608 0.04119491 -0.02639156 -0.02360129 0.0295605 -0.03012371 -0.02480387 0.03730571 -0.02741163 -0.02792459 0.034653 -0.03185206 -0.02106422 0.04461491 -0.02699184 -0.02774399 0.04391252 -0.03258806 -0.01691174 0.0440191 -0.01052981 0.01632237 -0.03873938 -0.007012486 -0.01714587 -0.03968113 -0.007721185 0.0281288 -0.03458243 -0.001864135 0.0288093 -0.03353285 -0.0138958 -0.028122 -0.009762465 -0.01372498 -0.02635812 -0.02295148 -0.02094829 -0.03003799 0.01029056 7.47729e-4 -0.02882462 -0.04183322 -0.02706605 -0.02610665 0.02117699 -0.02456444 0.02821308 0.03253895 -0.007478296 -0.02816331 -0.04170173 -0.01075816 -0.01613497 -0.04154461 -0.02980369 0.02213418 0.04554909 -0.00642699 -0.0266813 -0.03717482 -0.01078051 0.03141546 -0.02541196 -0.001626074 0.03128898 -0.0390774 -0.007827579 0.03192037 -0.03004008 -0.0154345 0.03165936 -1.86869e-4 -0.02061498 -0.02332764 -0.01209503 -0.02246218 -0.02284449 -0.003480792 -0.02832251 0.02533733 0.04114633 -0.01398366 0.003107488 -0.03872776 -0.01680606 -0.007920861 -0.03900086 -0.00581783 -0.02884387 -0.04151046 -0.01009374 -0.0297178 -0.02976977 -0.03235965 -0.02220237 0.04183566 -0.005853593 0.02736592 -0.03782236 -0.01136934 -0.02345329 -0.03943085 -0.01781463 -0.01764583 -0.03959876 -0.01075154 0.03295832 -0.007190942 -0.02185028 0.02506744 0.01467466 -0.01906353 0.02654355 0.006581127 -0.02581274 -0.02137899 0.01134151 -0.02838373 0.02083599 0.0430516 -0.02732503 0.02159172 0.03526002 -0.0310111 0.01856654 0.04519057 -0.01226091 0.03185588 -0.01424121 -0.01551866 0.02690201 -0.01405179 -0.02476036 0.0228064 0.02215027 -0.03081399 -0.02137327 0.0213865 -0.03264915 -0.02006793 0.03141188 -0.03318715 0.01834356 0.04284083 -0.0354923 0.01346248 0.0453543 -0.01119804 -0.02558755 -0.03658747 -0.01956713 -0.02325606 -0.01827412 -0.02418315 -0.02634614 0.00159496 -0.02259635 -0.02590674 -0.01017445 -0.02847242 -0.02312737 0.01058793 -0.02923899 0.02302825 0.03090167 -0.02519863 0.02661424 0.02440398 -0.03483492 -0.01758503 0.04209655 -0.03645342 -0.008888065 0.04505032 -0.03290545 -0.01451307 0.04134595 -0.02952587 -0.01929771 0.03033167 -0.02429866 0.02543807 0.0043931 -0.02484065 0.0264849 0.01725417 -0.03354543 0.01274693 0.0447961 -0.03231978 0.01381808 0.04289752 -0.03057891 0.01654165 0.0355733 -0.03431761 -0.01044756 0.04328304 -0.01770752 0.02910518 -0.0128979 -0.02836292 0.01752465 0.01920515 -0.03180944 -0.01326543 0.02514654 -0.03388255 -0.006831407 0.02830642 -0.0143516 0.02240318 -0.03891229 -0.02436733 0.02143192 0.005694091 -0.01415342 0.02554064 -0.03574699 -0.03519821 0.003868401 0.04379361 -0.03352195 0.009744703 0.03669089 -0.02935481 -0.01557946 0.01049244 -0.03279614 0.01611256 0.02511626 -0.03543841 0.01126253 0.03083568 -0.03675413 0.007003068 0.04557228 -0.008480131 -0.02876287 -0.04199671 -0.008400678 -0.0286715 -0.04210263 -0.01281851 -0.02804213 -0.04160934 -0.01212352 -0.02762454 -0.03903728 -0.01794296 -0.02628636 -0.03150027 -0.02007824 0.02394777 -0.01099544 -0.03736627 -0.008992254 0.04156345 -0.03489643 -0.013071 0.02227288 -0.03692632 -0.00195378 0.04499328 -0.03818428 -0.002311348 0.04203921 -0.02973467 0.02076679 0.0198906 -0.03060436 0.0134117 0.0197466 -0.0353192 -0.00483793 0.04344934 -0.03493893 -0.002574861 0.03512829 -0.01828104 -0.02333188 -0.02597111 -0.01780003 -0.0219801 -0.0363813 -0.0197032 -0.02619493 -0.02183341 -0.02867108 0.02035492 0.004320383 -0.02753269 -0.01684075 -9.48066e-4 -0.03685528 0.008919239 0.04320883 -0.03638422 -0.007347047 0.02292919 -0.0130127 0.02947461 -0.03536272 -0.01409947 0.03014016 -0.02890038 -0.01861906 0.02738821 -0.02622425 -0.02107441 0.02783542 -0.001493692 -0.01688235 0.02438193 -0.03221833 -0.02497965 -0.01769417 -0.01831924 -0.03203707 -0.01751023 0.01043862 -0.03173196 -0.01017582 0.01356631 -0.03404694 0.002745449 0.02673542 -0.03305464 0.007972002 0.02593934 -0.02113658 0.01584464 -0.03864538 -0.02540755 0.007772207 -0.03864896 -0.02530026 -0.002625882 -0.03887385 -0.02713531 -0.02201437 -0.004052281 -0.02993839 -0.01829385 -0.004706263 -0.02604603 0.02291786 -0.002595603 -0.03791397 0.001863539 0.04029923 -0.03057515 -0.009162127 -0.003695189 -0.03289294 0.01487207 0.01707857 -0.02806329 0.01604366 0.004715621 -0.02003014 -0.01838153 -0.0384432 -0.02549964 0.01731377 -0.01643568 -0.03299522 -0.003561615 0.01307141 -0.03642159 0.004166841 0.02348285 -0.03713077 -0.001463115 0.02574825 -0.02357965 0.02428525 -0.01995193 -0.02193087 0.02544134 -0.01740676 -0.02352529 0.02486097 -0.009978115 -0.02432924 -0.02313107 -0.01878112 -0.02894562 -0.01140969 -0.01257163 -0.03544533 0.008637905 0.02325117 -0.0310744 0.01004886 0.008924603 -0.03586649 -0.006595671 0.01494127 -0.03367233 -0.01257073 0.006471633 -0.03283774 0.003284037 0.01306819 -0.0190742 0.02056312 -0.03782618 -0.01986241 -0.02398496 -0.04145121 -0.03184455 -0.004838883 -5.92676e-4 -0.0363807 -0.002640366 0.01618534 -0.02289795 -0.01721823 -0.0362609 -0.02549695 -0.01413106 -0.03464651 -0.02533733 -0.01561337 -0.02429354 -0.02125459 0.02127528 -0.02641254 -0.02578574 -0.02054941 -0.02489984 -0.02230238 -0.02322369 -0.03220254 -0.02783548 -0.01130253 -0.02532213 -0.02900689 0.01289772 -0.003711938 -0.01771044 0.02740579 -0.03039437 -0.01618677 0.02744054 -0.04106533 -0.02987861 0.01747936 -0.006665229 -0.03201937 0.01324588 -0.001373469 -0.02771091 -0.0195685 -0.01777136 -0.03208446 -0.01346647 -0.007386684 -0.03428924 0.01014101 0.01423281 -0.0359683 0.005392491 0.01683825 -0.03226584 0.01403379 0.005975544 -0.0311346 0.008079349 9.44295e-4 -0.03200268 0.00236845 -8.15881e-4 -0.02049928 0.0214709 -0.03411442 -0.03090876 -0.01270461 -0.02376687 -0.02626883 0.0211361 -0.01434457 -0.02604812 0.01513165 -0.02502006 -0.02914148 0.01040685 -0.01492458 -0.03477764 -0.004344463 -0.001489996 -0.0342186 -0.007567703 -0.003439486 -0.03566569 5.28313e-4 0.008729398 -0.01066434 0.01050305 -0.04131293 -0.02580171 0.01883524 -0.04099076 -0.03127056 0.004525959 -0.04103893 -0.02356189 0.02276617 -0.03119677 -0.02636265 0.02001029 -0.02364295 -0.02985829 -0.006861925 -0.01909035 -0.03126639 -0.001507937 -0.01073634 -0.03530782 0.005448639 0.01198309 -0.03449153 0.004043579 -0.003838062 -0.02529245 -0.01018047 -0.03860718 -0.02463394 -0.01971089 -0.03858518 -0.02506858 -0.0199939 -0.04137831 -0.02909159 -0.01264023 -0.04120665 -0.0307874 0.003309965 -0.01409238 -0.02210146 0.02302038 -0.04086935 -0.02763724 -0.01706284 -0.03342795 -0.03243082 -0.009818077 -0.01778733 -0.02999889 0.01576268 -0.01049435 -0.0305581 0.0143482 -0.01609879 -0.03262215 0.01084095 -0.006177902 -0.02423894 0.01509618 -0.03727728 -0.02898371 0.00532484 -0.03600531 -0.02795171 0.001752197 -0.03780269 -0.03452801 -0.00140804 -0.008445978 -0.02535676 0.01510429 -0.03535711 -0.02909958 0.00737971 -0.02574646 -0.03314524 -0.004383444 -0.02316516 -0.03158217 -0.00649321 -0.03789818 -0.03022837 8.24393e-5 -0.02347987 -0.03314173 0.002977609 -0.02424263 -0.03218334 0.009452998 -0.01893281 -0.02775621 -0.004507899 -0.03775846 -0.02812063 0.01641339 -0.03474211 -0.0289793 -0.006054997 -0.03473061 -0.02787601 0.01021534 -0.03433054 -0.02958768 3.18229e-4 -0.03537642 -0.03138035 0.009073793 -0.03150695 -0.03234803 -0.001040339 -0.03643912 -0.03218376 0.003944933 -0.03590452 -0.03103446 0.01026552 -0.04055923 -0.03027427 0.0129655 -0.04096156 -0.03178244 -0.005843997 -0.04111582 -0.01824915 -0.004848599 -0.04132801 -0.03247088 -0.002261459 -0.04106044 - - - - - - - - - - 0.4995402 1.52597e-4 0.8662908 -0.7039831 -0.09366297 0.7040137 0.7702479 -0.1473475 0.6204894 0.9986433 0.03527998 0.03830134 0.3961345 0.05243134 0.9166943 -0.157753 -0.02917617 0.9870475 0.8861178 -0.4595239 0.06027489 0.9372413 -0.3290874 -0.11524 0.9856701 -0.1270198 -0.1109973 0.9754788 0.2077733 -0.07260465 0.9259874 0.3773717 -0.01174992 0.5861809 0.3005829 0.7523576 -0.5480034 -0.3820703 0.7441201 -0.8743741 -0.3634222 0.3215499 -0.96246 0.06961476 0.2623448 -0.9616006 -0.1702669 0.2152522 0.9856918 0.01870793 -0.1675169 -0.893812 0.2280995 0.3860967 0.5236501 -0.3330571 0.7841323 -0.4964628 0.3703557 0.785087 -0.8527658 0.4059961 0.328569 0.07278764 -0.006195306 0.9973283 0.6591619 -0.6159156 0.4314553 0.9135807 0.37471 -0.1579959 0.9827331 0.0693385 -0.1715456 0.9394075 0.3014369 -0.1632465 0.7578226 -0.6365393 -0.1432572 0.8501981 -0.5017322 -0.1594617 0.4725052 0.3534786 0.8073362 0.8121138 0.5823659 0.03634822 0.9682906 -0.167918 -0.1849784 0.8108458 0.5589978 -0.1733515 -0.9826512 -0.07574814 0.1692889 -0.9785523 0.1008338 0.1796332 -0.9637296 0.2019748 0.1744467 0.9004127 -0.3957445 -0.1806746 -0.7147226 0.635465 0.2921576 -0.9538176 -0.252333 0.1629727 -0.8827952 -0.4431372 0.1558915 -0.8375009 -0.4672756 0.2832769 -0.8407503 0.5162063 0.1633096 -0.9357449 0.3035731 0.1795131 -0.8348841 0.5207496 0.1782933 -0.9604282 -0.2194305 0.1715464 -0.9845693 -0.02566635 0.173103 0.7776912 -0.6009848 -0.1844277 -0.3403797 -0.4609912 0.8195297 -0.7069718 -0.6692199 0.2287701 0.4802865 0.5181308 0.7077184 0.6994768 0.7135768 -0.03924804 0.4916626 -0.731329 0.4726797 0.6457861 -0.7508636 -0.138435 0.963325 0.2208948 -0.1523497 0.9824398 -0.0792275 -0.1689231 0.9875962 0.06177049 -0.1443551 0.8281143 0.5305193 -0.1810413 0.8911184 -0.4205796 -0.1703559 0.9549261 -0.2434544 -0.1698412 -0.7366724 0.6515238 0.1811925 -0.4621499 0.7844311 0.4136247 -0.6307821 0.7596974 0.1580312 -0.9773355 0.127111 0.169288 0.2213831 -0.523702 0.8226334 0.9023003 0.3982756 -0.1650173 0.6746008 0.7233708 -0.147134 -0.7520913 0.6321193 0.1865044 -0.7443774 -0.6500103 0.1529346 0.9306963 -0.3323588 -0.1527813 0.9809367 -0.112584 -0.1583928 -0.8848478 0.4317269 0.1750895 -0.9547326 0.2402778 0.1753634 -0.9276674 -0.3372697 0.1602573 -0.806921 -0.5712231 0.1502753 -0.8710946 -0.4652125 0.1573903 -0.1541526 -0.2784879 0.9479882 -0.4587374 -0.8166081 0.3503019 0.8394001 0.5201998 -0.1574791 0.7450743 0.6506468 -0.1467075 0.8148572 -0.5541945 -0.1699298 0.8484895 -0.500939 -0.1706623 0.4908416 -0.8661068 -0.09451818 0.6054722 -0.7765328 -0.1743566 0.42785 0.6303457 0.6477721 0.5206871 0.852064 -0.0535916 0.9330783 0.3229792 -0.1582699 0.9804759 0.0247507 -0.1950758 0.9820389 0.08520889 -0.1683425 -0.9852788 -0.04654163 0.164498 -0.9698883 -0.1834791 0.1601628 0.703066 -0.6940323 -0.1549754 -0.7618239 0.6257076 0.1676732 -0.7120969 0.6815475 0.1685557 -0.5522448 -0.82295 0.1333383 -0.6506754 -0.7426001 0.1586403 0.3557305 -0.934586 -0.002227842 -0.4888607 0.8567118 0.1644998 -0.3880574 0.9185196 0.07571923 -0.01492381 -0.0363788 0.9992267 -0.602824 0.7794412 0.1705132 0.6153567 0.7761008 -0.1378548 0.5249301 0.8398272 -0.1383435 -0.4696882 0.8672905 0.1649249 0.409072 -0.8979198 -0.1624813 0.320024 -0.9340698 -0.158425 0.3932437 0.8531419 0.3427949 0.08523964 0.05298101 0.9949509 0.1545484 -0.9857958 0.06573802 0.03970479 -0.9968324 0.06891119 0.9599557 -0.2378373 -0.1480494 -0.9849459 0.02447634 0.1711211 -0.9177967 -0.3650373 0.156196 -0.9678794 -0.1890956 0.1656876 0.8581342 0.4909597 -0.1502147 0.772207 0.6187545 -0.1443577 -0.8947536 0.4144164 0.1663586 0.6956336 -0.6966103 -0.1755793 -0.6999633 -0.6994751 0.1441738 -0.5560271 -0.8184301 0.1449351 0.5592342 -0.8132762 -0.1607447 -0.3845965 -0.9154387 0.1185651 -0.2516598 -0.9023864 0.349809 0.9052084 -0.3843321 -0.1813468 0.3758735 0.9229289 -0.08319509 0.1634913 -0.9749048 -0.1511005 0.9633569 -0.1968158 -0.1822278 0.9857648 -0.02475088 -0.1662982 0.9741438 0.1564416 -0.1630033 0.9273222 0.3450487 -0.1449656 0.8641966 0.4801974 -0.1502486 0.7453486 -0.6403308 -0.1855589 0.8324002 -0.5286161 -0.1663579 -0.9743539 0.1272037 0.1856173 -0.9402616 0.2841629 0.1875091 -0.8872302 0.4288284 0.1700847 -0.8234801 -0.5465146 0.1523233 0.6542394 0.7442099 -0.13462 0.4446293 0.8862068 -0.1301629 0.2725954 0.9284176 0.2524529 -0.3047895 0.9386003 0.1616571 -0.1739913 0.9229077 0.3434657 -0.6051702 0.7767201 0.1745712 0.9018126 -0.396933 -0.1708161 0.09070438 0.3917503 0.9155897 -0.09564602 -0.8755854 0.4734997 0.01086497 -0.6381963 0.769797 -0.01092582 0.9602538 0.2789143 0.1341016 0.4796101 0.8671742 -0.9795364 -0.1325743 0.151435 -0.4333764 0.8861631 0.1640115 0.9434833 -0.282581 -0.1731683 0.9790935 -0.09338939 -0.1807054 0.9826253 0.07742708 -0.1686794 -0.9132422 -0.387191 0.1267747 -0.8233385 0.5433277 0.164039 0.4865379 -0.8579572 -0.1648955 0.5670145 -0.8070778 -0.1646811 0.5040834 0.8538319 -0.1298891 -0.04583972 -0.9882711 -0.1456679 0.9585554 0.2304525 -0.1675213 -0.8399148 -0.5223336 0.147346 0.7719767 0.6202366 -0.1391358 -0.7110514 0.6830343 0.1669436 -0.5772086 0.7996931 0.1652916 0.2114366 0.9718517 -0.1039177 0.07605427 0.9960606 0.04559588 -0.5617631 -0.8169018 0.1307433 -0.6909568 -0.710245 0.1346511 -0.3978841 -0.9078059 0.1325772 0.2268807 -0.962 -0.1519252 0.2640845 -0.9525416 -0.1514068 0.279127 0.9531397 -0.1166742 -0.2585302 -0.9573339 0.1291278 0.904234 0.3939161 -0.1648973 0.8226621 0.550832 -0.1407522 0.701313 -0.6931032 -0.1666377 0.8263701 -0.536254 -0.1718845 -0.1188422 0.9813486 0.1511011 -0.1544596 0.9761387 0.1526285 -0.3154483 0.9361819 0.1550995 -0.164712 -0.9805507 0.1067255 0.5215122 0.8429101 -0.1323923 0.65396 0.7436246 -0.1391358 -0.4672246 0.8694425 0.1605331 0.3698933 0.9204301 -0.1264412 0.05771106 0.9934487 -0.0986368 0.06778252 -0.9868598 -0.1466739 0.9829563 -0.05380499 -0.1757895 0.9780969 0.112187 -0.1753304 -0.79699 0.5477971 0.2544117 -0.1768574 -0.9839314 0.02450668 -0.2331029 -0.7921779 0.5640189 0.9535655 -0.2370714 -0.185769 0.8946768 -0.4182991 -0.1567782 0.8995544 0.4035863 -0.1670928 0.6447221 0.1805832 -0.7427808 -0.9860028 0.006500482 0.1666023 -0.9652796 0.2253814 0.1320549 -0.9087055 0.3665952 0.1996558 0.6828753 0.7185222 -0.1319361 -0.2330457 -0.9652965 0.1178657 -0.0631749 -0.9915413 0.1133791 0.08966499 0.9853386 0.1451486 0.1288531 0.9439362 0.3039432 0.5268773 -0.834141 -0.1631232 0.663064 -0.7307559 -0.162302 0.4090194 -0.9004409 -0.1480185 0.3631714 -0.9186405 -0.1555838 0.4895642 0.8641918 -0.1161879 0.3211547 0.9406356 -0.109839 -0.2567242 0.9538347 0.1558595 -0.2469601 0.9568331 0.1532361 0.01052898 -0.9955254 0.09390652 0.168986 -0.9522671 0.2542268 -0.06302136 0.6573145 0.7509768 -0.13169 0.9882097 -0.07809847 0.3043687 -0.6300095 0.7144563 -0.1606204 -0.9783717 -0.1303458 -0.9461838 -0.2996976 0.1221374 -0.4304979 -0.8941392 0.1232348 -0.4748423 -0.8707628 0.1276602 -0.3055225 -0.9444921 0.1207929 0.2177857 0.9699338 -0.1086181 0.1289119 0.9862188 -0.1037033 -0.04397815 0.9864107 0.158303 0.7941983 -0.5856003 -0.1622394 -0.07245296 0.9864777 0.1470118 0.04370313 0.9882959 0.1461553 0.3120906 0.8856404 0.3438612 0.1687996 0.1662055 0.9715362 -0.8040798 -0.5804988 0.1283622 -0.7826251 -0.583154 0.2177824 0.9586326 -0.2023105 -0.2002352 0.6688662 -0.06979817 -0.7400988 0.5994018 -0.3314716 -0.7285906 0.7946379 -0.21382 -0.5681828 -0.888118 -0.1292501 0.4410681 -0.9369781 0.1614785 0.3098336 0.7618235 0.6434085 -0.07516908 0.8595319 0.4806103 -0.1738352 -0.4098384 0.8943872 0.1791765 -0.5765632 0.7966045 0.1816485 0.122932 -0.9811064 -0.1493923 -0.7878208 0.3630556 0.4975228 -0.6300131 0.6160656 0.4728074 -0.04187184 0.9929316 -0.1110582 0.2457994 0.9597899 0.1355956 0.6835326 0.2108858 -0.6987921 0.4968822 0.1213136 -0.859297 0.5217896 -0.4206179 -0.74217 0.4026714 -0.5255116 -0.7494621 0.2080798 -0.6615034 -0.720497 0.4887635 -0.8592961 -0.1507338 -0.6697381 -0.7309591 0.1309567 -0.05819934 -0.9885961 -0.1388911 -0.2342022 -0.9620784 -0.1398376 0.1901353 0.9729556 0.131172 0.345995 0.9300389 0.1237549 0.498802 -0.07867789 -0.8631375 0.5388132 0.2707342 -0.7977365 -0.8440221 -0.4253529 0.3266522 -0.2738467 0.9606761 0.04593104 -0.1346819 0.4286138 0.893393 0.05209624 -0.9882115 -0.143959 0.1835123 -0.9715195 -0.1499106 -0.04458761 -0.9931666 0.1078527 -0.1508561 -0.9822283 0.1116696 0.11692 -0.9874264 0.1063908 0.2092673 -0.9750144 0.07452684 0.3312512 -0.915534 0.2281891 -0.3137392 -0.9419808 -0.1193308 -0.5327475 0.1467375 0.8334556 -0.5857797 0.03540188 0.8096969 0.5399446 0.8326842 -0.12287 0.3828632 0.915942 -0.1202761 0.03366297 0.9942339 -0.101813 -0.01559531 0.008697926 -0.9998406 -0.01565635 0.008728444 -0.9998394 0.4604447 -0.3377876 -0.8209082 -0.5594491 -0.229383 0.7964925 0.6311417 0.763718 -0.1356283 0.482104 0.7546359 0.4450848 0.4082592 0.9035295 0.1302266 0.5583483 0.343066 -0.7553496 0.2895991 -0.9441803 -0.1570225 0.161081 0.9810436 -0.1077332 0.2087527 0.9718598 -0.1091374 -0.5555134 -0.5077812 0.6584552 -0.6308 -0.7216554 0.2851403 -0.05945163 -0.02362191 0.9979518 -0.2714414 -0.9556297 0.114418 -0.3039414 -0.8825867 0.3586929 -0.4894327 -0.8439105 0.219706 -0.001281738 0.9887776 0.1493893 0.03787434 0.986747 0.1577843 -0.2271836 0.9623869 0.1489939 -0.1694098 -0.9771507 -0.128362 -0.1874783 -0.9727324 -0.136542 -0.1967262 0.9751771 -0.1016286 -0.34166 0.9370244 -0.07248258 0.3963249 -0.9154905 0.06930953 0.2883149 -0.9526265 0.0968374 0.4205863 0.8985184 0.1255868 -0.3138306 0.2334121 0.920342 -0.01568681 0.008758962 -0.9998386 0.3859175 0.5464189 -0.7432994 0.3447754 0.9308052 -0.1213749 0.3105615 0.616362 -0.7236363 0.1069385 0.9859766 0.1281186 0.2120153 -0.9723958 0.09744709 -0.457666 0.8751383 0.1570823 0.2664285 -0.2953603 0.9174848 0.5507235 -0.8081856 0.2086614 -0.4959619 -0.8417711 -0.2131742 -0.4857763 -0.8655894 -0.1215585 -0.3824623 -0.9143753 -0.132818 -0.4324535 -0.7764937 0.458303 0.553775 0.6268079 -0.5481289 0.3507581 -0.9035236 -0.2461991 -0.1711792 -0.1662963 0.9711042 -0.3863442 0.607945 0.6936433 -0.5070534 0.8277539 0.2402507 -0.2737541 0.8275798 0.4900718 0.05990964 0.9503449 0.3053776 -0.2395415 0.8378918 0.4904665 -0.289655 -0.9482225 -0.1302852 -0.3848531 -0.914339 -0.1259852 0.5380602 -0.839899 0.07114112 0.5851772 0.8035733 0.1088013 0.08743625 -0.003692746 0.9961633 0.09183061 -0.03155624 0.9952746 -0.08499526 0.3388519 0.9369927 0.0140081 0.9946708 -0.1021466 -0.1364829 0.9863882 -0.09171086 -0.5167462 0.5777535 0.6318024 -0.5396416 -0.4089276 0.7359111 0.5009527 0.4114075 0.7614396 -0.09894382 -0.2678381 0.9583699 -0.4051169 -0.6573917 0.635387 0.1069392 -0.3073281 -0.9455757 0.05865764 -0.9870784 -0.1491162 0.2208362 -0.638826 -0.7369754 0.03186231 -0.9849247 -0.170024 0.01815903 0.9946877 -0.1013243 0.03469973 -0.9938716 0.1049537 0.2554121 0.9581997 0.1289115 0.4548231 0.8817824 0.1248833 0.5413264 0.8327887 0.1158829 0.6519473 0.7466173 0.1323915 -0.01361143 -0.9895479 -0.1435613 0.05066144 -0.0275281 0.9983365 0.07269662 -0.0571013 0.9957181 -0.3916521 0.9160624 -0.08624702 -0.3210588 0.9434916 -0.08212631 -0.6797292 -0.7252336 -0.1095648 -0.6104426 -0.7844929 -0.1092277 0.06631743 0.022767 0.9975389 0.05313372 -0.008179068 0.9985539 -0.0666846 0.9659353 0.2500445 -0.1422781 -0.9826409 0.1190534 0.4299195 -0.8980182 0.09344881 0.4424069 -0.8925657 0.08719342 -0.5300832 0.844245 -0.07913553 -0.1216198 -0.5787091 0.8064146 0.06921762 -0.3259151 0.9428618 0.04892152 0.2142109 0.9755616 0.02697873 0.7305629 0.6823124 0.1460661 0.7133313 -0.6854366 0.2255395 0.9689347 -0.1014775 -0.1187202 0.6836025 -0.7201341 -0.2082297 0.6119019 -0.7630311 0.1700544 0.9777828 -0.1225662 -0.138894 0.9856567 -0.09586161 -0.1319019 0.9853277 -0.1083109 -0.6061105 0.7947494 0.03167885 -0.5447358 -0.8313714 -0.1099299 -0.09970676 -0.8893651 0.4461933 0.2620093 0.9568148 0.1259232 0.2047231 -0.9737473 0.09952324 0.3584794 -0.9291594 0.09030652 -0.5531623 -0.8271952 -0.09879094 -0.1898009 -0.9728096 -0.1327294 0.1313869 0.9824877 0.1321194 -0.3468231 0.930752 -0.1158213 -0.4255548 -0.8968879 -0.1203968 -0.4970929 0.8628016 -0.09204518 -0.5755234 0.8135395 -0.08322471 0.6726449 -0.664893 0.3247557 0.6695252 -0.7390473 0.07446628 0.6712771 0.732774 0.1114878 -0.4238805 -0.8987279 -0.1123104 0.5490387 -0.8314014 0.08560603 0.8180737 0.5560948 0.1466764 0.7662156 0.6356849 0.09390765 -0.7865128 -0.6157573 -0.04733538 -0.7308145 -0.6798169 -0.06131321 -0.331592 -0.2322517 0.9143883 -0.4405983 -0.3157769 0.8403322 0.7703613 0.3285983 0.5464127 0.02777242 0.01492387 0.9995029 0.02914553 -0.07391673 0.9968385 0.2223616 -0.9506984 0.2161663 0.01614445 -0.9839282 0.1778334 0.4434077 0.8883414 0.1193285 0.4358409 0.8924651 0.1163992 -0.567081 -0.8153869 -0.116462 0.0461753 -0.6364135 -0.7699648 -0.7158653 -0.6912056 -0.09885263 -0.6768726 0.7314703 -0.08243077 0.05352979 0.09021329 -0.9944829 -0.0162971 0.008423209 -0.9998318 -0.2844985 0.2859023 0.9150522 0.1779578 0.8998912 0.3981544 -0.2976174 0.9533708 -0.05008101 0.01709061 0.9874427 -0.1570508 -0.1770699 0.9803853 -0.08655124 -0.498503 0.8632093 -0.07977753 0.6414535 0.7585863 0.1143861 0.7137822 0.6932123 0.0998587 -0.7660952 0.6420038 0.03048872 0.02038651 -0.01733464 0.9996419 0.00589019 -0.0446496 0.9989855 -0.09348064 -0.7976527 -0.5958285 -0.2675905 -0.9534742 -0.1388614 -0.8172619 -0.5591037 0.1395928 0.1369084 -0.7973402 0.5877965 0.2565704 0.5152771 0.8177171 0.1956577 0.1606523 0.9674239 -0.3249659 0.939099 -0.1117604 0.6703324 -0.7379944 0.0775808 0.6072414 -0.7901433 0.08325648 0.786656 0.609402 0.09900337 0.7943236 -0.5841072 0.16694 0.7895994 -0.6092904 0.07278889 0.518161 -0.3001293 0.8008942 -0.3665633 0.9270138 -0.0792272 0.5051496 -0.8591387 0.08188229 0.7630784 -0.640909 0.08334863 -0.8434545 -0.5306955 -0.08334743 -0.8669309 -0.4901398 -0.0905202 -0.8586925 0.5061329 0.0804795 -0.6139236 0.245954 0.7500697 0.348069 0.8728733 0.3419651 0.6281791 0.7698803 0.1125857 -0.6597396 -0.7423864 -0.1166454 -0.6180443 -0.7795824 -0.1013543 -0.7680421 -0.6332395 -0.09549403 -0.7968947 0.5987622 -0.08026629 -0.7082274 0.7014521 -0.07986861 -0.9054023 -0.3744356 0.2001119 -0.3090646 -0.09546303 0.9462378 0.9265523 0.3527369 0.1306817 0.8602256 0.5022916 0.08783543 -0.6846963 0.7254698 -0.06988877 -0.6990464 0.7114983 -0.07144582 0.6048352 -0.2130565 0.7673209 0.8987991 -0.400843 0.1774403 0.8820592 -0.4662992 0.06735533 0.8904321 0.2319164 0.3915936 -0.5301171 0.8445861 -0.07516855 0.8437299 -0.5309706 0.07867813 0.9348094 0.3445641 0.08606469 0.9782691 0.19038 0.08212769 0.224709 -0.3625924 0.9044516 0.7566614 -0.6493256 0.07641994 0.4217181 -0.8237512 0.3789298 0.8882886 -0.1227172 0.4425878 0.9561119 -0.2866383 0.06073361 0.8916997 0.4433778 0.09103769 -0.8969337 0.4359997 -0.07358217 -0.9464098 0.3130996 -0.07922857 -0.4245792 -0.02414041 0.905069 0.09674668 0.9868772 -0.1292804 -0.1141411 -0.200571 0.9730072 -0.2868505 -0.7668269 -0.5741894 -0.3111401 -0.9503582 0.003357052 -0.4698802 -0.8756692 -0.1114271 0.6618015 -0.7454843 0.07919645 -0.97534 -0.2019165 0.08911669 -0.9406708 -0.3298238 -0.0797168 -0.2343557 -0.04141432 0.9712685 -0.9872946 -0.03213661 0.1556171 -0.8215281 0.5658344 -0.07016468 0.9109759 -0.4052376 0.07684803 0.9228692 0.09698992 0.3727001 0.9966822 0.04297041 0.06912499 0.6122391 0.7823818 0.1142016 0.5471152 0.7540345 0.3634515 -0.5820056 -0.8063235 -0.1054141 -0.8234878 0.5606601 -0.08676481 0.8552033 0.5091484 0.09692829 -0.9768721 0.2070081 0.05356025 -0.9856885 -0.1497592 -0.07739746 -0.3737651 0.9180087 -0.1325131 -0.4395674 0.8962561 -0.05920714 -0.5781286 0.8121818 -0.07828217 -0.6134703 0.7885906 -0.04217779 0.5530765 -0.8270206 0.1007147 0.798569 0.5901525 0.118354 -0.8863626 -0.455282 -0.08414077 0.9566466 0.2776918 0.08783346 0.9914684 -0.1019332 0.08124136 0.9659567 -0.2452506 0.08234024 0.2486725 -0.1718856 0.9532143 0.3761844 -0.1273277 0.9177544 0.2073187 -0.002166867 0.9782711 -0.7683152 -0.6350694 -0.07986813 -0.8423514 -0.5310894 -0.09158712 -0.7669453 0.6382767 -0.06631803 -0.9942206 0.1073356 0.00213629 0.9520455 0.2927094 0.08905494 -0.9105451 0.4078302 -0.06769192 0.8651589 -0.4968835 0.06787472 0.5077466 0.4833923 0.7131097 0.8231697 -0.5629916 0.07370436 0.9933196 0.08401769 0.07910418 -0.9897143 0.1265335 -0.06674593 -0.9891502 0.002410948 -0.1468878 -0.7067247 0.7041306 -0.06885045 -0.7194657 0.6881833 0.09366422 -0.6970612 0.7123209 -0.08188331 -0.6730041 -0.7290979 -0.1244258 0.9160537 0.3904581 0.09158706 -0.9586133 0.2762002 -0.06909584 0.9469084 -0.313978 0.06915569 -0.9832595 -0.1600108 -0.08716207 -0.9467598 -0.3117514 -0.08035647 0.9905889 -0.1136531 0.07626718 0.5059178 -0.5358267 0.6759712 -0.4009366 -0.5788355 -0.71007 0.9877046 0.1316003 0.08438658 -0.9969576 -0.02139365 -0.07495415 0.734556 0.5833662 0.346571 0.8364909 0.4938254 0.2375281 0.8035543 0.5836291 0.1169517 0.7226623 -0.6874127 0.07226926 -0.7538353 -0.6495802 -0.09888362 -0.6578074 -0.7475333 -0.09210646 0.9053176 0.4167379 0.08203524 0.9082515 -0.4120398 0.07281881 -0.5722706 0.8119401 -0.1151499 -0.3466705 0.6224749 -0.7016728 -0.8638395 0.4999923 -0.06155675 -0.9210203 0.3852793 -0.05728524 -0.8045085 -0.5841621 -0.1073349 -0.9248256 -0.3709618 -0.08417212 -0.951724 0.2978315 -0.07428234 -0.9807435 0.1743883 -0.08792662 -0.9089475 0.4097787 -0.0767858 0.9643558 -0.2534341 0.07608515 0.9935398 -0.08230918 0.07812815 0.6777646 -0.7022103 0.2180272 -0.9152997 -0.3918048 -0.09335803 -0.7932883 0.6053199 -0.06543338 0.8647727 -0.4970726 0.07132428 0.9389088 -0.3349736 0.07901298 -0.9951387 -0.0629 -0.07577908 -0.9757321 -0.2010305 -0.08679682 -0.9966483 0.04196316 -0.07022345 -0.01577836 0.008789479 -0.9998369 -0.5432705 0.4356907 -0.7176566 -0.6459704 0.05847483 -0.7611196 -0.7094824 0.7022188 -0.05936002 -0.7926161 0.6053498 -0.07288002 0.9733877 0.2143381 0.08109021 0.9949787 0.05685675 0.08237063 -0.9804576 0.1760649 -0.08777302 -0.9871814 0.1471647 -0.06177127 0.5680288 0.2356104 0.7885627 -0.758109 -0.6520226 -0.01171952 -0.6121902 -0.5108656 -0.6035227 -0.6318457 -0.294727 -0.7168731 0.988203 -0.1319028 0.07782328 -0.524867 0.5718663 -0.630463 -0.8208088 -0.561733 -0.1035815 -0.9633211 -0.2544645 -0.08520805 -0.8822313 0.4605109 -0.09796804 -0.8913083 0.4492706 -0.06103801 -0.9484184 0.3123958 -0.05395811 0.6415736 -0.4029749 0.6526826 0.892951 -0.187874 0.4090746 0.6287277 -0.03289973 0.7769293 -0.9970307 -0.03180092 -0.07013303 0.8212149 -0.5000597 0.2748573 0.9668025 -0.2482697 0.06045758 -0.988323 -0.1301019 -0.07931852 -0.9670146 -0.2516649 -0.03933978 0.9972745 -0.01168882 0.07284921 -0.9923718 0.09961253 -0.07263416 -0.9562211 0.2831247 -0.07403904 0.6925526 0.1190572 0.7114748 -0.8535029 0.5196217 -0.0390647 0.9351669 0.2439088 0.2568489 0.9131653 -0.3472476 0.2134208 0.9543927 0.006805717 0.2984766 -0.9561437 0.2894464 -0.04483306 -0.9983518 -0.01062071 -0.05639988 -0.9903832 0.09793657 -0.09772288 -0.9161953 0.1921202 -0.3516761 -0.718242 0.3075128 -0.6241509 -0.7087262 -0.1889774 -0.6797021 -0.01614457 0.008331656 -0.999835 -0.7622716 -0.01315361 -0.6471236 -0.01571404 0.008748769 -0.9998384 -0.01572 0.008754134 -0.9998381 -0.01571911 0.008749723 -0.9998382 -0.01571869 0.008751094 -0.9998382 - - - - - - - - - - 0.167584 0.001978099 0.170813 0.005488336 0.122597 0.001978099 0.387122 0.645634 0.383443 0.632545 0.415832 0.649596 0.387122 0.645634 0.34213 0.645873 0.383443 0.632545 0.167584 0.001978099 0.196213 0.004784286 0.170813 0.005488336 0.122597 0.001978099 0.170813 0.005488336 0.113986 0.008504092 0.122597 0.001978099 0.113986 0.008504092 0.08069568 0.01884698 0.34213 0.645873 0.328605 0.623663 0.358262 0.621048 0.34213 0.645873 0.358262 0.621048 0.383443 0.632545 0.34213 0.645873 0.300013 0.64156 0.328605 0.623663 0.415832 0.649596 0.383443 0.632545 0.412445 0.62415 0.415832 0.649596 0.412445 0.62415 0.440557 0.636203 0.415832 0.649596 0.440557 0.636203 0.449773 0.649278 0.196213 0.004784286 0.230222 0.01596677 0.241495 0.02878135 0.163344 0.664088 0.208431 0.666263 0.180244 0.674518 0.196213 0.004784286 0.213504 0.01910185 0.170813 0.005488336 0.137777 0.669205 0.1127099 0.675849 0.08099538 0.666249 0.137777 0.669205 0.1467649 0.679272 0.1127099 0.675849 0.137777 0.669205 0.180244 0.674518 0.1467649 0.679272 0.383443 0.632545 0.358262 0.621048 0.380399 0.601017 0.383443 0.632545 0.380399 0.601017 0.412445 0.62415 0.08099538 0.666249 0.1127099 0.675849 0.0871939 0.67571 0.3335 0.646893 0.29623 0.647557 0.300013 0.64156 0.113986 0.008504092 0.0734086 0.02914637 0.07679396 0.02199417 0.08099538 0.666249 0.06335675 0.675267 0.04026657 0.666424 0.08099538 0.666249 0.0871939 0.67571 0.06335675 0.675267 0.07679396 0.02199417 0.03527379 0.06236189 0.05140006 0.04054886 0.07679396 0.02199417 0.0734086 0.02914637 0.03527379 0.06236189 0.29623 0.647557 0.270666 0.645482 0.300013 0.64156 0.412445 0.62415 0.436487 0.60161 0.440557 0.636203 0.412445 0.62415 0.380399 0.601017 0.388055 0.559238 0.412445 0.62415 0.388055 0.559238 0.425976 0.561127 0.412445 0.62415 0.425976 0.561127 0.436487 0.60161 0.300013 0.64156 0.277981 0.614182 0.298922 0.607805 0.300013 0.64156 0.298922 0.607805 0.328605 0.623663 0.300013 0.64156 0.270666 0.645482 0.277981 0.614182 0.230222 0.01596677 0.260007 0.03492617 0.241495 0.02878135 0.449773 0.649278 0.476158 0.642273 0.479476 0.650516 0.449773 0.649278 0.440557 0.636203 0.476158 0.642273 0.358262 0.621048 0.355301 0.576576 0.380399 0.601017 0.358262 0.621048 0.328605 0.623663 0.355301 0.576576 0.440557 0.636203 0.436487 0.60161 0.466123 0.59727 0.440557 0.636203 0.466123 0.59727 0.476158 0.642273 0.1127099 0.675849 0.1467649 0.679272 0.139499 0.700269 0.1127099 0.675849 0.139499 0.700269 0.112491 0.740354 0.1127099 0.675849 0.112491 0.740354 0.09719699 0.705355 0.1127099 0.675849 0.09719699 0.705355 0.0871939 0.67571 0.328605 0.623663 0.298922 0.607805 0.321105 0.559831 0.328605 0.623663 0.321105 0.559831 0.355301 0.576576 0.0871939 0.67571 0.09719699 0.705355 0.06335675 0.675267 0.0734086 0.02914637 0.0967074 0.02201199 0.06111174 0.04508578 0.04026657 0.666424 0.02759939 0.67537 0.001978099 0.664088 0.380399 0.601017 0.355301 0.576576 0.388055 0.559238 0.1467649 0.679272 0.159795 0.700098 0.139499 0.700269 0.1467649 0.679272 0.180244 0.674518 0.159795 0.700098 0.180244 0.674518 0.187786 0.750857 0.159795 0.700098 0.180244 0.674518 0.208431 0.666263 0.199348 0.674166 0.180244 0.674518 0.199348 0.674166 0.187786 0.750857 0.06335675 0.675267 0.04906409 0.698516 0.02759939 0.67537 0.06335675 0.675267 0.08408218 0.749619 0.05456787 0.771913 0.06335675 0.675267 0.05456787 0.771913 0.04906409 0.698516 0.06335675 0.675267 0.09719699 0.705355 0.08408218 0.749619 0.139499 0.700269 0.159795 0.700098 0.157595 0.749626 0.139499 0.700269 0.123738 0.757675 0.112491 0.740354 0.139499 0.700269 0.157595 0.749626 0.123738 0.757675 0.09719699 0.705355 0.112491 0.740354 0.08408218 0.749619 0.298922 0.607805 0.289222 0.565989 0.321105 0.559831 0.298922 0.607805 0.277981 0.614182 0.289222 0.565989 0.241495 0.02878135 0.260007 0.03492617 0.271347 0.05449169 0.208431 0.666263 0.226015 0.675867 0.199348 0.674166 0.208431 0.666263 0.238194 0.664299 0.226015 0.675867 0.260007 0.03492617 0.279107 0.05357235 0.271347 0.05449169 0.479476 0.650516 0.476158 0.642273 0.489198 0.637296 0.479476 0.650516 0.489198 0.637296 0.498471 0.650752 0.05140006 0.04054886 0.03527379 0.06236189 0.0282377 0.06815159 0.651014 0.001978099 0.651973 0.02943396 0.62066 0.0151962 0.270666 0.645482 0.261581 0.615301 0.277981 0.614182 0.388055 0.559238 0.409542 0.51755 0.425976 0.561127 0.388055 0.559238 0.355301 0.576576 0.366592 0.544085 0.388055 0.559238 0.392287 0.512146 0.409542 0.51755 0.388055 0.559238 0.366592 0.544085 0.392287 0.512146 0.436487 0.60161 0.425976 0.561127 0.461388 0.581888 0.436487 0.60161 0.461388 0.581888 0.466123 0.59727 0.159795 0.700098 0.187786 0.750857 0.157595 0.749626 0.321105 0.559831 0.289222 0.565989 0.320392 0.531596 0.321105 0.559831 0.345544 0.541304 0.355301 0.576576 0.321105 0.559831 0.320392 0.531596 0.345544 0.541304 0.476158 0.642273 0.466123 0.59727 0.489198 0.637296 0.02759939 0.67537 0.04906409 0.698516 0.02915817 0.701368 0.06111174 0.04508578 0.03147494 0.08005559 0.03527379 0.06236189 0.484713 0.669743 0.468098 0.695651 0.449769 0.668465 0.484713 0.669743 0.482535 0.69591 0.468098 0.695651 0.355301 0.576576 0.345544 0.541304 0.366592 0.544085 0.112491 0.740354 0.123738 0.757675 0.108254 0.803532 0.112491 0.740354 0.108254 0.803532 0.08408218 0.749619 0.03527379 0.06236189 0.03147494 0.08005559 0.009264111 0.1091549 0.03527379 0.06236189 0.009264111 0.1091549 0.0282377 0.06815159 0.425976 0.561127 0.439282 0.528487 0.461388 0.581888 0.425976 0.561127 0.409542 0.51755 0.439282 0.528487 0.466123 0.59727 0.490861 0.591939 0.489198 0.637296 0.466123 0.59727 0.461388 0.581888 0.490861 0.591939 0.04906409 0.698516 0.04030507 0.746915 0.02915817 0.701368 0.04906409 0.698516 0.05456787 0.771913 0.04030507 0.746915 0.199348 0.674166 0.216578 0.755242 0.187786 0.750857 0.199348 0.674166 0.226015 0.675867 0.216578 0.755242 0.277981 0.614182 0.261581 0.615301 0.289222 0.565989 0.345544 0.541304 0.336676 0.499375 0.364015 0.500796 0.345544 0.541304 0.364015 0.500796 0.366592 0.544085 0.345544 0.541304 0.320392 0.531596 0.336676 0.499375 0.08408218 0.749619 0.06815266 0.78772 0.05456787 0.771913 0.08408218 0.749619 0.108254 0.803532 0.09563386 0.855881 0.08408218 0.749619 0.09563386 0.855881 0.06815266 0.78772 0.187786 0.750857 0.173758 0.780804 0.157595 0.749626 0.187786 0.750857 0.216578 0.755242 0.203768 0.784147 0.187786 0.750857 0.188502 0.803106 0.173758 0.780804 0.187786 0.750857 0.203768 0.784147 0.188502 0.803106 0.482535 0.69591 0.484013 0.741117 0.468098 0.695651 0.271347 0.05449169 0.279107 0.05357235 0.289683 0.07566756 0.271347 0.05449169 0.289683 0.07566756 0.287858 0.08194977 0.509608 0.67037 0.53712 0.674654 0.502711 0.682215 0.366592 0.544085 0.364015 0.500796 0.392287 0.512146 0.461388 0.581888 0.439282 0.528487 0.453571 0.531437 0.461388 0.581888 0.453571 0.531437 0.476517 0.539288 0.461388 0.581888 0.476517 0.539288 0.490861 0.591939 0.320392 0.531596 0.289222 0.565989 0.298894 0.523708 0.320392 0.531596 0.298894 0.523708 0.311478 0.479114 0.320392 0.531596 0.311478 0.479114 0.336676 0.499375 0.62066 0.0151962 0.651973 0.02943396 0.632376 0.04264885 0.62066 0.0151962 0.632376 0.04264885 0.569104 0.03086686 0.62066 0.0151962 0.569104 0.03086686 0.571972 0.001978099 0.279107 0.05357235 0.290809 0.07094091 0.289683 0.07566756 0.724846 0.315643 0.736891 0.328494 0.705401 0.33706 0.724846 0.315643 0.705401 0.33706 0.707361 0.315455 0.409542 0.51755 0.425008 0.483742 0.439282 0.528487 0.409542 0.51755 0.392287 0.512146 0.388778 0.485073 0.409542 0.51755 0.393677 0.465807 0.425008 0.483742 0.409542 0.51755 0.388778 0.485073 0.393677 0.465807 0.123738 0.757675 0.1325049 0.826508 0.108254 0.803532 0.123738 0.757675 0.157595 0.749626 0.151767 0.792761 0.123738 0.757675 0.151767 0.792761 0.1325049 0.826508 0.157595 0.749626 0.173758 0.780804 0.151767 0.792761 0.289222 0.565989 0.279746 0.515194 0.298894 0.523708 0.289222 0.565989 0.260767 0.563716 0.279746 0.515194 0.05456787 0.771913 0.04604047 0.842252 0.03290635 0.794351 0.05456787 0.771913 0.03290635 0.794351 0.04030507 0.746915 0.05456787 0.771913 0.06815266 0.78772 0.04604047 0.842252 0.736891 0.328494 0.72909 0.374464 0.705401 0.33706 0.502711 0.682215 0.53712 0.674654 0.533157 0.710532 0.502711 0.682215 0.533157 0.710532 0.521112 0.742544 0.502711 0.682215 0.521112 0.742544 0.510202 0.761929 0.651973 0.02943396 0.641457 0.06384766 0.632376 0.04264885 0.651973 0.02943396 0.653932 0.07031428 0.641457 0.06384766 0.449769 0.668465 0.468098 0.695651 0.447254 0.692126 0.449769 0.668465 0.430337 0.671805 0.399007 0.664844 0.03147494 0.08005559 0.007678568 0.130607 0.009264111 0.1091549 0.449769 0.668465 0.447254 0.692126 0.430337 0.671805 0.392287 0.512146 0.364015 0.500796 0.388778 0.485073 0.484013 0.741117 0.470288 0.78988 0.457056 0.768514 0.04030507 0.746915 0.01705819 0.771598 0.0146113 0.699627 0.490861 0.591939 0.476517 0.539288 0.493987 0.543184 0.72909 0.374464 0.70426 0.366619 0.705401 0.33706 0.72909 0.374464 0.717627 0.424063 0.70426 0.366619 0.468098 0.695651 0.444997 0.74781 0.447254 0.692126 0.468098 0.695651 0.457056 0.768514 0.444997 0.74781 0.632376 0.04264885 0.534166 0.06307005 0.569104 0.03086686 0.632376 0.04264885 0.565341 0.069579 0.534166 0.06307005 0.632376 0.04264885 0.641457 0.06384766 0.565341 0.069579 0.707361 0.315455 0.705401 0.33706 0.692985 0.31869 0.290809 0.07094091 0.299395 0.08546715 0.306283 0.111487 0.290809 0.07094091 0.306283 0.111487 0.289683 0.07566756 0.663925 0.03855228 0.665561 0.07447135 0.656634 0.04483896 0.653932 0.07031428 0.642426 0.09160816 0.641457 0.06384766 0.653932 0.07031428 0.645919 0.118799 0.642426 0.09160816 0.653932 0.07031428 0.654489 0.09175449 0.645919 0.118799 0.364015 0.500796 0.336676 0.499375 0.347498 0.482244 0.364015 0.500796 0.393677 0.465807 0.388778 0.485073 0.364015 0.500796 0.347498 0.482244 0.393677 0.465807 0.439282 0.528487 0.425008 0.483742 0.453571 0.531437 0.108254 0.803532 0.122849 0.870261 0.09563386 0.855881 0.108254 0.803532 0.1325049 0.826508 0.122849 0.870261 0.151767 0.792761 0.1718789 0.857806 0.151174 0.870338 0.151767 0.792761 0.173758 0.780804 0.1718789 0.857806 0.151767 0.792761 0.151174 0.870338 0.1325049 0.826508 0.173758 0.780804 0.188502 0.803106 0.1718789 0.857806 0.453571 0.531437 0.450152 0.479541 0.468363 0.486889 0.453571 0.531437 0.468363 0.486889 0.476517 0.539288 0.453571 0.531437 0.425008 0.483742 0.450152 0.479541 0.06815266 0.78772 0.09563386 0.855881 0.07617866 0.850051 0.06815266 0.78772 0.07617866 0.850051 0.04604047 0.842252 0.298894 0.523708 0.281211 0.486292 0.311478 0.479114 0.298894 0.523708 0.279746 0.515194 0.281211 0.486292 0.216578 0.755242 0.217621 0.828524 0.203768 0.784147 0.510202 0.761929 0.538523 0.766303 0.525914 0.835338 0.510202 0.761929 0.521112 0.742544 0.538523 0.766303 0.569104 0.03086686 0.534166 0.06307005 0.522366 0.04234015 0.569104 0.03086686 0.522366 0.04234015 0.521014 0.0216794 0.53712 0.674654 0.556337 0.702049 0.533157 0.710532 0.53712 0.674654 0.569594 0.674152 0.556337 0.702049 0.656634 0.04483896 0.665561 0.07447135 0.657591 0.07730257 0.336676 0.499375 0.337278 0.46816 0.347498 0.482244 0.336676 0.499375 0.311478 0.479114 0.337278 0.46816 0.521014 0.0216794 0.522366 0.04234015 0.492163 0.02587866 0.705401 0.33706 0.70426 0.366619 0.682504 0.348214 0.705401 0.33706 0.682504 0.348214 0.692985 0.31869 0.447254 0.692126 0.444997 0.74781 0.430337 0.671805 0.521112 0.742544 0.533157 0.710532 0.538523 0.766303 0.641457 0.06384766 0.571347 0.09434705 0.565341 0.069579 0.641457 0.06384766 0.642426 0.09160816 0.571347 0.09434705 0.347498 0.482244 0.35577 0.431956 0.379813 0.430146 0.347498 0.482244 0.337278 0.46816 0.35577 0.431956 0.347498 0.482244 0.379813 0.430146 0.393677 0.465807 0.425008 0.483742 0.401598 0.43607 0.424719 0.409868 0.425008 0.483742 0.424719 0.409868 0.445281 0.434309 0.425008 0.483742 0.445281 0.434309 0.450152 0.479541 0.425008 0.483742 0.393677 0.465807 0.401598 0.43607 0.311478 0.479114 0.281211 0.486292 0.28909 0.469811 0.311478 0.479114 0.28909 0.469811 0.311646 0.438533 0.311478 0.479114 0.311646 0.438533 0.337278 0.46816 0.09563386 0.855881 0.122849 0.870261 0.110658 0.906226 0.09563386 0.855881 0.08955609 0.927768 0.0738331 0.90782 0.09563386 0.855881 0.0738331 0.90782 0.07617866 0.850051 0.09563386 0.855881 0.110658 0.906226 0.08955609 0.927768 0.188502 0.803106 0.196169 0.84929 0.1718789 0.857806 0.188502 0.803106 0.203768 0.784147 0.196169 0.84929 0.203768 0.784147 0.217621 0.828524 0.196169 0.84929 0.476517 0.539288 0.468363 0.486889 0.487134 0.499733 0.735166 0.427135 0.719846 0.467612 0.717627 0.424063 0.533157 0.710532 0.556337 0.702049 0.538523 0.766303 0.70426 0.366619 0.717627 0.424063 0.69004 0.417777 0.70426 0.366619 0.69004 0.417777 0.682504 0.348214 0.393677 0.465807 0.379813 0.430146 0.401598 0.43607 0.692985 0.31869 0.682504 0.348214 0.661831 0.322671 0.692985 0.31869 0.661831 0.322671 0.66668 0.315891 0.430337 0.671805 0.444997 0.74781 0.41951 0.730794 0.430337 0.671805 0.41951 0.730794 0.400855 0.673329 0.430337 0.671805 0.400855 0.673329 0.399007 0.664844 0.1325049 0.826508 0.151174 0.870338 0.122849 0.870261 0.470288 0.78988 0.475157 0.837141 0.456741 0.816084 0.470288 0.78988 0.456741 0.816084 0.457056 0.768514 0.337278 0.46816 0.311646 0.438533 0.328936 0.416023 0.337278 0.46816 0.328936 0.416023 0.35577 0.431956 0.66668 0.315891 0.661831 0.322671 0.625849 0.315464 0.665561 0.07447135 0.662421 0.10457 0.657591 0.07730257 0.306283 0.111487 0.316147 0.152157 0.307503 0.1415719 0.654489 0.09175449 0.657887 0.129064 0.645919 0.118799 0.399007 0.664844 0.377683 0.672867 0.345681 0.66482 0.007678568 0.130607 0.006712853 0.1838369 0.001978099 0.16796 0.399007 0.664844 0.400855 0.673329 0.377683 0.672867 0.122849 0.870261 0.144516 0.921086 0.110658 0.906226 0.122849 0.870261 0.151174 0.870338 0.144516 0.921086 0.457056 0.768514 0.456741 0.816084 0.434192 0.824188 0.457056 0.768514 0.434192 0.824188 0.444997 0.74781 0.379813 0.430146 0.349394 0.384495 0.371378 0.379027 0.379813 0.430146 0.371378 0.379027 0.391762 0.381622 0.379813 0.430146 0.391762 0.381622 0.401598 0.43607 0.379813 0.430146 0.35577 0.431956 0.349394 0.384495 0.35577 0.431956 0.328936 0.416023 0.349394 0.384495 0.450152 0.479541 0.445281 0.434309 0.468363 0.486889 0.151174 0.870338 0.171947 0.923328 0.144516 0.921086 0.151174 0.870338 0.1718789 0.857806 0.171947 0.923328 0.07617866 0.850051 0.0738331 0.90782 0.06010425 0.872896 0.07617866 0.850051 0.06010425 0.872896 0.04604047 0.842252 0.492163 0.02587866 0.486003 0.05604368 0.456001 0.04852426 0.492163 0.02587866 0.522366 0.04234015 0.486003 0.05604368 0.492163 0.02587866 0.456001 0.04852426 0.475863 0.0236209 0.717627 0.424063 0.719846 0.467612 0.698705 0.4604 0.717627 0.424063 0.698705 0.4604 0.69004 0.417777 0.642426 0.09160816 0.57201 0.129007 0.571347 0.09434705 0.642426 0.09160816 0.645919 0.118799 0.57201 0.129007 0.401598 0.43607 0.391762 0.381622 0.413015 0.380733 0.401598 0.43607 0.413015 0.380733 0.424719 0.409868 0.1718789 0.857806 0.196169 0.84929 0.189227 0.892983 0.1718789 0.857806 0.189227 0.892983 0.171947 0.923328 0.468363 0.486889 0.466574 0.428493 0.487134 0.499733 0.468363 0.486889 0.445281 0.434309 0.466574 0.428493 0.475157 0.837141 0.46414 0.916737 0.449912 0.906748 0.04604047 0.842252 0.06010425 0.872896 0.04591798 0.920867 0.475157 0.837141 0.449912 0.906748 0.456741 0.816084 0.661831 0.322671 0.682504 0.348214 0.65701 0.355499 0.661831 0.322671 0.630785 0.327094 0.625849 0.315464 0.661831 0.322671 0.65701 0.355499 0.630785 0.327094 0.525914 0.835338 0.538523 0.766303 0.545758 0.849883 0.217621 0.828524 0.211592 0.90722 0.196169 0.84929 0.525914 0.835338 0.545758 0.849883 0.535195 0.914293 0.538523 0.766303 0.556337 0.702049 0.561931 0.777711 0.538523 0.766303 0.561931 0.777711 0.545758 0.849883 0.534166 0.06307005 0.486003 0.05604368 0.522366 0.04234015 0.534166 0.06307005 0.523803 0.09085357 0.451987 0.08987325 0.534166 0.06307005 0.451987 0.08987325 0.486003 0.05604368 0.534166 0.06307005 0.565341 0.069579 0.523803 0.09085357 0.682504 0.348214 0.69004 0.417777 0.666111 0.419225 0.682504 0.348214 0.666111 0.419225 0.65701 0.355499 0.556337 0.702049 0.569594 0.674152 0.575499 0.729577 0.556337 0.702049 0.575499 0.729577 0.561931 0.777711 0.424719 0.409868 0.431246 0.383926 0.452575 0.386579 0.424719 0.409868 0.413015 0.380733 0.431246 0.383926 0.424719 0.409868 0.452575 0.386579 0.445281 0.434309 0.311646 0.438533 0.28909 0.469811 0.286856 0.436635 0.311646 0.438533 0.314235 0.380019 0.328936 0.416023 0.311646 0.438533 0.286856 0.436635 0.314235 0.380019 0.475863 0.0236209 0.456001 0.04852426 0.442666 0.0331276 0.400855 0.673329 0.41951 0.730794 0.391931 0.728197 0.400855 0.673329 0.391931 0.728197 0.377683 0.672867 0.445281 0.434309 0.452575 0.386579 0.466574 0.428493 0.565341 0.069579 0.571347 0.09434705 0.523803 0.09085357 0.41951 0.730794 0.399561 0.794765 0.391931 0.728197 0.41951 0.730794 0.420237 0.789696 0.399561 0.794765 0.41951 0.730794 0.444997 0.74781 0.420237 0.789696 0.569594 0.674152 0.596926 0.669703 0.589889 0.697459 0.569594 0.674152 0.589889 0.697459 0.575499 0.729577 0.328936 0.416023 0.314235 0.380019 0.349394 0.384495 0.196169 0.84929 0.211592 0.90722 0.189227 0.892983 0.719846 0.467612 0.702721 0.49242 0.698705 0.4604 0.719846 0.467612 0.730783 0.538716 0.718587 0.522206 0.719846 0.467612 0.718587 0.522206 0.702721 0.49242 0.444997 0.74781 0.434192 0.824188 0.420237 0.789696 0.456741 0.816084 0.440509 0.878039 0.434192 0.824188 0.456741 0.816084 0.449912 0.906748 0.440509 0.878039 0.69004 0.417777 0.698705 0.4604 0.679013 0.464476 0.69004 0.417777 0.679013 0.464476 0.666111 0.419225 0.65701 0.355499 0.631035 0.356946 0.630785 0.327094 0.65701 0.355499 0.666111 0.419225 0.631035 0.356946 0.571347 0.09434705 0.529956 0.11428 0.523803 0.09085357 0.571347 0.09434705 0.57201 0.129007 0.529956 0.11428 0.391762 0.381622 0.371378 0.379027 0.380342 0.356171 0.391762 0.381622 0.380342 0.356171 0.396035 0.331639 0.391762 0.381622 0.396035 0.331639 0.413015 0.380733 0.06010425 0.872896 0.06558108 0.97158 0.04591798 0.920867 0.06010425 0.872896 0.0738331 0.90782 0.06558108 0.97158 0.657887 0.129064 0.647348 0.147536 0.645919 0.118799 0.657887 0.129064 0.660702 0.190954 0.647348 0.147536 0.001978099 0.16796 0.006712853 0.1838369 0.01356285 0.229785 0.371378 0.379027 0.352563 0.358071 0.380342 0.356171 0.371378 0.379027 0.349394 0.384495 0.352563 0.358071 0.349394 0.384495 0.331811 0.348011 0.352563 0.358071 0.349394 0.384495 0.314235 0.380019 0.331811 0.348011 0.413015 0.380733 0.433739 0.367645 0.431246 0.383926 0.413015 0.380733 0.396035 0.331639 0.41609 0.315745 0.413015 0.380733 0.41609 0.315745 0.433739 0.367645 0.110658 0.906226 0.144516 0.921086 0.130607 0.941794 0.110658 0.906226 0.130607 0.941794 0.106602 0.958171 0.110658 0.906226 0.106602 0.958171 0.08955609 0.927768 0.0738331 0.90782 0.08955609 0.927768 0.08167737 0.967924 0.0738331 0.90782 0.08167737 0.967924 0.06558108 0.97158 0.466574 0.428493 0.452575 0.386579 0.476095 0.397876 0.730783 0.538716 0.71845 0.57005 0.718587 0.522206 0.698705 0.4604 0.702721 0.49242 0.679013 0.464476 0.575499 0.729577 0.585061 0.791564 0.561931 0.777711 0.575499 0.729577 0.589889 0.697459 0.608743 0.758534 0.575499 0.729577 0.608743 0.758534 0.585061 0.791564 0.377683 0.672867 0.362546 0.73268 0.353324 0.674803 0.377683 0.672867 0.391931 0.728197 0.362546 0.73268 0.377683 0.672867 0.353324 0.674803 0.345681 0.66482 0.442666 0.0331276 0.400796 0.06100189 0.36865 0.04714107 0.442666 0.0331276 0.456001 0.04852426 0.400796 0.06100189 0.286856 0.436635 0.290742 0.362479 0.314235 0.380019 0.456001 0.04852426 0.486003 0.05604368 0.44812 0.07273757 0.456001 0.04852426 0.41017 0.07963246 0.400796 0.06100189 0.456001 0.04852426 0.44812 0.07273757 0.41017 0.07963246 0.702721 0.49242 0.718587 0.522206 0.692763 0.530474 0.702721 0.49242 0.668767 0.516501 0.679013 0.464476 0.702721 0.49242 0.692763 0.530474 0.668767 0.516501 0.434192 0.824188 0.440509 0.878039 0.412885 0.893075 0.434192 0.824188 0.410148 0.836747 0.420237 0.789696 0.434192 0.824188 0.412885 0.893075 0.410148 0.836747 0.596926 0.669703 0.615388 0.696457 0.589889 0.697459 0.596926 0.669703 0.632503 0.670594 0.615388 0.696457 0.307503 0.1415719 0.316147 0.152157 0.306909 0.177162 0.630785 0.327094 0.597911 0.315455 0.625849 0.315464 0.630785 0.327094 0.631035 0.356946 0.600068 0.359185 0.630785 0.327094 0.600068 0.359185 0.597911 0.315455 0.316147 0.152157 0.316705 0.180043 0.29991 0.216031 0.66895 0.115194 0.669715 0.178964 0.662028 0.140156 0.645919 0.118799 0.617321 0.14528 0.57201 0.129007 0.645919 0.118799 0.647348 0.147536 0.617321 0.14528 0.144516 0.921086 0.171947 0.923328 0.1646119 0.936538 0.144516 0.921086 0.1646119 0.936538 0.130607 0.941794 0.718587 0.522206 0.71845 0.57005 0.692763 0.530474 0.486003 0.05604368 0.451987 0.08987325 0.44812 0.07273757 0.545758 0.849883 0.561931 0.777711 0.563004 0.854015 0.545758 0.849883 0.563004 0.854015 0.562693 0.913004 0.545758 0.849883 0.562693 0.913004 0.535195 0.914293 0.561931 0.777711 0.579658 0.865654 0.563004 0.854015 0.561931 0.777711 0.585061 0.791564 0.579658 0.865654 0.666111 0.419225 0.679013 0.464476 0.656998 0.473563 0.666111 0.419225 0.656998 0.473563 0.642413 0.420134 0.666111 0.419225 0.642413 0.420134 0.631035 0.356946 0.420237 0.789696 0.410148 0.836747 0.399561 0.794765 0.391931 0.728197 0.399561 0.794765 0.382045 0.774917 0.391931 0.728197 0.382045 0.774917 0.362546 0.73268 0.314235 0.380019 0.309956 0.341166 0.331811 0.348011 0.314235 0.380019 0.290742 0.362479 0.309956 0.341166 0.08955609 0.927768 0.106602 0.958171 0.08167737 0.967924 0.399561 0.794765 0.410148 0.836747 0.387239 0.835609 0.399561 0.794765 0.387239 0.835609 0.368238 0.798389 0.399561 0.794765 0.368238 0.798389 0.382045 0.774917 0.589889 0.697459 0.615388 0.696457 0.608743 0.758534 0.345681 0.66482 0.353324 0.674803 0.323909 0.67206 0.006712853 0.1838369 0.0237689 0.240414 0.01356285 0.229785 0.345681 0.66482 0.323909 0.67206 0.288893 0.66482 0.171947 0.923328 0.189227 0.892983 0.195475 0.935138 0.171947 0.923328 0.195475 0.935138 0.190409 0.967819 0.171947 0.923328 0.190409 0.967819 0.1646119 0.936538 0.380342 0.356171 0.352563 0.358071 0.366845 0.324766 0.380342 0.356171 0.375422 0.315455 0.396035 0.331639 0.380342 0.356171 0.366845 0.324766 0.375422 0.315455 0.352563 0.358071 0.329959 0.315488 0.344548 0.316563 0.352563 0.358071 0.344548 0.316563 0.366845 0.324766 0.352563 0.358071 0.331811 0.348011 0.329959 0.315488 0.431246 0.383926 0.433739 0.367645 0.452575 0.386579 0.130607 0.941794 0.1646119 0.936538 0.141616 0.982649 0.130607 0.941794 0.1127279 0.978918 0.106602 0.958171 0.130607 0.941794 0.141616 0.982649 0.1127279 0.978918 0.452575 0.386579 0.464128 0.329012 0.476095 0.397876 0.452575 0.386579 0.443423 0.331631 0.464128 0.329012 0.452575 0.386579 0.433739 0.367645 0.443423 0.331631 0.449912 0.906748 0.424905 0.950643 0.440509 0.878039 0.449912 0.906748 0.450006 0.949413 0.424905 0.950643 0.449912 0.906748 0.46414 0.916737 0.450006 0.949413 0.523803 0.09085357 0.480904 0.106818 0.451987 0.08987325 0.523803 0.09085357 0.529956 0.11428 0.480904 0.106818 0.331811 0.348011 0.309956 0.341166 0.329959 0.315488 0.106602 0.958171 0.1127279 0.978918 0.08167737 0.967924 0.06558108 0.97158 0.08432877 0.985219 0.0523923 0.983347 0.06558108 0.97158 0.08167737 0.967924 0.08432877 0.985219 0.06558108 0.97158 0.0523923 0.983347 0.04591798 0.920867 0.46414 0.916737 0.459402 0.979507 0.450006 0.949413 0.433739 0.367645 0.41609 0.315745 0.443423 0.331631 0.44812 0.07273757 0.451987 0.08987325 0.41017 0.07963246 0.631035 0.356946 0.61452 0.414864 0.600068 0.359185 0.631035 0.356946 0.642413 0.420134 0.61452 0.414864 0.353324 0.674803 0.336498 0.704808 0.323909 0.67206 0.353324 0.674803 0.362546 0.73268 0.336498 0.704808 0.396035 0.331639 0.39506 0.315629 0.401475 0.315661 0.396035 0.331639 0.401475 0.315661 0.41609 0.315745 0.396035 0.331639 0.375422 0.315455 0.39506 0.315629 0.290742 0.362479 0.304058 0.315455 0.309956 0.341166 0.36865 0.04714107 0.321796 0.05833345 0.321939 0.04384905 0.36865 0.04714107 0.321832 0.07607889 0.321796 0.05833345 0.36865 0.04714107 0.400796 0.06100189 0.3557 0.07097887 0.36865 0.04714107 0.3557 0.07097887 0.321832 0.07607889 0.211592 0.90722 0.195475 0.935138 0.189227 0.892983 0.211592 0.90722 0.210631 0.947998 0.195475 0.935138 0.535195 0.914293 0.562693 0.913004 0.541885 0.955163 0.440509 0.878039 0.424905 0.950643 0.412885 0.893075 0.679013 0.464476 0.668767 0.516501 0.656998 0.473563 0.57201 0.129007 0.516989 0.132288 0.529956 0.11428 0.57201 0.129007 0.567964 0.1582469 0.516989 0.132288 0.57201 0.129007 0.617321 0.14528 0.567964 0.1582469 0.362546 0.73268 0.382045 0.774917 0.368238 0.798389 0.362546 0.73268 0.368238 0.798389 0.351444 0.798308 0.362546 0.73268 0.351444 0.798308 0.329437 0.783784 0.362546 0.73268 0.329437 0.783784 0.336498 0.704808 0.366845 0.324766 0.344548 0.316563 0.355564 0.315497 0.366845 0.324766 0.355564 0.315497 0.375422 0.315455 0.41609 0.315745 0.431417 0.315928 0.443423 0.331631 0.911023 0.08555769 0.911367 0.100163 0.90318 0.07036185 0.1646119 0.936538 0.1789399 0.975173 0.141616 0.982649 0.1646119 0.936538 0.190409 0.967819 0.1789399 0.975173 0.597911 0.315455 0.600068 0.359185 0.585195 0.327983 0.316705 0.180043 0.300761 0.223589 0.29991 0.216031 0.597911 0.315455 0.585195 0.327983 0.554527 0.317391 0.451987 0.08987325 0.480904 0.106818 0.443006 0.120522 0.451987 0.08987325 0.443006 0.120522 0.413075 0.104134 0.451987 0.08987325 0.413075 0.104134 0.41017 0.07963246 0.585061 0.791564 0.611562 0.818616 0.599836 0.87024 0.585061 0.791564 0.599836 0.87024 0.579658 0.865654 0.585061 0.791564 0.608743 0.758534 0.611562 0.818616 0.410148 0.836747 0.412885 0.893075 0.387239 0.835609 0.608743 0.758534 0.615388 0.696457 0.634926 0.75287 0.608743 0.758534 0.634926 0.75287 0.611562 0.818616 0.615388 0.696457 0.644693 0.692712 0.634926 0.75287 0.615388 0.696457 0.632503 0.670594 0.644693 0.692712 0.632503 0.670594 0.662432 0.670933 0.644693 0.692712 0.662028 0.140156 0.669715 0.178964 0.662107 0.170087 0.647348 0.147536 0.660702 0.190954 0.630255 0.169989 0.647348 0.147536 0.630255 0.169989 0.617321 0.14528 0.910088 0.157123 0.905036 0.171766 0.910336 0.14608 0.1127279 0.978918 0.09881228 0.992524 0.08432877 0.985219 0.1127279 0.978918 0.120461 0.992282 0.09881228 0.992524 0.1127279 0.978918 0.08432877 0.985219 0.08167737 0.967924 0.1127279 0.978918 0.141616 0.982649 0.120461 0.992282 0.195475 0.935138 0.210631 0.947998 0.190409 0.967819 0.400796 0.06100189 0.41017 0.07963246 0.3557 0.07097887 0.692763 0.530474 0.71845 0.57005 0.699527 0.585179 0.692763 0.530474 0.699527 0.585179 0.679137 0.569453 0.692763 0.530474 0.679137 0.569453 0.668767 0.516501 0.642413 0.420134 0.656998 0.473563 0.628691 0.458467 0.642413 0.420134 0.628691 0.458467 0.61452 0.414864 0.617321 0.14528 0.630255 0.169989 0.567964 0.1582469 0.916391 0.126128 0.911367 0.100163 0.915642 0.106508 0.916391 0.126128 0.828282 0.160665 0.821914 0.119079 0.916391 0.126128 0.821914 0.119079 0.911367 0.100163 0.916391 0.126128 0.894584 0.183579 0.828282 0.160665 0.916391 0.126128 0.910336 0.14608 0.894584 0.183579 0.329959 0.315488 0.309956 0.341166 0.31831 0.31546 0.905036 0.171766 0.894584 0.183579 0.910336 0.14608 0.141616 0.982649 0.1789399 0.975173 0.16686 0.991715 0.184316 0.06162035 0.209905 0.07541525 0.163495 0.06782978 0.309956 0.341166 0.304058 0.315455 0.31831 0.31546 0.71845 0.57005 0.721546 0.639126 0.709927 0.618624 0.71845 0.57005 0.709927 0.618624 0.699527 0.585179 0.563004 0.854015 0.579658 0.865654 0.562693 0.913004 0.529956 0.11428 0.516989 0.132288 0.480904 0.106818 0.0181598 0.206025 0.03087484 0.233161 0.0237689 0.240414 0.323909 0.67206 0.336498 0.704808 0.315547 0.705286 0.323909 0.67206 0.315547 0.705286 0.296712 0.673016 0.911367 0.100163 0.821914 0.119079 0.90318 0.07036185 0.443423 0.331631 0.431417 0.315928 0.448219 0.316122 0.443423 0.331631 0.448219 0.316122 0.464128 0.329012 0.41017 0.07963246 0.360899 0.0933907 0.3557 0.07097887 0.41017 0.07963246 0.413075 0.104134 0.360899 0.0933907 0.668767 0.516501 0.649372 0.516966 0.656998 0.473563 0.668767 0.516501 0.679137 0.569453 0.656922 0.566321 0.668767 0.516501 0.656922 0.566321 0.649372 0.516966 0.656998 0.473563 0.649372 0.516966 0.628691 0.458467 0.480904 0.106818 0.516989 0.132288 0.443006 0.120522 0.1789399 0.975173 0.196517 0.987648 0.16686 0.991715 0.1789399 0.975173 0.190409 0.967819 0.211099 0.97564 0.1789399 0.975173 0.211099 0.97564 0.196517 0.987648 0.163495 0.06782978 0.169125 0.07857257 0.141896 0.07319128 0.163495 0.06782978 0.209905 0.07541525 0.169125 0.07857257 0.894584 0.183579 0.87317 0.2114959 0.828282 0.160665 0.894584 0.183579 0.887429 0.197943 0.87317 0.2114959 0.190409 0.967819 0.210631 0.947998 0.211099 0.97564 0.562693 0.913004 0.591828 0.913903 0.585644 0.984797 0.562693 0.913004 0.56433 0.978768 0.541885 0.955163 0.562693 0.913004 0.585644 0.984797 0.56433 0.978768 0.562693 0.913004 0.579658 0.865654 0.591828 0.913903 0.412885 0.893075 0.377618 0.922241 0.372862 0.905297 0.412885 0.893075 0.424905 0.950643 0.410925 0.944887 0.412885 0.893075 0.410925 0.944887 0.377618 0.922241 0.412885 0.893075 0.372862 0.905297 0.387239 0.835609 0.579658 0.865654 0.599836 0.87024 0.591828 0.913903 0.516989 0.132288 0.567964 0.1582469 0.499667 0.1488969 0.516989 0.132288 0.449212 0.151762 0.443006 0.120522 0.516989 0.132288 0.499667 0.1488969 0.449212 0.151762 0.600068 0.359185 0.61452 0.414864 0.594342 0.42052 0.600068 0.359185 0.594342 0.42052 0.573705 0.364927 0.600068 0.359185 0.573705 0.364927 0.585195 0.327983 0.644693 0.692712 0.662432 0.670933 0.666152 0.698974 0.644693 0.692712 0.666152 0.698974 0.652969 0.75971 0.644693 0.692712 0.652969 0.75971 0.634926 0.75287 0.336498 0.704808 0.317343 0.738016 0.315547 0.705286 0.336498 0.704808 0.329437 0.783784 0.317343 0.738016 0.127195 0.07216089 0.114686 0.09006828 0.0953443 0.09267836 0.127195 0.07216089 0.141896 0.07319128 0.114686 0.09006828 0.90318 0.07036185 0.821914 0.119079 0.807973 0.06941205 0.90318 0.07036185 0.807973 0.06941205 0.877311 0.03174108 0.90318 0.07036185 0.877311 0.03174108 0.895171 0.05369436 0.141896 0.07319128 0.169125 0.07857257 0.114686 0.09006828 0.699527 0.585179 0.672334 0.619717 0.679137 0.569453 0.699527 0.585179 0.709927 0.618624 0.688279 0.652984 0.699527 0.585179 0.688279 0.652984 0.672334 0.619717 0.541885 0.955163 0.56433 0.978768 0.548315 0.982857 0.368238 0.798389 0.387239 0.835609 0.36718 0.866292 0.368238 0.798389 0.36718 0.866292 0.351444 0.798308 0.634926 0.75287 0.645666 0.821767 0.611562 0.818616 0.634926 0.75287 0.652969 0.75971 0.645666 0.821767 0.585195 0.327983 0.550524 0.325339 0.554527 0.317391 0.585195 0.327983 0.573705 0.364927 0.550524 0.325339 0.669715 0.178964 0.670617 0.221774 0.663185 0.201817 0.669715 0.178964 0.663185 0.201817 0.662107 0.170087 0.29991 0.216031 0.300761 0.223589 0.271718 0.259019 0.630255 0.169989 0.643033 0.200456 0.61424 0.199669 0.630255 0.169989 0.660702 0.190954 0.643033 0.200456 0.630255 0.169989 0.61424 0.199669 0.581252 0.17956 0.630255 0.169989 0.581252 0.17956 0.567964 0.1582469 0.660702 0.190954 0.661438 0.206187 0.643033 0.200456 0.01356285 0.229785 0.0237689 0.240414 0.01795387 0.244992 0.448219 0.316122 0.46703 0.316806 0.464128 0.329012 0.895171 0.05369436 0.877311 0.03174108 0.884481 0.03507184 0.721546 0.639126 0.72142 0.651301 0.714336 0.652012 0.464128 0.329012 0.470468 0.316515 0.477941 0.349967 0.709927 0.618624 0.714336 0.652012 0.688279 0.652984 0.3557 0.07097887 0.332501 0.08159059 0.321832 0.07607889 0.3557 0.07097887 0.360899 0.0933907 0.332501 0.08159059 0.387239 0.835609 0.372862 0.905297 0.36718 0.866292 0.61452 0.414864 0.628691 0.458467 0.594342 0.42052 0.209905 0.07541525 0.239518 0.0897296 0.220139 0.08671289 0.209905 0.07541525 0.220139 0.08671289 0.169125 0.07857257 0.0953443 0.09267836 0.114686 0.09006828 0.08398777 0.112705 0.459402 0.979507 0.440772 0.971138 0.450006 0.949413 0.459402 0.979507 0.439933 0.986705 0.440772 0.971138 0.424905 0.950643 0.450006 0.949413 0.43795 0.952699 0.06536537 0.125196 0.07511168 0.112265 0.07608926 0.112796 0.424905 0.950643 0.437487 0.953721 0.440772 0.971138 0.424905 0.950643 0.440772 0.971138 0.4141 0.983149 0.424905 0.950643 0.4141 0.983149 0.410925 0.944887 0.567964 0.1582469 0.491088 0.164562 0.499667 0.1488969 0.567964 0.1582469 0.536492 0.181671 0.491088 0.164562 0.567964 0.1582469 0.581252 0.17956 0.536492 0.181671 0.662432 0.670933 0.694174 0.670299 0.687785 0.705656 0.662432 0.670933 0.687785 0.705656 0.666152 0.698974 0.315547 0.705286 0.28825 0.700855 0.296712 0.673016 0.315547 0.705286 0.317343 0.738016 0.28825 0.700855 0.450006 0.949413 0.440772 0.971138 0.43795 0.952699 0.169125 0.07857257 0.220139 0.08671289 0.202705 0.1082 0.169125 0.07857257 0.202705 0.1082 0.148147 0.104125 0.169125 0.07857257 0.148147 0.104125 0.114686 0.09006828 0.114686 0.09006828 0.07950848 0.135752 0.08398777 0.112705 0.114686 0.09006828 0.148147 0.104125 0.07950848 0.135752 0.679137 0.569453 0.672334 0.619717 0.656922 0.566321 0.628691 0.458467 0.626179 0.513824 0.605628 0.475091 0.628691 0.458467 0.649372 0.516966 0.626179 0.513824 0.628691 0.458467 0.605628 0.475091 0.594342 0.42052 0.300761 0.223589 0.272739 0.26585 0.271718 0.259019 0.554527 0.317391 0.550524 0.325339 0.512752 0.322808 0.0237689 0.240414 0.0362336 0.261236 0.01795387 0.244992 0.0237689 0.240414 0.0566495 0.268579 0.0362336 0.261236 0.0237689 0.240414 0.03087484 0.233161 0.0566495 0.268579 0.220139 0.08671289 0.25546 0.121078 0.202705 0.1082 0.220139 0.08671289 0.239518 0.0897296 0.25546 0.121078 0.239518 0.0897296 0.25967 0.112126 0.25546 0.121078 0.540822 0.995206 0.548315 0.982857 0.563364 0.993572 0.87317 0.2114959 0.855636 0.224104 0.844362 0.222375 0.87317 0.2114959 0.844362 0.222375 0.828282 0.160665 0.360899 0.0933907 0.413075 0.104134 0.382971 0.121936 0.360899 0.0933907 0.321999 0.09697848 0.332501 0.08159059 0.360899 0.0933907 0.339072 0.128435 0.321999 0.09697848 0.360899 0.0933907 0.382971 0.121936 0.339072 0.128435 0.649372 0.516966 0.656922 0.566321 0.631617 0.58325 0.649372 0.516966 0.631617 0.58325 0.626179 0.513824 0.611562 0.818616 0.645666 0.821767 0.626644 0.87421 0.611562 0.818616 0.626644 0.87421 0.599836 0.87024 0.351444 0.798308 0.36718 0.866292 0.345838 0.872258 0.351444 0.798308 0.345838 0.872258 0.329437 0.783784 0.329437 0.783784 0.345838 0.872258 0.319247 0.834786 0.329437 0.783784 0.302314 0.791752 0.317343 0.738016 0.329437 0.783784 0.319247 0.834786 0.302314 0.791752 0.296712 0.673016 0.28825 0.700855 0.27399 0.675474 0.296712 0.673016 0.27399 0.675474 0.260767 0.668914 0.548315 0.982857 0.56433 0.978768 0.563364 0.993572 0.440772 0.971138 0.439933 0.986705 0.4141 0.983149 0.289182 0.33973 0.288241 0.357366 0.28729 0.358374 0.56433 0.978768 0.585644 0.984797 0.563364 0.993572 0.443006 0.120522 0.449212 0.151762 0.409847 0.130582 0.443006 0.120522 0.409847 0.130582 0.413075 0.104134 0.877311 0.03174108 0.807973 0.06941205 0.850955 0.01336938 0.148147 0.104125 0.202705 0.1082 0.155387 0.165864 0.148147 0.104125 0.110055 0.138151 0.07950848 0.135752 0.148147 0.104125 0.155387 0.165864 0.110055 0.138151 0.413075 0.104134 0.409847 0.130582 0.382971 0.121936 0.499667 0.1488969 0.491088 0.164562 0.449212 0.151762 0.594342 0.42052 0.570183 0.418058 0.573705 0.364927 0.594342 0.42052 0.605628 0.475091 0.579086 0.479354 0.594342 0.42052 0.579086 0.479354 0.570183 0.418058 0.317343 0.738016 0.302314 0.791752 0.28825 0.700855 0.643033 0.200456 0.661438 0.206187 0.644722 0.2246429 0.643033 0.200456 0.612748 0.2167659 0.61424 0.199669 0.643033 0.200456 0.644722 0.2246429 0.612748 0.2167659 0.202705 0.1082 0.25546 0.121078 0.240307 0.143562 0.202705 0.1082 0.2010239 0.165771 0.155387 0.165864 0.202705 0.1082 0.240307 0.143562 0.2010239 0.165771 0.08398777 0.112705 0.07950848 0.135752 0.06775808 0.138332 0.321832 0.07607889 0.332501 0.08159059 0.321956 0.08733189 0.410925 0.944887 0.388819 0.972068 0.377618 0.922241 0.410925 0.944887 0.4141 0.983149 0.388819 0.972068 0.599836 0.87024 0.626644 0.87421 0.606633 0.955382 0.599836 0.87024 0.606633 0.955382 0.591828 0.913903 0.36718 0.866292 0.372862 0.905297 0.345838 0.872258 0.652969 0.75971 0.666152 0.698974 0.671163 0.753909 0.652969 0.75971 0.671163 0.753909 0.672469 0.819747 0.652969 0.75971 0.672469 0.819747 0.645666 0.821767 0.573705 0.364927 0.54393 0.372066 0.550524 0.325339 0.573705 0.364927 0.570183 0.418058 0.54393 0.372066 0.666152 0.698974 0.687785 0.705656 0.671163 0.753909 0.25546 0.121078 0.270408 0.1431739 0.269801 0.1841329 0.25546 0.121078 0.25967 0.112126 0.270408 0.1431739 0.25546 0.121078 0.269801 0.1841329 0.240307 0.143562 0.07950848 0.135752 0.110055 0.138151 0.07603275 0.172322 0.07950848 0.135752 0.07603275 0.172322 0.06631207 0.172393 0.07950848 0.135752 0.06631207 0.172393 0.06775808 0.138332 0.688279 0.652984 0.656372 0.65443 0.656725 0.642205 0.850955 0.01336938 0.777271 0.001978099 0.818839 0.001978099 0.688279 0.652984 0.656725 0.642205 0.672334 0.619717 0.850955 0.01336938 0.750683 0.01154315 0.777271 0.001978099 0.850955 0.01336938 0.807973 0.06941205 0.750683 0.01154315 0.656922 0.566321 0.672334 0.619717 0.651828 0.624021 0.656922 0.566321 0.651828 0.624021 0.631617 0.58325 0.591828 0.913903 0.606633 0.955382 0.585644 0.984797 0.626179 0.513824 0.608999 0.526822 0.605628 0.475091 0.626179 0.513824 0.631617 0.58325 0.611187 0.565957 0.626179 0.513824 0.611187 0.565957 0.608999 0.526822 0.550524 0.325339 0.527509 0.336671 0.512752 0.322808 0.550524 0.325339 0.54393 0.372066 0.527509 0.336671 0.61424 0.199669 0.612748 0.2167659 0.581692 0.2049109 0.61424 0.199669 0.581692 0.2049109 0.581252 0.17956 0.563364 0.993572 0.585644 0.984797 0.594468 0.994642 0.850175 0.228549 0.834882 0.232452 0.844362 0.222375 0.585644 0.984797 0.606286 0.986605 0.594468 0.994642 0.585644 0.984797 0.606633 0.955382 0.606286 0.986605 0.372862 0.905297 0.377618 0.922241 0.347043 0.934073 0.372862 0.905297 0.347043 0.934073 0.345838 0.872258 0.645666 0.821767 0.646157 0.883777 0.626644 0.87421 0.645666 0.821767 0.66006 0.899446 0.646157 0.883777 0.645666 0.821767 0.672469 0.819747 0.66006 0.899446 0.581252 0.17956 0.555608 0.207347 0.536492 0.181671 0.581252 0.17956 0.581692 0.2049109 0.555608 0.207347 0.001996994 0.317462 0.02023088 0.316661 0.02518945 0.3353 0.672334 0.619717 0.656725 0.642205 0.651828 0.624021 0.382971 0.121936 0.409847 0.130582 0.387612 0.157095 0.382971 0.121936 0.387612 0.157095 0.339072 0.128435 0.377618 0.922241 0.369494 0.955216 0.347043 0.934073 0.377618 0.922241 0.388819 0.972068 0.369494 0.955216 0.409847 0.130582 0.449212 0.151762 0.387612 0.157095 0.605628 0.475091 0.608999 0.526822 0.582048 0.506446 0.605628 0.475091 0.582048 0.506446 0.579086 0.479354 0.491088 0.164562 0.536492 0.181671 0.459635 0.187584 0.491088 0.164562 0.459635 0.187584 0.449212 0.151762 0.570183 0.418058 0.579086 0.479354 0.563776 0.476098 0.570183 0.418058 0.563776 0.476098 0.541838 0.42463 0.570183 0.418058 0.541838 0.42463 0.54393 0.372066 0.694174 0.670299 0.717361 0.669703 0.708795 0.706857 0.694174 0.670299 0.708795 0.706857 0.687785 0.705656 0.2823 0.2389799 0.271718 0.259019 0.262979 0.262279 0.28825 0.700855 0.302314 0.791752 0.283955 0.76523 0.28825 0.700855 0.283955 0.76523 0.27399 0.675474 0.4141 0.983149 0.380401 0.988869 0.388819 0.972068 0.449212 0.151762 0.459635 0.187584 0.427456 0.1887699 0.449212 0.151762 0.427456 0.1887699 0.387612 0.157095 0.687785 0.705656 0.685987 0.757301 0.671163 0.753909 0.687785 0.705656 0.708795 0.706857 0.685987 0.757301 0.740992 0.635695 0.767297 0.632977 0.749561 0.642813 0.740992 0.635695 0.748501 0.545012 0.760673 0.587021 0.740992 0.635695 0.760673 0.587021 0.767297 0.632977 0.644722 0.2246429 0.66311 0.222541 0.636172 0.245774 0.02518945 0.3353 0.04754698 0.34493 0.03499859 0.355105 0.644722 0.2246429 0.62541 0.234977 0.612748 0.2167659 0.0566495 0.268579 0.07917177 0.291126 0.05280345 0.271909 0.0566495 0.268579 0.05280345 0.271909 0.0362336 0.261236 0.749561 0.642813 0.767297 0.632977 0.788468 0.643598 0.0566495 0.268579 0.09563857 0.294021 0.07917177 0.291126 0.240307 0.143562 0.269801 0.1841329 0.2335129 0.205923 0.240307 0.143562 0.2335129 0.205923 0.2010239 0.165771 0.110055 0.138151 0.1012549 0.1920869 0.07603275 0.172322 0.110055 0.138151 0.155387 0.165864 0.1012549 0.1920869 0.626644 0.87421 0.646375 0.977458 0.623278 0.972919 0.626644 0.87421 0.646157 0.883777 0.646375 0.977458 0.626644 0.87421 0.623278 0.972919 0.606633 0.955382 0.345838 0.872258 0.324939 0.876156 0.319247 0.834786 0.345838 0.872258 0.347043 0.934073 0.329476 0.928108 0.345838 0.872258 0.329476 0.928108 0.324939 0.876156 0.536492 0.181671 0.555608 0.207347 0.528662 0.209367 0.536492 0.181671 0.528662 0.209367 0.459635 0.187584 0.671163 0.753909 0.685987 0.757301 0.672469 0.819747 0.02023088 0.316661 0.03667086 0.318417 0.04754698 0.34493 0.321999 0.09697848 0.339072 0.128435 0.322128 0.12357 0.834882 0.232452 0.808382 0.237151 0.844362 0.222375 0.581692 0.2049109 0.612748 0.2167659 0.57213 0.233653 0.581692 0.2049109 0.57213 0.233653 0.555608 0.207347 0.54393 0.372066 0.519923 0.370766 0.527509 0.336671 0.54393 0.372066 0.541838 0.42463 0.519923 0.370766 0.844362 0.222375 0.775812 0.235244 0.761827 0.1879889 0.844362 0.222375 0.808382 0.237151 0.775812 0.235244 0.844362 0.222375 0.761827 0.1879889 0.828282 0.160665 0.271718 0.259019 0.272739 0.26585 0.249884 0.282916 0.271718 0.259019 0.249884 0.282916 0.262979 0.262279 0.606633 0.955382 0.623278 0.972919 0.606286 0.986605 0.388819 0.972068 0.362475 0.982197 0.369494 0.955216 0.388819 0.972068 0.380401 0.988869 0.362475 0.982197 0.631617 0.58325 0.590841 0.595692 0.611187 0.565957 0.631617 0.58325 0.630867 0.647104 0.6038 0.613104 0.631617 0.58325 0.651828 0.624021 0.630867 0.647104 0.631617 0.58325 0.6038 0.613104 0.590841 0.595692 0.579086 0.479354 0.582048 0.506446 0.565233 0.497271 0.579086 0.479354 0.565233 0.497271 0.563776 0.476098 0.302314 0.791752 0.29901 0.886997 0.289159 0.853453 0.302314 0.791752 0.319247 0.834786 0.29901 0.886997 0.302314 0.791752 0.289159 0.853453 0.283955 0.76523 0.527509 0.336671 0.519923 0.370766 0.502711 0.338035 0.527509 0.336671 0.502711 0.338035 0.512752 0.322808 0.256763 0.320786 0.246193 0.334799 0.23395 0.317033 0.155387 0.165864 0.2010239 0.165771 0.181275 0.219622 0.155387 0.165864 0.181275 0.219622 0.137702 0.2308149 0.155387 0.165864 0.137702 0.2308149 0.1012549 0.1920869 0.651828 0.624021 0.656725 0.642205 0.630867 0.647104 0.339072 0.128435 0.323404 0.149545 0.322128 0.12357 0.339072 0.128435 0.369878 0.1664389 0.323404 0.149545 0.339072 0.128435 0.387612 0.157095 0.369878 0.1664389 0.555608 0.207347 0.57213 0.233653 0.528662 0.209367 0.612748 0.2167659 0.62541 0.234977 0.57213 0.233653 0.03667086 0.318417 0.06304121 0.316352 0.05824565 0.327257 0.03667086 0.318417 0.05824565 0.327257 0.04754698 0.34493 0.270408 0.1431739 0.279175 0.154842 0.27709 0.1874009 0.270408 0.1431739 0.27709 0.1874009 0.269801 0.1841329 0.656725 0.642205 0.656372 0.65443 0.630867 0.647104 0.07603275 0.172322 0.07631027 0.209343 0.06631207 0.172393 0.07603275 0.172322 0.1012549 0.1920869 0.09930247 0.234826 0.07603275 0.172322 0.09930247 0.234826 0.07631027 0.209343 0.608999 0.526822 0.585675 0.52352 0.582048 0.506446 0.608999 0.526822 0.611187 0.565957 0.585675 0.52352 0.646157 0.883777 0.66006 0.899446 0.646375 0.977458 0.319247 0.834786 0.324939 0.876156 0.29901 0.886997 0.685987 0.757301 0.704915 0.783232 0.693478 0.815043 0.685987 0.757301 0.693478 0.815043 0.672469 0.819747 0.685987 0.757301 0.708795 0.706857 0.704915 0.783232 0.748501 0.545012 0.767595 0.514582 0.760673 0.587021 0.748501 0.545012 0.76035 0.456006 0.767595 0.514582 0.955862 0.636667 0.937682 0.635935 0.93989 0.604981 0.955862 0.636667 0.93989 0.604981 0.959534 0.599206 0.481095 0.653215 0.453932 0.660555 0.462936 0.652068 0.262979 0.262279 0.249884 0.282916 0.2358109 0.287699 0.2010239 0.165771 0.2335129 0.205923 0.181275 0.219622 0.808382 0.237151 0.782431 0.237809 0.775812 0.235244 0.611187 0.565957 0.590841 0.595692 0.581781 0.551915 0.611187 0.565957 0.581781 0.551915 0.585675 0.52352 0.387612 0.157095 0.427456 0.1887699 0.369878 0.1664389 0.672469 0.819747 0.678325 0.896606 0.66006 0.899446 0.672469 0.819747 0.693478 0.815043 0.678325 0.896606 0.959534 0.599206 0.93989 0.604981 0.943399 0.552913 0.959534 0.599206 0.943399 0.552913 0.951632 0.523074 0.03499859 0.355105 0.05946135 0.408385 0.0408113 0.408703 0.03499859 0.355105 0.04754698 0.34493 0.06560856 0.368794 0.03499859 0.355105 0.06560856 0.368794 0.05946135 0.408385 0.23395 0.317033 0.218612 0.327409 0.199524 0.316967 0.249884 0.282916 0.215631 0.305442 0.2358109 0.287699 0.23395 0.317033 0.246193 0.334799 0.218612 0.327409 0.04754698 0.34493 0.05824565 0.327257 0.06560856 0.368794 0.369494 0.955216 0.362475 0.982197 0.343462 0.981205 0.369494 0.955216 0.343462 0.981205 0.347043 0.934073 0.324939 0.876156 0.329476 0.928108 0.304972 0.911108 0.324939 0.876156 0.304972 0.911108 0.29901 0.886997 0.459635 0.187584 0.494483 0.222247 0.44786 0.215981 0.459635 0.187584 0.44786 0.215981 0.427456 0.1887699 0.459635 0.187584 0.528662 0.209367 0.494483 0.222247 0.528662 0.209367 0.57213 0.233653 0.530388 0.239284 0.528662 0.209367 0.530388 0.239284 0.494483 0.222247 0.256763 0.36918 0.2359949 0.375179 0.246193 0.334799 0.256763 0.36918 0.249594 0.401268 0.2359949 0.375179 0.519923 0.370766 0.541838 0.42463 0.519805 0.403237 0.06304121 0.316352 0.07647037 0.326713 0.05824565 0.327257 0.07917177 0.291126 0.09563857 0.294021 0.127291 0.309302 0.06304121 0.316352 0.111117 0.315903 0.07647037 0.326713 0.767297 0.632977 0.797668 0.632754 0.788468 0.643598 0.767297 0.632977 0.777695 0.589612 0.797668 0.632754 0.767297 0.632977 0.760673 0.587021 0.777695 0.589612 0.656372 0.65443 0.61487 0.656764 0.630867 0.647104 0.606286 0.986605 0.623278 0.972919 0.63879 0.990258 0.582048 0.506446 0.585675 0.52352 0.565233 0.497271 0.563776 0.476098 0.529138 0.48219 0.523275 0.431413 0.563776 0.476098 0.523275 0.431413 0.541838 0.42463 0.563776 0.476098 0.565233 0.497271 0.529138 0.48219 0.541838 0.42463 0.523275 0.431413 0.519805 0.403237 0.462936 0.652068 0.430858 0.659041 0.435097 0.65151 0.937682 0.635935 0.909837 0.63601 0.919887 0.606714 0.462936 0.652068 0.453932 0.660555 0.430858 0.659041 0.937682 0.635935 0.919887 0.606714 0.93989 0.604981 0.788468 0.643598 0.797668 0.632754 0.813908 0.640005 0.09563857 0.294021 0.121259 0.30084 0.127291 0.309302 0.1012549 0.1920869 0.137702 0.2308149 0.09930247 0.234826 0.380401 0.988869 0.343572 0.992331 0.362475 0.982197 0.623278 0.972919 0.646375 0.977458 0.63879 0.990258 0.347043 0.934073 0.343462 0.981205 0.329476 0.928108 0.585675 0.52352 0.559995 0.54838 0.565233 0.497271 0.585675 0.52352 0.581781 0.551915 0.559995 0.54838 0.0408113 0.408703 0.05946135 0.408385 0.05147218 0.450991 0.760673 0.587021 0.767595 0.514582 0.777695 0.589612 0.246193 0.334799 0.2359949 0.375179 0.218612 0.327409 0.05824565 0.327257 0.07647037 0.326713 0.06560856 0.368794 0.93989 0.604981 0.919887 0.606714 0.922137 0.541751 0.93989 0.604981 0.922137 0.541751 0.943399 0.552913 0.2358109 0.287699 0.215631 0.305442 0.21284 0.297737 0.797668 0.632754 0.777695 0.589612 0.800957 0.568424 0.797668 0.632754 0.800957 0.568424 0.82667 0.580275 0.797668 0.632754 0.82667 0.580275 0.813908 0.640005 0.269801 0.1841329 0.257579 0.221025 0.2335129 0.205923 0.269801 0.1841329 0.27709 0.1874009 0.257579 0.221025 0.951632 0.523074 0.943399 0.552913 0.936281 0.487829 0.704915 0.783232 0.714293 0.819257 0.693478 0.815043 0.362475 0.982197 0.343572 0.992331 0.343462 0.981205 0.66006 0.899446 0.678325 0.896606 0.671696 0.982636 0.66006 0.899446 0.671696 0.982636 0.646375 0.977458 0.909837 0.63601 0.870533 0.640558 0.893068 0.611816 0.435097 0.65151 0.430858 0.659041 0.3957 0.655161 0.909837 0.63601 0.893068 0.611816 0.919887 0.606714 0.777695 0.589612 0.767595 0.514582 0.790355 0.510595 0.777695 0.589612 0.790355 0.510595 0.800957 0.568424 0.218612 0.327409 0.207985 0.397435 0.1893399 0.374291 0.218612 0.327409 0.2359949 0.375179 0.207985 0.397435 0.218612 0.327409 0.1893399 0.374291 0.199524 0.316967 0.21284 0.297737 0.215631 0.305442 0.190079 0.310454 0.21284 0.297737 0.190079 0.310454 0.1778219 0.304291 0.630867 0.647104 0.61487 0.656764 0.6038 0.613104 0.606332 0.66527 0.616691 0.662589 0.606673 0.665659 0.323404 0.149545 0.323074 0.177258 0.32107 0.159767 0.782431 0.237809 0.771906 0.237676 0.775812 0.235244 0.323404 0.149545 0.369878 0.1664389 0.333304 0.174517 0.323404 0.149545 0.333304 0.174517 0.323074 0.177258 0.646375 0.977458 0.671696 0.982636 0.63879 0.990258 0.369878 0.1664389 0.427456 0.1887699 0.363288 0.1975679 0.369878 0.1664389 0.363288 0.1975679 0.333304 0.174517 0.693478 0.815043 0.696463 0.884977 0.678325 0.896606 0.693478 0.815043 0.714293 0.819257 0.696463 0.884977 0.07647037 0.326713 0.111117 0.315903 0.110328 0.329721 0.07647037 0.326713 0.09228128 0.405749 0.06560856 0.368794 0.07647037 0.326713 0.110328 0.329721 0.09228128 0.405749 0.127291 0.309302 0.121259 0.30084 0.154713 0.311154 0.111117 0.315903 0.138513 0.316839 0.1367689 0.328522 0.111117 0.315903 0.1367689 0.328522 0.110328 0.329721 0.249594 0.401268 0.225915 0.418598 0.2359949 0.375179 0.249594 0.401268 0.248358 0.429592 0.225915 0.418598 0.2359949 0.375179 0.225915 0.418598 0.207985 0.397435 0.919887 0.606714 0.905884 0.544301 0.922137 0.541751 0.919887 0.606714 0.893068 0.611816 0.905884 0.544301 0.339102 0.65332 0.361264 0.653902 0.372654 0.659975 0.813908 0.640005 0.82667 0.580275 0.844176 0.606871 0.813908 0.640005 0.844176 0.606871 0.836078 0.640082 0.329476 0.928108 0.312328 0.941161 0.304972 0.911108 0.329476 0.928108 0.317276 0.982067 0.312328 0.941161 0.329476 0.928108 0.343462 0.981205 0.317276 0.982067 0.427456 0.1887699 0.401617 0.204532 0.363288 0.1975679 0.427456 0.1887699 0.44786 0.215981 0.401617 0.204532 0.248358 0.429592 0.242913 0.480459 0.222715 0.480264 0.248358 0.429592 0.222715 0.480264 0.225915 0.418598 0.767595 0.514582 0.784231 0.465391 0.790355 0.510595 0.767595 0.514582 0.76035 0.456006 0.784231 0.465391 0.06560856 0.368794 0.09228128 0.405749 0.05946135 0.408385 0.199524 0.316967 0.181313 0.325019 0.173983 0.315455 0.199524 0.316967 0.1893399 0.374291 0.181313 0.325019 0.143427 0.304789 0.1778219 0.304291 0.154713 0.311154 0.836078 0.640082 0.844176 0.606871 0.870533 0.640558 0.110328 0.329721 0.114943 0.403743 0.09228128 0.405749 0.110328 0.329721 0.1367689 0.328522 0.114943 0.403743 0.63879 0.990258 0.671696 0.982636 0.672233 0.995442 0.6038 0.613104 0.584954 0.635827 0.578793 0.610536 0.6038 0.613104 0.578793 0.610536 0.590841 0.595692 0.6038 0.613104 0.61487 0.656764 0.584954 0.635827 0.590841 0.595692 0.56028 0.601466 0.559995 0.54838 0.590841 0.595692 0.559995 0.54838 0.581781 0.551915 0.590841 0.595692 0.578793 0.610536 0.56028 0.601466 0.565233 0.497271 0.543477 0.504354 0.529138 0.48219 0.565233 0.497271 0.559995 0.54838 0.543477 0.504354 0.678325 0.896606 0.682659 0.968892 0.671696 0.982636 0.678325 0.896606 0.696463 0.884977 0.682659 0.968892 0.757594 0.421925 0.779126 0.396643 0.76035 0.456006 0.757594 0.421925 0.757264 0.397433 0.779126 0.396643 0.05946135 0.408385 0.0735827 0.452183 0.05147218 0.450991 0.05946135 0.408385 0.09228128 0.405749 0.0735827 0.452183 0.800957 0.568424 0.790355 0.510595 0.81198 0.522207 0.800957 0.568424 0.81198 0.522207 0.82667 0.580275 0.893068 0.611816 0.864363 0.573067 0.884964 0.569384 0.893068 0.611816 0.884964 0.569384 0.905884 0.544301 0.893068 0.611816 0.870533 0.640558 0.864363 0.573067 0.1778219 0.304291 0.190079 0.310454 0.154713 0.311154 0.870533 0.640558 0.844176 0.606871 0.864363 0.573067 0.138513 0.316839 0.173983 0.315455 0.1367689 0.328522 0.61487 0.656764 0.588193 0.658557 0.584954 0.635827 0.2335129 0.205923 0.231648 0.247888 0.199744 0.264806 0.2335129 0.205923 0.257579 0.221025 0.231648 0.247888 0.2335129 0.205923 0.199744 0.264806 0.181275 0.219622 0.181275 0.219622 0.1586509 0.264407 0.137702 0.2308149 0.181275 0.219622 0.199744 0.264806 0.1586509 0.264407 0.343462 0.981205 0.343572 0.992331 0.317276 0.982067 0.494483 0.222247 0.472437 0.234022 0.44786 0.215981 0.03792107 0.486275 0.06897908 0.512118 0.05440068 0.509124 0.03792107 0.486275 0.05147218 0.450991 0.06897908 0.512118 0.242913 0.480459 0.232196 0.507918 0.222715 0.480264 0.529138 0.48219 0.543477 0.504354 0.524327 0.51052 0.173983 0.315455 0.181313 0.325019 0.1531 0.335842 0.173983 0.315455 0.1531 0.335842 0.1367689 0.328522 0.05147218 0.450991 0.0735827 0.452183 0.06897908 0.512118 0.790355 0.510595 0.814235 0.453692 0.81198 0.522207 0.790355 0.510595 0.784231 0.465391 0.814235 0.453692 0.225915 0.418598 0.202255 0.429169 0.207985 0.397435 0.225915 0.418598 0.222715 0.480264 0.202255 0.429169 0.922137 0.541751 0.936281 0.487829 0.943399 0.552913 0.922137 0.541751 0.914798 0.484472 0.936281 0.487829 0.922137 0.541751 0.905884 0.544301 0.914798 0.484472 0.07631027 0.209343 0.096309 0.243603 0.08191215 0.234808 0.07631027 0.209343 0.09930247 0.234826 0.096309 0.243603 0.76035 0.456006 0.779126 0.396643 0.784231 0.465391 0.936281 0.487829 0.914798 0.484472 0.917698 0.400523 0.936281 0.487829 0.917698 0.400523 0.944603 0.421451 0.82667 0.580275 0.838047 0.519559 0.844176 0.606871 0.82667 0.580275 0.81198 0.522207 0.838047 0.519559 0.844176 0.606871 0.838047 0.519559 0.864363 0.573067 0.181313 0.325019 0.1893399 0.374291 0.1605139 0.402721 0.181313 0.325019 0.1605139 0.402721 0.1531 0.335842 0.1367689 0.328522 0.138475 0.393174 0.114943 0.403743 0.1367689 0.328522 0.1531 0.335842 0.138475 0.393174 0.255783 0.549319 0.235877 0.576835 0.2407439 0.566851 0.559995 0.54838 0.56028 0.601466 0.539003 0.578331 0.559995 0.54838 0.544741 0.567705 0.536335 0.538835 0.559995 0.54838 0.536335 0.538835 0.543477 0.504354 0.44786 0.215981 0.41396 0.2229 0.401617 0.204532 0.03848677 0.532959 0.05440068 0.509124 0.04853868 0.567371 0.543477 0.504354 0.536335 0.538835 0.524327 0.51052 0.784231 0.465391 0.804473 0.418751 0.814235 0.453692 0.784231 0.465391 0.779126 0.396643 0.804473 0.418751 0.207985 0.397435 0.202255 0.429169 0.178187 0.404087 0.207985 0.397435 0.178187 0.404087 0.1893399 0.374291 0.905884 0.544301 0.884964 0.569384 0.891466 0.501745 0.905884 0.544301 0.891466 0.501745 0.914798 0.484472 0.09228128 0.405749 0.117106 0.435478 0.0926662 0.468423 0.09228128 0.405749 0.0926662 0.468423 0.0735827 0.452183 0.09228128 0.405749 0.114943 0.403743 0.117106 0.435478 0.1893399 0.374291 0.178187 0.404087 0.1605139 0.402721 0.864363 0.573067 0.865112 0.518847 0.884964 0.569384 0.864363 0.573067 0.838047 0.519559 0.865112 0.518847 0.1531 0.335842 0.1605139 0.402721 0.138475 0.393174 0.257579 0.221025 0.250232 0.239723 0.231648 0.247888 0.672233 0.995442 0.671696 0.982636 0.690933 0.991544 0.333304 0.174517 0.324021 0.205214 0.323074 0.177258 0.333304 0.174517 0.363288 0.1975679 0.324021 0.205214 0.757264 0.397433 0.7562 0.366942 0.779126 0.396643 0.81198 0.522207 0.814235 0.453692 0.831617 0.465537 0.81198 0.522207 0.831617 0.465537 0.838047 0.519559 0.884964 0.569384 0.865112 0.518847 0.891466 0.501745 0.114943 0.403743 0.132858 0.430953 0.117106 0.435478 0.114943 0.403743 0.1605139 0.402721 0.132858 0.430953 0.114943 0.403743 0.138475 0.393174 0.1605139 0.402721 0.05588179 0.197588 0.05834388 0.2150689 0.05551218 0.197904 0.754695 0.235224 0.775812 0.235244 0.771906 0.237676 0.754695 0.235224 0.761827 0.1879889 0.775812 0.235244 0.754695 0.235224 0.726509 0.219796 0.761827 0.1879889 0.312328 0.941161 0.317276 0.982067 0.297012 0.982733 0.7562 0.366942 0.779206 0.325494 0.791519 0.331556 0.7562 0.366942 0.791519 0.331556 0.786729 0.372746 0.7562 0.366942 0.786729 0.372746 0.779126 0.396643 0.696463 0.884977 0.700204 0.946366 0.682659 0.968892 0.944603 0.421451 0.917698 0.400523 0.932425 0.360606 0.401617 0.204532 0.389907 0.2287189 0.360746 0.214882 0.401617 0.204532 0.360746 0.214882 0.363288 0.1975679 0.401617 0.204532 0.41396 0.2229 0.389907 0.2287189 0.779126 0.396643 0.803608 0.368208 0.804473 0.418751 0.779126 0.396643 0.786729 0.372746 0.803608 0.368208 0.914798 0.484472 0.891466 0.501745 0.901473 0.451381 0.914798 0.484472 0.901473 0.451381 0.917698 0.400523 0.584954 0.635827 0.56506 0.617692 0.578793 0.610536 0.584954 0.635827 0.574134 0.659444 0.56506 0.617692 0.584954 0.635827 0.588193 0.658557 0.574134 0.659444 0.363288 0.1975679 0.360746 0.214882 0.324021 0.205214 0.232196 0.507918 0.239176 0.537359 0.210194 0.523526 0.232196 0.507918 0.193955 0.502136 0.222715 0.480264 0.232196 0.507918 0.210194 0.523526 0.193955 0.502136 0.05440068 0.509124 0.06265038 0.563758 0.04853868 0.567371 0.05440068 0.509124 0.06897908 0.512118 0.06265038 0.563758 0.0735827 0.452183 0.08773958 0.523251 0.06897908 0.512118 0.0735827 0.452183 0.0926662 0.468423 0.08773958 0.523251 0.202255 0.429169 0.18323 0.439978 0.164688 0.42918 0.202255 0.429169 0.164688 0.42918 0.178187 0.404087 0.202255 0.429169 0.197817 0.473088 0.18323 0.439978 0.202255 0.429169 0.222715 0.480264 0.197817 0.473088 0.891466 0.501745 0.865112 0.518847 0.882858 0.470314 0.891466 0.501745 0.882858 0.470314 0.901473 0.451381 0.838047 0.519559 0.860082 0.463914 0.865112 0.518847 0.838047 0.519559 0.831617 0.465537 0.860082 0.463914 0.1605139 0.402721 0.164688 0.42918 0.132858 0.430953 0.1605139 0.402721 0.178187 0.404087 0.164688 0.42918 0.137702 0.2308149 0.1586509 0.264407 0.09930247 0.234826 0.671696 0.982636 0.696796 0.976839 0.690933 0.991544 0.671696 0.982636 0.682659 0.968892 0.696796 0.976839 0.578793 0.610536 0.56506 0.617692 0.56028 0.601466 0.222715 0.480264 0.193955 0.502136 0.197817 0.473088 0.06897908 0.512118 0.08909839 0.588247 0.06265038 0.563758 0.06897908 0.512118 0.08773958 0.523251 0.08909839 0.588247 0.865112 0.518847 0.860082 0.463914 0.882858 0.470314 0.317276 0.982067 0.308997 0.990601 0.297012 0.982733 0.239176 0.537359 0.2407439 0.566851 0.2239429 0.554309 0.239176 0.537359 0.2239429 0.554309 0.210194 0.523526 0.04853868 0.567371 0.06265038 0.563758 0.05808454 0.591898 0.917698 0.400523 0.908176 0.366716 0.932425 0.360606 0.917698 0.400523 0.901473 0.451381 0.890469 0.407191 0.917698 0.400523 0.890469 0.407191 0.908176 0.366716 0.117106 0.435478 0.124345 0.500828 0.111415 0.508223 0.117106 0.435478 0.111415 0.508223 0.0926662 0.468423 0.117106 0.435478 0.132858 0.430953 0.144635 0.460824 0.117106 0.435478 0.144635 0.460824 0.124345 0.500828 0.750683 0.01154315 0.807973 0.06941205 0.759936 0.08270537 0.750683 0.01154315 0.699398 0.0510779 0.73667 0.01624286 0.750683 0.01154315 0.678998 0.108098 0.699398 0.0510779 0.750683 0.01154315 0.759936 0.08270537 0.678998 0.108098 0.56028 0.601466 0.542348 0.622905 0.529209 0.594056 0.56028 0.601466 0.529209 0.594056 0.539003 0.578331 0.56028 0.601466 0.56506 0.617692 0.542348 0.622905 0.682659 0.968892 0.700204 0.946366 0.696796 0.976839 0.814235 0.453692 0.804473 0.418751 0.821759 0.392439 0.814235 0.453692 0.821759 0.392439 0.843753 0.424994 0.814235 0.453692 0.843753 0.424994 0.831617 0.465537 0.0926662 0.468423 0.111415 0.508223 0.08773958 0.523251 0.18323 0.439978 0.164427 0.448425 0.164688 0.42918 0.18323 0.439978 0.157269 0.510988 0.164427 0.448425 0.18323 0.439978 0.193955 0.502136 0.157269 0.510988 0.18323 0.439978 0.197817 0.473088 0.193955 0.502136 0.164688 0.42918 0.164427 0.448425 0.132858 0.430953 0.132858 0.430953 0.164427 0.448425 0.144635 0.460824 0.09930247 0.234826 0.1586509 0.264407 0.128762 0.264399 0.09930247 0.234826 0.128762 0.264399 0.096309 0.243603 0.324021 0.205214 0.360746 0.214882 0.335721 0.224184 0.324021 0.205214 0.335721 0.224184 0.324625 0.225898 0.689068 0.175754 0.726509 0.219796 0.705594 0.204468 0.726509 0.219796 0.689068 0.175754 0.761827 0.1879889 0.235877 0.576835 0.2239429 0.554309 0.2407439 0.566851 0.235877 0.576835 0.218537 0.591052 0.2239429 0.554309 0.831617 0.465537 0.843753 0.424994 0.860082 0.463914 0.882858 0.470314 0.890469 0.407191 0.901473 0.451381 0.882858 0.470314 0.860082 0.463914 0.890469 0.407191 0.860082 0.463914 0.862464 0.411202 0.890469 0.407191 0.860082 0.463914 0.843753 0.424994 0.862464 0.411202 0.56506 0.617692 0.550879 0.66071 0.542348 0.622905 0.56506 0.617692 0.574134 0.659444 0.550879 0.66071 0.04684156 0.620545 0.07095199 0.626072 0.06002205 0.64622 0.04684156 0.620545 0.05808454 0.591898 0.07095199 0.626072 0.05808454 0.591898 0.06265038 0.563758 0.08909839 0.588247 0.05808454 0.591898 0.08909839 0.588247 0.07095199 0.626072 0.932425 0.360606 0.908176 0.366716 0.932422 0.330063 0.804473 0.418751 0.803608 0.368208 0.821759 0.392439 0.08773958 0.523251 0.111415 0.508223 0.101088 0.564852 0.08773958 0.523251 0.101088 0.564852 0.08909839 0.588247 0.164427 0.448425 0.157269 0.510988 0.144635 0.460824 0.774447 0.316985 0.806733 0.315455 0.779206 0.325494 0.786729 0.372746 0.791519 0.331556 0.803608 0.368208 0.2239429 0.554309 0.203013 0.53853 0.210194 0.523526 0.2239429 0.554309 0.196835 0.560605 0.203013 0.53853 0.2239429 0.554309 0.218537 0.591052 0.196835 0.560605 0.210194 0.523526 0.203013 0.53853 0.183941 0.52094 0.210194 0.523526 0.183941 0.52094 0.193955 0.502136 0.193955 0.502136 0.183941 0.52094 0.157269 0.510988 0.144635 0.460824 0.157269 0.510988 0.124345 0.500828 0.250232 0.239723 0.2285889 0.260176 0.231648 0.247888 0.928483 0.315455 0.932422 0.330063 0.906813 0.318149 0.231648 0.247888 0.2285889 0.260176 0.199744 0.264806 0.199744 0.264806 0.189869 0.278985 0.1758829 0.274895 0.199744 0.264806 0.2285889 0.260176 0.189869 0.278985 0.199744 0.264806 0.1758829 0.274895 0.1586509 0.264407 0.111415 0.508223 0.135245 0.528698 0.101088 0.564852 0.111415 0.508223 0.124345 0.500828 0.135245 0.528698 0.124345 0.500828 0.157269 0.510988 0.135245 0.528698 0.73667 0.01624286 0.699398 0.0510779 0.713666 0.0342313 0.932422 0.330063 0.907018 0.32575 0.906813 0.318149 0.932422 0.330063 0.908176 0.366716 0.907018 0.32575 0.779206 0.325494 0.806733 0.315455 0.791519 0.331556 0.890469 0.407191 0.862464 0.411202 0.877389 0.364605 0.890469 0.407191 0.877389 0.364605 0.908176 0.366716 0.08909839 0.588247 0.122005 0.586727 0.112189 0.644898 0.08909839 0.588247 0.101088 0.564852 0.122005 0.586727 0.08909839 0.588247 0.112189 0.644898 0.08760559 0.657367 0.08909839 0.588247 0.08760559 0.657367 0.07095199 0.626072 0.843753 0.424994 0.848751 0.374327 0.862464 0.411202 0.843753 0.424994 0.821759 0.392439 0.848751 0.374327 0.157269 0.510988 0.150994 0.591748 0.135245 0.528698 0.157269 0.510988 0.177157 0.571353 0.150994 0.591748 0.157269 0.510988 0.183941 0.52094 0.177157 0.571353 0.1586509 0.264407 0.151129 0.274139 0.128762 0.264399 0.1586509 0.264407 0.1758829 0.274895 0.151129 0.274139 0.218537 0.591052 0.2287189 0.621252 0.203141 0.634694 0.218537 0.591052 0.203141 0.634694 0.196835 0.560605 0.203013 0.53853 0.196835 0.560605 0.183941 0.52094 0.821759 0.392439 0.823358 0.330369 0.848751 0.374327 0.821759 0.392439 0.803608 0.368208 0.823358 0.330369 0.862464 0.411202 0.848751 0.374327 0.877389 0.364605 0.2287189 0.621252 0.212126 0.659691 0.203141 0.634694 0.2287189 0.621252 0.228765 0.659607 0.212126 0.659691 0.06002205 0.64622 0.08760559 0.657367 0.05860716 0.657266 0.06002205 0.64622 0.07095199 0.626072 0.08760559 0.657367 0.791519 0.331556 0.823358 0.330369 0.803608 0.368208 0.791519 0.331556 0.806733 0.315455 0.823358 0.330369 0.183941 0.52094 0.196835 0.560605 0.177157 0.571353 0.806733 0.315455 0.829189 0.318219 0.823358 0.330369 0.908176 0.366716 0.887742 0.330299 0.907018 0.32575 0.908176 0.366716 0.877389 0.364605 0.887742 0.330299 0.196835 0.560605 0.203141 0.634694 0.177157 0.571353 0.101088 0.564852 0.135245 0.528698 0.122005 0.586727 0.135245 0.528698 0.150994 0.591748 0.122005 0.586727 0.906813 0.318149 0.907018 0.32575 0.868213 0.324152 0.907018 0.32575 0.887742 0.330299 0.868213 0.324152 0.848751 0.374327 0.848472 0.327153 0.868213 0.324152 0.848751 0.374327 0.868213 0.324152 0.877389 0.364605 0.848751 0.374327 0.823358 0.330369 0.848472 0.327153 0.177157 0.571353 0.203141 0.634694 0.174387 0.621149 0.177157 0.571353 0.174387 0.621149 0.150994 0.591748 0.823358 0.330369 0.829189 0.318219 0.848472 0.327153 0.877389 0.364605 0.868213 0.324152 0.887742 0.330299 0.122005 0.586727 0.133877 0.639677 0.112189 0.644898 0.122005 0.586727 0.150994 0.591748 0.133877 0.639677 0.150994 0.591748 0.153643 0.638064 0.133877 0.639677 0.150994 0.591748 0.174387 0.621149 0.153643 0.638064 0.203141 0.634694 0.178178 0.657149 0.174387 0.621149 0.203141 0.634694 0.212126 0.659691 0.188827 0.659013 0.203141 0.634694 0.188827 0.659013 0.178178 0.657149 0.699398 0.0510779 0.678998 0.108098 0.682218 0.07466048 0.829189 0.318219 0.853927 0.317402 0.848472 0.327153 0.689068 0.175754 0.677855 0.1491259 0.731261 0.144028 0.689068 0.175754 0.731261 0.144028 0.761827 0.1879889 0.08760559 0.657367 0.112189 0.644898 0.114421 0.657721 0.868213 0.324152 0.848472 0.327153 0.853927 0.317402 0.174387 0.621149 0.178178 0.657149 0.153643 0.638064 0.112189 0.644898 0.128574 0.657871 0.114421 0.657721 0.112189 0.644898 0.133877 0.639677 0.128574 0.657871 0.153643 0.638064 0.178178 0.657149 0.155434 0.658468 0.153643 0.638064 0.155434 0.658468 0.133877 0.639677 0.133877 0.639677 0.155434 0.658468 0.128574 0.657871 0.677855 0.1491259 0.67483 0.135028 0.678998 0.108098 0.677855 0.1491259 0.678998 0.108098 0.731261 0.144028 0.678998 0.108098 0.759936 0.08270537 0.731261 0.144028 0.678998 0.108098 0.67944 0.08542895 0.682218 0.07466048 0.828282 0.160665 0.761827 0.1879889 0.821914 0.119079 0.821914 0.119079 0.761827 0.1879889 0.731261 0.144028 0.821914 0.119079 0.731261 0.144028 0.759936 0.08270537 0.821914 0.119079 0.759936 0.08270537 0.807973 0.06941205 - - - - - - - - - - - - - - - 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 -

0 0 0 1 1 1 2 2 2 0 0 3 3 3 4 4 4 5 0 0 6 2 2 7 3 3 8 0 0 9 4 4 10 1 1 11 2 2 12 1 1 13 5 5 14 2 2 15 5 5 16 6 6 17 2 2 18 7 7 19 8 8 20 2 2 21 8 8 22 3 3 23 2 2 24 6 6 25 7 7 26 4 4 27 3 3 28 9 9 29 4 4 30 9 9 31 10 10 32 4 4 33 10 10 34 11 11 35 4 4 36 11 11 37 12 12 38 4 4 39 12 12 40 13 13 41 4 4 42 13 13 43 1 1 44 1 1 45 14 14 46 5 5 47 1 1 48 15 15 49 14 14 50 1 1 51 13 13 52 15 15 53 3 3 54 8 8 55 16 16 56 3 3 57 16 16 58 9 9 59 5 5 60 14 14 61 17 17 62 5 5 63 18 18 64 6 6 65 5 5 66 19 19 67 18 18 68 5 5 69 20 20 70 19 19 71 5 5 72 17 17 73 20 20 74 18 18 75 21 21 76 22 22 77 18 18 78 19 19 79 21 21 80 18 18 81 22 22 82 6 6 83 9 9 84 23 23 85 10 10 86 9 9 87 16 16 88 24 24 89 9 9 90 24 24 91 25 25 92 9 9 93 25 25 94 23 23 95 6 6 96 26 26 97 27 27 98 6 6 99 27 27 100 7 7 101 6 6 102 22 22 103 26 26 104 11 11 105 28 28 106 12 12 107 11 11 108 29 29 109 28 28 110 11 11 111 10 10 112 29 29 113 8 8 114 30 30 115 16 16 116 8 8 117 7 7 118 30 30 119 10 10 120 23 23 121 31 31 122 10 10 123 31 31 124 29 29 125 14 14 126 15 15 127 32 32 128 14 14 129 32 32 130 33 33 131 14 14 132 33 33 133 34 34 134 14 14 135 34 34 136 17 17 137 7 7 138 27 27 139 35 35 140 7 7 141 35 35 142 30 30 143 17 17 144 34 34 145 20 20 146 19 19 147 20 20 148 36 36 149 19 19 150 36 36 151 21 21 152 16 16 153 30 30 154 24 24 155 15 15 156 37 37 157 32 32 158 15 15 159 13 13 160 37 37 161 13 13 162 38 38 163 37 37 164 13 13 165 12 12 166 39 39 167 13 13 168 39 39 169 38 38 170 20 20 171 40 40 172 36 36 173 20 20 174 41 41 175 42 42 176 20 20 177 42 42 178 40 40 179 20 20 180 34 34 181 41 41 182 32 32 183 37 37 184 43 43 185 32 32 186 44 44 187 33 33 188 32 32 189 43 43 190 44 44 191 34 34 192 33 33 193 41 41 194 27 27 195 45 45 196 35 35 197 27 27 198 26 26 199 45 45 200 12 12 201 28 28 202 46 46 203 12 12 204 47 47 205 39 39 206 12 12 207 46 46 208 47 47 209 28 28 210 48 48 211 46 46 212 28 28 213 29 29 214 49 49 215 28 28 216 49 49 217 48 48 218 22 22 219 21 21 220 50 50 221 22 22 222 50 50 223 51 51 224 22 22 225 51 51 226 26 26 227 24 24 228 52 52 229 25 25 230 24 24 231 30 30 232 53 53 233 24 24 234 54 54 235 52 52 236 24 24 237 53 53 238 54 54 239 23 23 240 25 25 241 55 55 242 23 23 243 55 55 244 31 31 245 37 37 246 38 38 247 43 43 248 35 35 249 45 45 250 56 56 251 35 35 252 57 57 253 30 30 254 35 35 255 56 56 256 57 57 257 29 29 258 31 31 259 49 49 260 36 36 261 40 40 262 58 58 263 36 36 264 59 59 265 21 21 266 36 36 267 60 60 268 59 59 269 36 36 270 58 58 271 60 60 272 30 30 273 57 57 274 53 53 275 33 33 276 44 44 277 61 61 278 33 33 279 61 61 280 41 41 281 21 21 282 59 59 283 62 62 284 21 21 285 62 62 286 50 50 287 25 25 288 63 63 289 55 55 290 25 25 291 52 52 292 63 63 293 31 31 294 64 64 295 49 49 296 31 31 297 55 55 298 64 64 299 40 40 300 65 65 301 58 58 302 40 40 303 42 42 304 65 65 305 39 39 306 66 66 307 38 38 308 39 39 309 47 47 310 66 66 311 26 26 312 51 51 313 45 45 314 57 57 315 67 67 316 68 68 317 57 57 318 68 68 319 53 53 320 57 57 321 56 56 322 67 67 323 41 41 324 69 69 325 42 42 326 41 41 327 61 61 328 70 70 329 41 41 330 70 70 331 69 69 332 38 38 333 71 71 334 43 43 335 38 38 336 66 66 337 72 72 338 38 38 339 73 73 340 71 71 341 38 38 342 72 72 343 73 73 344 58 58 345 65 65 346 60 60 347 46 46 348 48 48 349 74 74 350 46 46 351 74 74 352 75 75 353 46 46 354 75 75 355 47 47 356 53 53 357 68 68 358 54 54 359 55 55 360 63 63 361 76 76 362 55 55 363 76 76 364 77 77 365 55 55 366 77 77 367 64 64 368 56 56 369 45 45 370 78 78 371 56 56 372 78 78 373 79 79 374 56 56 375 79 79 376 67 67 377 51 51 378 50 50 379 80 80 380 51 51 381 80 80 382 81 81 383 51 51 384 81 81 385 45 45 386 48 48 387 82 82 388 74 74 389 48 48 390 49 49 391 83 83 392 48 48 393 83 83 394 82 82 395 52 52 396 84 84 397 63 63 398 52 52 399 54 54 400 85 85 401 52 52 402 86 86 403 84 84 404 52 52 405 85 85 406 86 86 407 44 44 408 87 87 409 61 61 410 44 44 411 43 43 412 88 88 413 44 44 414 88 88 415 87 87 416 43 43 417 71 71 418 88 88 419 45 45 420 89 89 421 78 78 422 45 45 423 81 81 424 89 89 425 42 42 426 90 90 427 91 91 428 42 42 429 91 91 430 65 65 431 42 42 432 69 69 433 90 90 434 49 49 435 64 64 436 83 83 437 47 47 438 75 75 439 92 92 440 47 47 441 92 92 442 93 93 443 47 47 444 93 93 445 66 66 446 50 50 447 94 94 448 80 80 449 50 50 450 62 62 451 94 94 452 59 59 453 60 60 454 95 95 455 59 59 456 96 96 457 97 97 458 59 59 459 97 97 460 62 62 461 59 59 462 95 95 463 96 96 464 54 54 465 68 68 466 85 85 467 65 65 468 91 91 469 98 98 470 65 65 471 98 98 472 60 60 473 64 64 474 77 77 475 99 99 476 64 64 477 100 100 478 83 83 479 64 64 480 99 99 481 100 100 482 60 60 483 101 101 484 95 95 485 60 60 486 98 98 487 101 101 488 80 80 489 102 102 490 81 81 491 80 80 492 103 103 493 102 102 494 80 80 495 94 94 496 103 103 497 82 82 498 83 83 499 104 104 500 82 82 501 104 104 502 105 105 503 82 82 504 105 105 505 74 74 506 74 74 507 105 105 508 75 75 509 62 62 510 106 106 511 94 94 512 62 62 513 107 107 514 106 106 515 62 62 516 97 97 517 107 107 518 68 68 519 67 67 520 108 108 521 68 68 522 86 86 523 85 85 524 68 68 525 108 108 526 86 86 527 63 63 528 84 84 529 76 76 530 61 61 531 109 109 532 70 70 533 61 61 534 87 87 535 109 109 536 88 88 537 110 110 538 111 111 539 88 88 540 71 71 541 110 110 542 88 88 543 111 111 544 87 87 545 71 71 546 73 73 547 110 110 548 76 76 549 112 112 550 113 113 551 76 76 552 113 113 553 77 77 554 76 76 555 84 84 556 112 112 557 69 69 558 70 70 559 114 114 560 69 69 561 114 114 562 90 90 563 78 78 564 115 115 565 79 79 566 78 78 567 89 89 568 115 115 569 66 66 570 116 116 571 72 72 572 66 66 573 117 117 574 116 116 575 66 66 576 93 93 577 117 117 578 81 81 579 102 102 580 118 118 581 81 81 582 118 118 583 89 89 584 75 75 585 119 119 586 92 92 587 75 75 588 120 120 589 119 119 590 75 75 591 105 105 592 120 120 593 67 67 594 121 121 595 108 108 596 67 67 597 79 79 598 121 121 599 89 89 600 118 118 601 115 115 602 83 83 603 100 100 604 122 122 605 83 83 606 122 122 607 104 104 608 95 95 609 101 101 610 96 96 611 93 93 612 92 92 613 117 117 614 94 94 615 123 123 616 103 103 617 94 94 618 106 106 619 123 123 620 108 108 621 124 124 622 125 125 623 108 108 624 121 121 625 124 124 626 108 108 627 125 125 628 86 86 629 84 84 630 126 126 631 127 127 632 84 84 633 127 127 634 128 128 635 84 84 636 128 128 637 112 112 638 84 84 639 86 86 640 126 126 641 79 79 642 115 115 643 129 129 644 79 79 645 129 129 646 130 130 647 79 79 648 130 130 649 121 121 650 70 70 651 109 109 652 131 131 653 70 70 654 132 132 655 133 133 656 70 70 657 133 133 658 114 114 659 70 70 660 131 131 661 132 132 662 73 73 663 134 134 664 110 110 665 73 73 666 72 72 667 134 134 668 72 72 669 116 116 670 134 134 671 77 77 672 113 113 673 135 135 674 77 77 675 135 135 676 99 99 677 92 92 678 119 119 679 117 117 680 100 100 681 99 99 682 136 136 683 100 100 684 136 136 685 122 122 686 86 86 687 125 125 688 126 126 689 104 104 690 122 122 691 137 137 692 104 104 693 137 137 694 105 105 695 96 96 696 101 101 697 138 138 698 96 96 699 138 138 700 139 139 701 96 96 702 139 139 703 97 97 704 87 87 705 111 111 706 109 109 707 91 91 708 90 90 709 140 140 710 91 91 711 140 140 712 98 98 713 121 121 714 130 130 715 141 141 716 121 121 717 141 141 718 124 124 719 105 105 720 137 137 721 142 142 722 105 105 723 143 143 724 120 120 725 105 105 726 142 142 727 143 143 728 97 97 729 144 144 730 107 107 731 97 97 732 145 145 733 146 146 734 97 97 735 146 146 736 144 144 737 97 97 738 139 139 739 145 145 740 109 109 741 147 147 742 131 131 743 109 109 744 111 111 745 147 147 746 98 98 747 140 140 748 148 148 749 98 98 750 148 148 751 101 101 752 125 125 753 149 149 754 150 150 755 125 125 756 150 150 757 151 151 758 125 125 759 151 151 760 126 126 761 125 125 762 124 124 763 149 149 764 124 124 765 141 141 766 149 149 767 112 112 768 128 128 769 113 113 770 111 111 771 152 152 772 147 147 773 111 111 774 110 110 775 152 152 776 114 114 777 133 133 778 153 153 779 114 114 780 153 153 781 90 90 782 115 115 783 154 154 784 155 155 785 115 115 786 118 118 787 154 154 788 115 115 789 155 155 790 129 129 791 99 99 792 135 135 793 156 156 794 99 99 795 156 156 796 136 136 797 106 106 798 157 157 799 123 123 800 106 106 801 107 107 802 157 157 803 126 126 804 151 151 805 158 158 806 126 126 807 158 158 808 127 127 809 110 110 810 134 134 811 159 159 812 110 110 813 159 159 814 152 152 815 113 113 816 160 160 817 135 135 818 113 113 819 128 128 820 160 160 821 90 90 822 161 161 823 162 162 824 90 90 825 153 153 826 161 161 827 90 90 828 162 162 829 140 140 830 137 137 831 122 122 832 163 163 833 137 137 834 164 164 835 142 142 836 137 137 837 163 163 838 164 164 839 116 116 840 117 117 841 165 165 842 116 116 843 166 166 844 134 134 845 116 116 846 165 165 847 166 166 848 117 117 849 119 119 850 167 167 851 117 117 852 167 167 853 165 165 854 102 102 855 154 154 856 118 118 857 102 102 858 168 168 859 169 169 860 102 102 861 169 169 862 154 154 863 102 102 864 103 103 865 168 168 866 122 122 867 136 136 868 170 170 869 122 122 870 170 170 871 163 163 872 119 119 873 120 120 874 171 171 875 119 119 876 171 171 877 167 167 878 127 127 879 172 172 880 173 173 881 127 127 882 158 158 883 172 172 884 127 127 885 173 173 886 128 128 887 130 130 888 129 129 889 174 174 890 130 130 891 175 175 892 141 141 893 130 130 894 174 174 895 175 175 896 129 129 897 155 155 898 174 174 899 139 139 900 138 138 901 176 176 902 139 139 903 176 176 904 145 145 905 128 128 906 173 173 907 160 160 908 103 103 909 123 123 910 168 168 911 138 138 912 177 177 913 176 176 914 138 138 915 178 178 916 177 177 917 138 138 918 101 101 919 178 178 920 120 120 921 143 143 922 179 179 923 120 120 924 179 179 925 171 171 926 141 141 927 175 175 928 149 149 929 134 134 930 166 166 931 159 159 932 135 135 933 180 180 934 156 156 935 135 135 936 160 160 937 181 181 938 135 135 939 181 181 940 180 180 941 101 101 942 148 148 943 178 178 944 140 140 945 182 182 946 148 148 947 140 140 948 162 162 949 182 182 950 136 136 951 156 156 952 183 183 953 136 136 954 183 183 955 170 170 956 163 163 957 184 184 958 164 164 959 163 163 960 170 170 961 184 184 962 123 123 963 185 185 964 168 168 965 123 123 966 157 157 967 185 185 968 151 151 969 150 150 970 186 186 971 151 151 972 186 186 973 187 187 974 151 151 975 187 187 976 158 158 977 153 153 978 188 188 979 161 161 980 153 153 981 133 133 982 188 188 983 144 144 984 189 189 985 107 107 986 144 144 987 190 190 988 189 189 989 144 144 990 146 146 991 190 190 992 150 150 993 191 191 994 186 186 995 150 150 996 149 149 997 191 191 998 149 149 999 192 192 1000 191 191 1001 149 149 1002 175 175 1003 192 192 1004 158 158 1005 193 193 1006 172 172 1007 158 158 1008 187 187 1009 194 194 1010 158 158 1011 194 194 1012 193 193 1013 131 131 1014 147 147 1015 195 195 1016 131 131 1017 195 195 1018 196 196 1019 131 131 1020 196 196 1021 132 132 1022 133 133 1023 132 132 1024 197 197 1025 133 133 1026 197 197 1027 188 188 1028 160 160 1029 173 173 1030 198 198 1031 160 160 1032 198 198 1033 181 181 1034 156 156 1035 180 180 1036 183 183 1037 171 171 1038 199 199 1039 167 167 1040 171 171 1041 179 179 1042 200 200 1043 171 171 1044 200 200 1045 199 199 1046 145 145 1047 201 201 1048 202 202 1049 145 145 1050 176 176 1051 201 201 1052 145 145 1053 202 202 1054 146 146 1055 174 174 1056 203 203 1057 204 204 1058 174 174 1059 155 155 1060 203 203 1061 174 174 1062 204 204 1063 175 175 1064 155 155 1065 154 154 1066 205 205 1067 155 155 1068 206 206 1069 203 203 1070 155 155 1071 205 205 1072 206 206 1073 180 180 1074 181 181 1075 207 207 1076 180 180 1077 208 208 1078 183 183 1079 180 180 1080 207 207 1081 208 208 1082 148 148 1083 182 182 1084 209 209 1085 148 148 1086 210 210 1087 178 178 1088 148 148 1089 209 209 1090 210 210 1091 143 143 1092 211 211 1093 179 179 1094 143 143 1095 212 212 1096 211 211 1097 143 143 1098 142 142 1099 212 212 1100 164 164 1101 213 213 1102 142 142 1103 164 164 1104 184 184 1105 214 214 1106 164 164 1107 214 214 1108 213 213 1109 142 142 1110 213 213 1111 215 215 1112 142 142 1113 215 215 1114 212 212 1115 107 107 1116 216 216 1117 157 157 1118 107 107 1119 189 189 1120 216 216 1121 147 147 1122 152 152 1123 217 217 1124 147 147 1125 217 217 1126 195 195 1127 181 181 1128 198 198 1129 207 207 1130 154 154 1131 169 169 1132 205 205 1133 165 165 1134 167 167 1135 218 218 1136 165 165 1137 218 218 1138 219 219 1139 165 165 1140 219 219 1141 166 166 1142 167 167 1143 220 220 1144 218 218 1145 167 167 1146 199 199 1147 220 220 1148 170 170 1149 183 183 1150 221 221 1151 170 170 1152 221 221 1153 222 222 1154 170 170 1155 222 222 1156 184 184 1157 178 178 1158 210 210 1159 177 177 1160 176 176 1161 177 177 1162 223 223 1163 176 176 1164 223 223 1165 201 201 1166 175 175 1167 224 224 1168 192 192 1169 175 175 1170 204 204 1171 224 224 1172 132 132 1173 196 196 1174 197 197 1175 177 177 1176 210 210 1177 225 225 1178 177 177 1179 225 225 1180 226 226 1181 177 177 1182 226 226 1183 223 223 1184 179 179 1185 211 211 1186 200 200 1187 146 146 1188 202 202 1189 227 227 1190 146 146 1191 228 228 1192 190 190 1193 146 146 1194 227 227 1195 228 228 1196 152 152 1197 159 159 1198 229 229 1199 152 152 1200 229 229 1201 230 230 1202 152 152 1203 230 230 1204 217 217 1205 186 186 1206 191 191 1207 231 231 1208 186 186 1209 232 232 1210 187 187 1211 186 186 1212 231 231 1213 232 232 1214 191 191 1215 233 233 1216 234 234 1217 191 191 1218 234 234 1219 231 231 1220 191 191 1221 192 192 1222 233 233 1223 172 172 1224 193 193 1225 173 173 1226 195 195 1227 217 217 1228 235 235 1229 195 195 1230 236 236 1231 196 196 1232 195 195 1233 235 235 1234 236 236 1235 173 173 1236 237 237 1237 198 198 1238 173 173 1239 238 238 1240 237 237 1241 173 173 1242 193 193 1243 238 238 1244 162 162 1245 239 239 1246 182 182 1247 162 162 1248 240 240 1249 239 239 1250 162 162 1251 161 161 1252 240 240 1253 168 168 1254 241 241 1255 169 169 1256 168 168 1257 185 185 1258 241 241 1259 192 192 1260 224 224 1261 233 233 1262 196 196 1263 236 236 1264 197 197 1265 188 188 1266 242 242 1267 243 243 1268 188 188 1269 197 197 1270 242 242 1271 188 188 1272 243 243 1273 161 161 1274 161 161 1275 243 243 1276 240 240 1277 193 193 1278 194 194 1279 238 238 1280 205 205 1281 169 169 1282 206 206 1283 184 184 1284 244 244 1285 214 214 1286 184 184 1287 222 222 1288 244 244 1289 202 202 1290 245 245 1291 227 227 1292 202 202 1293 201 201 1294 245 245 1295 187 187 1296 246 246 1297 247 247 1298 187 187 1299 247 247 1300 194 194 1301 187 187 1302 232 232 1303 246 246 1304 204 204 1305 248 248 1306 224 224 1307 204 204 1308 249 249 1309 248 248 1310 204 204 1311 250 250 1312 249 249 1313 204 204 1314 203 203 1315 251 251 1316 204 204 1317 251 251 1318 250 250 1319 166 166 1320 229 229 1321 159 159 1322 166 166 1323 252 252 1324 229 229 1325 166 166 1326 219 219 1327 252 252 1328 182 182 1329 239 239 1330 209 209 1331 183 183 1332 208 208 1333 221 221 1334 157 157 1335 253 253 1336 185 185 1337 157 157 1338 254 254 1339 253 253 1340 157 157 1341 216 216 1342 254 254 1343 201 201 1344 223 223 1345 226 226 1346 201 201 1347 226 226 1348 255 255 1349 201 201 1350 255 255 1351 256 256 1352 201 201 1353 256 256 1354 245 245 1355 231 231 1356 234 234 1357 257 257 1358 231 231 1359 257 257 1360 232 232 1361 194 194 1362 258 258 1363 238 238 1364 194 194 1365 247 247 1366 258 258 1367 217 217 1368 259 259 1369 235 235 1370 217 217 1371 230 230 1372 259 259 1373 213 213 1374 214 214 1375 260 260 1376 213 213 1377 261 261 1378 215 215 1379 213 213 1380 260 260 1381 261 261 1382 169 169 1383 241 241 1384 262 262 1385 169 169 1386 262 262 1387 263 263 1388 169 169 1389 263 263 1390 206 206 1391 199 199 1392 264 264 1393 265 265 1394 199 199 1395 265 265 1396 220 220 1397 199 199 1398 200 200 1399 264 264 1400 210 210 1401 209 209 1402 225 225 1403 200 200 1404 211 211 1405 266 266 1406 200 200 1407 266 266 1408 264 264 1409 211 211 1410 267 267 1411 266 266 1412 211 211 1413 212 212 1414 267 267 1415 212 212 1416 268 268 1417 267 267 1418 212 212 1419 215 215 1420 268 268 1421 189 189 1422 190 190 1423 269 269 1424 189 189 1425 269 269 1426 216 216 1427 234 234 1428 233 233 1429 257 257 1430 236 236 1431 270 270 1432 242 242 1433 236 236 1434 271 271 1435 270 270 1436 236 236 1437 242 242 1438 197 197 1439 236 236 1440 235 235 1441 271 271 1442 229 229 1443 252 252 1444 230 230 1445 203 203 1446 206 206 1447 251 251 1448 207 207 1449 198 198 1450 272 272 1451 207 207 1452 272 272 1453 273 273 1454 207 207 1455 273 273 1456 208 208 1457 222 222 1458 221 221 1459 274 274 1460 222 222 1461 274 274 1462 244 244 1463 216 216 1464 269 269 1465 254 254 1466 232 232 1467 247 247 1468 246 246 1469 232 232 1470 275 275 1471 276 276 1472 232 232 1473 276 276 1474 247 247 1475 232 232 1476 277 277 1477 275 275 1478 232 232 1479 257 257 1480 277 277 1481 233 233 1482 224 224 1483 277 277 1484 233 233 1485 277 277 1486 257 257 1487 235 235 1488 259 259 1489 278 278 1490 235 235 1491 278 278 1492 271 271 1493 224 224 1494 248 248 1495 277 277 1496 198 198 1497 237 237 1498 279 279 1499 198 198 1500 279 279 1501 272 272 1502 218 218 1503 220 220 1504 219 219 1505 185 185 1506 253 253 1507 241 241 1508 227 227 1509 280 280 1510 228 228 1511 227 227 1512 245 245 1513 281 281 1514 227 227 1515 281 281 1516 280 280 1517 247 247 1518 276 276 1519 258 258 1520 238 238 1521 258 258 1522 282 282 1523 238 238 1524 282 282 1525 237 237 1526 206 206 1527 283 283 1528 251 251 1529 206 206 1530 263 263 1531 283 283 1532 208 208 1533 284 284 1534 221 221 1535 208 208 1536 273 273 1537 285 285 1538 208 208 1539 285 285 1540 284 284 1541 221 221 1542 284 284 1543 274 274 1544 241 241 1545 253 253 1546 262 262 1547 259 259 1548 286 286 1549 278 278 1550 259 259 1551 230 230 1552 287 287 1553 259 259 1554 287 287 1555 286 286 1556 271 271 1557 288 288 1558 270 270 1559 271 271 1560 278 278 1561 288 288 1562 277 277 1563 249 249 1564 275 275 1565 277 277 1566 248 248 1567 249 249 1568 230 230 1569 252 252 1570 287 287 1571 219 219 1572 289 289 1573 290 290 1574 219 219 1575 291 291 1576 252 252 1577 219 219 1578 290 290 1579 291 291 1580 219 219 1581 220 220 1582 289 289 1583 209 209 1584 292 292 1585 293 293 1586 209 209 1587 239 239 1588 294 294 1589 209 209 1590 294 294 1591 292 292 1592 209 209 1593 293 293 1594 225 225 1595 220 220 1596 265 265 1597 289 289 1598 253 253 1599 254 254 1600 295 295 1601 253 253 1602 296 296 1603 262 262 1604 253 253 1605 295 295 1606 296 296 1607 214 214 1608 244 244 1609 297 297 1610 214 214 1611 297 297 1612 298 298 1613 214 214 1614 298 298 1615 260 260 1616 267 267 1617 268 268 1618 299 299 1619 267 267 1620 299 299 1621 300 300 1622 267 267 1623 300 300 1624 266 266 1625 245 245 1626 301 301 1627 281 281 1628 245 245 1629 256 256 1630 301 301 1631 242 242 1632 302 302 1633 243 243 1634 242 242 1635 270 270 1636 302 302 1637 258 258 1638 276 276 1639 303 303 1640 258 258 1641 303 303 1642 304 304 1643 258 258 1644 304 304 1645 282 282 1646 270 270 1647 288 288 1648 302 302 1649 272 272 1650 305 305 1651 273 273 1652 272 272 1653 279 279 1654 306 306 1655 272 272 1656 306 306 1657 305 305 1658 252 252 1659 291 291 1660 287 287 1661 226 226 1662 225 225 1663 307 307 1664 226 226 1665 307 307 1666 255 255 1667 266 266 1668 308 308 1669 264 264 1670 266 266 1671 300 300 1672 308 308 1673 260 260 1674 309 309 1675 261 261 1676 260 260 1677 298 298 1678 309 309 1679 215 215 1680 310 310 1681 311 311 1682 215 215 1683 311 311 1684 268 268 1685 215 215 1686 261 261 1687 310 310 1688 269 269 1689 312 312 1690 313 313 1691 269 269 1692 190 190 1693 312 312 1694 269 269 1695 313 313 1696 314 314 1697 269 269 1698 314 314 1699 254 254 1700 190 190 1701 315 315 1702 312 312 1703 190 190 1704 228 228 1705 315 315 1706 282 282 1707 316 316 1708 237 237 1709 282 282 1710 304 304 1711 316 316 1712 237 237 1713 316 316 1714 304 304 1715 237 237 1716 304 304 1717 279 279 1718 279 279 1719 304 304 1720 306 306 1721 251 251 1722 317 317 1723 250 250 1724 251 251 1725 283 283 1726 317 317 1727 225 225 1728 293 293 1729 307 307 1730 244 244 1731 274 274 1732 297 297 1733 278 278 1734 286 286 1735 318 318 1736 278 278 1737 318 318 1738 288 288 1739 243 243 1740 302 302 1741 319 319 1742 243 243 1743 320 320 1744 240 240 1745 243 243 1746 319 319 1747 320 320 1748 239 239 1749 240 240 1750 321 321 1751 239 239 1752 321 321 1753 322 322 1754 239 239 1755 322 322 1756 320 320 1757 239 239 1758 320 320 1759 323 323 1760 239 239 1761 323 323 1762 294 294 1763 254 254 1764 324 324 1765 295 295 1766 254 254 1767 325 325 1768 324 324 1769 254 254 1770 314 314 1771 325 325 1772 268 268 1773 311 311 1774 326 326 1775 268 268 1776 326 326 1777 299 299 1778 281 281 1779 327 327 1780 280 280 1781 281 281 1782 301 301 1783 327 327 1784 240 240 1785 320 320 1786 321 321 1787 288 288 1788 318 318 1789 328 328 1790 288 288 1791 328 328 1792 329 329 1793 288 288 1794 329 329 1795 302 302 1796 302 302 1797 330 330 1798 319 319 1799 302 302 1800 329 329 1801 330 330 1802 273 273 1803 305 305 1804 285 285 1805 274 274 1806 331 331 1807 332 332 1808 274 274 1809 284 284 1810 331 331 1811 274 274 1812 332 332 1813 297 297 1814 261 261 1815 333 333 1816 310 310 1817 261 261 1818 309 309 1819 333 333 1820 228 228 1821 334 334 1822 315 315 1823 228 228 1824 335 335 1825 334 334 1826 228 228 1827 280 280 1828 335 335 1829 318 318 1830 336 336 1831 328 328 1832 318 318 1833 286 286 1834 336 336 1835 286 286 1836 337 337 1837 336 336 1838 286 286 1839 287 287 1840 337 337 1841 249 249 1842 250 250 1843 338 338 1844 249 249 1845 338 338 1846 275 275 1847 283 283 1848 263 263 1849 339 339 1850 283 283 1851 340 340 1852 317 317 1853 283 283 1854 341 341 1855 340 340 1856 283 283 1857 339 339 1858 341 341 1859 284 284 1860 285 285 1861 342 342 1862 284 284 1863 342 342 1864 331 331 1865 264 264 1866 308 308 1867 343 343 1868 264 264 1869 343 343 1870 265 265 1871 255 255 1872 307 307 1873 344 344 1874 255 255 1875 344 344 1876 256 256 1877 256 256 1878 344 344 1879 345 345 1880 256 256 1881 346 346 1882 301 301 1883 256 256 1884 345 345 1885 346 346 1886 280 280 1887 327 327 1888 347 347 1889 280 280 1890 347 347 1891 335 335 1892 287 287 1893 291 291 1894 337 337 1895 320 320 1896 319 319 1897 323 323 1898 320 320 1899 322 322 1900 321 321 1901 291 291 1902 290 290 1903 337 337 1904 262 262 1905 296 296 1906 348 348 1907 262 262 1908 348 348 1909 263 263 1910 304 304 1911 303 303 1912 306 306 1913 329 329 1914 328 328 1915 349 349 1916 329 329 1917 350 350 1918 330 330 1919 329 329 1920 349 349 1921 350 350 1922 263 263 1923 348 348 1924 339 339 1925 295 295 1926 324 324 1927 296 296 1928 297 297 1929 351 351 1930 298 298 1931 297 297 1932 332 332 1933 352 352 1934 297 297 1935 352 352 1936 351 351 1937 301 301 1938 346 346 1939 327 327 1940 312 312 1941 315 315 1942 353 353 1943 312 312 1944 354 354 1945 313 313 1946 312 312 1947 353 353 1948 354 354 1949 328 328 1950 336 336 1951 355 355 1952 328 328 1953 356 356 1954 349 349 1955 328 328 1956 355 355 1957 356 356 1958 319 319 1959 330 330 1960 323 323 1961 250 250 1962 317 317 1963 338 338 1964 294 294 1965 357 357 1966 292 292 1967 294 294 1968 323 323 1969 357 357 1970 265 265 1971 343 343 1972 358 358 1973 265 265 1974 358 358 1975 289 289 1976 307 307 1977 293 293 1978 344 344 1979 300 300 1980 299 299 1981 359 359 1982 300 300 1983 359 359 1984 360 360 1985 300 300 1986 360 360 1987 308 308 1988 298 298 1989 361 361 1990 309 309 1991 298 298 1992 351 351 1993 361 361 1994 299 299 1995 326 326 1996 359 359 1997 336 336 1998 362 362 1999 363 363 2000 336 336 2001 337 337 2002 362 362 2003 336 336 2004 363 363 2005 355 355 2006 330 330 2007 350 350 2008 364 364 2009 330 330 2010 364 364 2011 365 365 2012 330 330 2013 365 365 2014 323 323 2015 306 306 2016 366 366 2017 367 367 2018 306 306 2019 368 368 2020 366 366 2021 306 306 2022 367 367 2023 305 305 2024 306 306 2025 369 369 2026 368 368 2027 306 306 2028 303 303 2029 369 369 2030 285 285 2031 305 305 2032 370 370 2033 285 285 2034 370 370 2035 342 342 2036 289 289 2037 358 358 2038 290 290 2039 331 331 2040 371 371 2041 332 332 2042 331 331 2043 342 342 2044 372 372 2045 331 331 2046 372 372 2047 371 371 2048 309 309 2049 373 373 2050 333 333 2051 309 309 2052 361 361 2053 373 373 2054 313 313 2055 354 354 2056 374 374 2057 313 313 2058 374 374 2059 314 314 2060 337 337 2061 290 290 2062 362 362 2063 317 317 2064 340 340 2065 338 338 2066 290 290 2067 375 375 2068 362 362 2069 290 290 2070 358 358 2071 375 375 2072 293 293 2073 292 292 2074 376 376 2075 293 293 2076 376 376 2077 344 344 2078 308 308 2079 377 377 2080 343 343 2081 308 308 2082 378 378 2083 377 377 2084 308 308 2085 360 360 2086 378 378 2087 314 314 2088 379 379 2089 325 325 2090 314 314 2091 374 374 2092 379 379 2093 315 315 2094 334 334 2095 353 353 2096 305 305 2097 367 367 2098 370 370 2099 339 339 2100 348 348 2101 380 380 2102 339 339 2103 380 380 2104 341 341 2105 292 292 2106 381 381 2107 376 376 2108 292 292 2109 357 357 2110 381 381 2111 348 348 2112 296 296 2113 380 380 2114 332 332 2115 371 371 2116 382 382 2117 332 332 2118 382 382 2119 352 352 2120 324 324 2121 325 325 2122 383 383 2123 324 324 2124 383 383 2125 296 296 2126 351 351 2127 352 352 2128 384 384 2129 351 351 2130 384 384 2131 385 385 2132 351 351 2133 385 385 2134 361 361 2135 311 311 2136 386 386 2137 387 387 2138 311 311 2139 387 387 2140 326 326 2141 311 311 2142 310 310 2143 386 386 2144 327 327 2145 346 346 2146 388 388 2147 327 327 2148 388 388 2149 347 347 2150 323 323 2151 365 365 2152 357 357 2153 296 296 2154 383 383 2155 389 389 2156 296 296 2157 389 389 2158 380 380 2159 326 326 2160 390 390 2161 359 359 2162 326 326 2163 387 387 2164 390 390 2165 347 347 2166 391 391 2167 335 335 2168 347 347 2169 388 388 2170 392 392 2171 347 347 2172 392 392 2173 391 391 2174 353 353 2175 334 334 2176 393 393 2177 353 353 2178 393 393 2179 394 394 2180 353 353 2181 394 394 2182 354 354 2183 335 335 2184 395 395 2185 396 396 2186 335 335 2187 396 396 2188 334 334 2189 335 335 2190 391 391 2191 397 397 2192 335 335 2193 397 397 2194 395 395 2195 355 355 2196 363 363 2197 398 398 2198 355 355 2199 398 398 2200 356 356 2201 350 350 2202 399 399 2203 364 364 2204 350 350 2205 349 349 2206 399 399 2207 343 343 2208 400 400 2209 401 401 2210 343 343 2211 377 377 2212 400 400 2213 343 343 2214 401 401 2215 358 358 2216 344 344 2217 402 402 2218 345 345 2219 344 344 2220 376 376 2221 403 403 2222 344 344 2223 403 403 2224 402 402 2225 325 325 2226 379 379 2227 404 404 2228 325 325 2229 404 404 2230 383 383 2231 359 359 2232 390 390 2233 360 360 2234 334 334 2235 396 396 2236 393 393 2237 340 340 2238 341 341 2239 405 405 2240 340 340 2241 405 405 2242 338 338 2243 374 374 2244 354 354 2245 406 406 2246 374 374 2247 406 406 2248 379 379 2249 361 361 2250 407 407 2251 373 373 2252 361 361 2253 385 385 2254 407 407 2255 338 338 2256 408 408 2257 409 409 2258 338 338 2259 405 405 2260 408 408 2261 338 338 2262 409 409 2263 275 275 2264 310 310 2265 333 333 2266 410 410 2267 310 310 2268 410 410 2269 386 386 2270 358 358 2271 401 401 2272 375 375 2273 357 357 2274 411 411 2275 381 381 2276 357 357 2277 365 365 2278 411 411 2279 342 342 2280 412 412 2281 372 372 2282 342 342 2283 413 413 2284 414 414 2285 342 342 2286 370 370 2287 413 413 2288 342 342 2289 414 414 2290 412 412 2291 352 352 2292 382 382 2293 415 415 2294 352 352 2295 415 415 2296 384 384 2297 346 346 2298 416 416 2299 417 417 2300 346 346 2301 345 345 2302 416 416 2303 346 346 2304 417 417 2305 388 388 2306 373 373 2307 407 407 2308 418 418 2309 373 373 2310 418 418 2311 333 333 2312 333 333 2313 418 418 2314 410 410 2315 349 349 2316 356 356 2317 419 419 2318 349 349 2319 419 419 2320 420 420 2321 349 349 2322 420 420 2323 399 399 2324 370 370 2325 367 367 2326 413 413 2327 341 341 2328 421 421 2329 405 405 2330 341 341 2331 422 422 2332 421 421 2333 341 341 2334 380 380 2335 422 422 2336 379 379 2337 406 406 2338 404 404 2339 354 354 2340 394 394 2341 406 406 2342 396 396 2343 395 395 2344 423 423 2345 396 396 2346 423 423 2347 393 393 2348 362 362 2349 375 375 2350 424 424 2351 362 362 2352 424 424 2353 363 363 2354 367 367 2355 366 366 2356 413 413 2357 364 364 2358 425 425 2359 365 365 2360 364 364 2361 399 399 2362 426 426 2363 364 364 2364 426 426 2365 425 425 2366 371 371 2367 427 427 2368 382 382 2369 371 371 2370 372 372 2371 427 427 2372 377 377 2373 378 378 2374 400 400 2375 345 345 2376 402 402 2377 416 416 2378 390 390 2379 428 428 2380 429 429 2381 390 390 2382 429 429 2383 360 360 2384 390 390 2385 387 387 2386 428 428 2387 388 388 2388 430 430 2389 392 392 2390 388 388 2391 417 417 2392 430 430 2393 386 386 2394 431 431 2395 432 432 2396 386 386 2397 432 432 2398 387 387 2399 386 386 2400 433 433 2401 431 431 2402 386 386 2403 410 410 2404 433 433 2405 356 356 2406 398 398 2407 419 419 2408 405 405 2409 421 421 2410 408 408 2411 372 372 2412 412 412 2413 434 434 2414 372 372 2415 434 434 2416 427 427 2417 380 380 2418 389 389 2419 422 422 2420 360 360 2421 435 435 2422 378 378 2423 360 360 2424 429 429 2425 435 435 2426 387 387 2427 432 432 2428 436 436 2429 387 387 2430 436 436 2431 428 428 2432 394 394 2433 437 437 2434 406 406 2435 394 394 2436 393 393 2437 438 438 2438 394 394 2439 438 438 2440 437 437 2441 410 410 2442 439 439 2443 440 440 2444 410 410 2445 440 440 2446 433 433 2447 410 410 2448 418 418 2449 439 439 2450 393 393 2451 423 423 2452 438 438 2453 381 381 2454 411 411 2455 441 441 2456 381 381 2457 441 441 2458 376 376 2459 402 402 2460 403 403 2461 442 442 2462 402 402 2463 442 442 2464 416 416 2465 383 383 2466 443 443 2467 444 444 2468 383 383 2469 444 444 2470 389 389 2471 383 383 2472 404 404 2473 443 443 2474 404 404 2475 406 406 2476 445 445 2477 404 404 2478 445 445 2479 443 443 2480 407 407 2481 446 446 2482 418 418 2483 407 407 2484 447 447 2485 446 446 2486 407 407 2487 385 385 2488 447 447 2489 395 395 2490 448 448 2491 423 423 2492 395 395 2493 397 397 2494 449 449 2495 395 395 2496 449 449 2497 448 448 2498 391 391 2499 450 450 2500 397 397 2501 391 391 2502 451 451 2503 450 450 2504 391 391 2505 392 392 2506 451 451 2507 366 366 2508 368 368 2509 413 413 2510 375 375 2511 401 401 2512 424 424 2513 382 382 2514 427 427 2515 415 415 2516 384 384 2517 452 452 2518 453 453 2519 384 384 2520 453 453 2521 385 385 2522 384 384 2523 415 415 2524 452 452 2525 385 385 2526 453 453 2527 447 447 2528 431 431 2529 454 454 2530 455 455 2531 431 431 2532 455 455 2533 456 456 2534 431 431 2535 433 433 2536 454 454 2537 431 431 2538 456 456 2539 432 432 2540 397 397 2541 450 450 2542 457 457 2543 397 397 2544 457 457 2545 449 449 2546 399 399 2547 420 420 2548 426 426 2549 365 365 2550 425 425 2551 411 411 2552 401 401 2553 400 400 2554 424 424 2555 376 376 2556 441 441 2557 403 403 2558 427 427 2559 458 458 2560 415 415 2561 427 427 2562 434 434 2563 458 458 2564 406 406 2565 437 437 2566 445 445 2567 392 392 2568 430 430 2569 451 451 2570 418 418 2571 446 446 2572 439 439 2573 423 423 2574 448 448 2575 438 438 2576 432 432 2577 456 456 2578 459 459 2579 432 432 2580 459 459 2581 436 436 2582 433 433 2583 440 440 2584 454 454 2585 450 450 2586 451 451 2587 460 460 2588 450 450 2589 460 460 2590 461 461 2591 450 450 2592 461 461 2593 457 457 2594 363 363 2595 462 462 2596 398 398 2597 363 363 2598 424 424 2599 462 462 2600 428 428 2601 436 436 2602 463 463 2603 428 428 2604 463 463 2605 429 429 2606 411 411 2607 425 425 2608 441 441 2609 378 378 2610 435 435 2611 464 464 2612 378 378 2613 464 464 2614 400 400 2615 455 455 2616 465 465 2617 466 466 2618 455 455 2619 454 454 2620 465 465 2621 455 455 2622 466 466 2623 456 456 2624 451 451 2625 430 430 2626 467 467 2627 451 451 2628 467 467 2629 460 460 2630 439 439 2631 468 468 2632 469 469 2633 439 439 2634 446 446 2635 468 468 2636 439 439 2637 469 469 2638 440 440 2639 454 454 2640 440 440 2641 470 470 2642 454 454 2643 470 470 2644 465 465 2645 413 413 2646 368 368 2647 414 414 2648 471 471 2649 421 421 2650 472 472 2651 421 421 2652 473 473 2653 472 472 2654 421 421 2655 471 471 2656 408 408 2657 421 421 2658 422 422 2659 474 474 2660 421 421 2661 474 474 2662 473 473 2663 400 400 2664 464 464 2665 424 424 2666 422 422 2667 389 389 2668 475 475 2669 422 422 2670 475 475 2671 474 474 2672 429 429 2673 476 476 2674 435 435 2675 429 429 2676 463 463 2677 476 476 2678 448 448 2679 449 449 2680 477 477 2681 448 448 2682 478 478 2683 438 438 2684 448 448 2685 477 477 2686 478 478 2687 449 449 2688 457 457 2689 479 479 2690 449 449 2691 479 479 2692 480 480 2693 449 449 2694 480 480 2695 477 477 2696 447 447 2697 481 481 2698 446 446 2699 447 447 2700 453 453 2701 481 481 2702 446 446 2703 481 481 2704 468 468 2705 456 456 2706 482 482 2707 459 459 2708 456 456 2709 466 466 2710 482 482 2711 457 457 2712 483 483 2713 479 479 2714 457 457 2715 461 461 2716 484 484 2717 457 457 2718 484 484 2719 483 483 2720 403 403 2721 485 485 2722 442 442 2723 403 403 2724 486 486 2725 485 485 2726 403 403 2727 441 441 2728 486 486 2729 389 389 2730 487 487 2731 475 475 2732 389 389 2733 444 444 2734 487 487 2735 453 453 2736 452 452 2737 488 488 2738 453 453 2739 488 488 2740 481 481 2741 430 430 2742 489 489 2743 467 467 2744 430 430 2745 417 417 2746 489 489 2747 438 438 2748 478 478 2749 437 437 2750 440 440 2751 490 490 2752 470 470 2753 440 440 2754 469 469 2755 490 490 2756 483 483 2757 465 465 2758 479 479 2759 483 483 2760 484 484 2761 465 465 2762 477 477 2763 491 491 2764 478 478 2765 477 477 2766 480 480 2767 491 491 2768 424 424 2769 464 464 2770 462 462 2771 414 414 2772 492 492 2773 493 493 2774 414 414 2775 493 493 2776 412 412 2777 414 414 2778 368 368 2779 492 492 2780 412 412 2781 494 494 2782 458 458 2783 412 412 2784 458 458 2785 434 434 2786 412 412 2787 493 493 2788 494 494 2789 415 415 2790 495 495 2791 452 452 2792 415 415 2793 458 458 2794 495 495 2795 435 435 2796 496 496 2797 464 464 2798 435 435 2799 476 476 2800 496 496 2801 416 416 2802 497 497 2803 417 417 2804 416 416 2805 442 442 2806 497 497 2807 437 437 2808 498 498 2809 445 445 2810 437 437 2811 478 478 2812 498 498 2813 460 460 2814 467 467 2815 499 499 2816 460 460 2817 499 499 2818 461 461 2819 466 466 2820 500 500 2821 501 501 2822 466 466 2823 501 501 2824 482 482 2825 466 466 2826 465 465 2827 500 500 2828 465 465 2829 470 470 2830 479 479 2831 465 465 2832 484 484 2833 500 500 2834 479 479 2835 470 470 2836 480 480 2837 368 368 2838 369 369 2839 492 492 2840 398 398 2841 502 502 2842 503 503 2843 398 398 2844 462 462 2845 502 502 2846 398 398 2847 503 503 2848 419 419 2849 419 419 2850 504 504 2851 420 420 2852 419 419 2853 503 503 2854 504 504 2855 441 441 2856 425 425 2857 486 486 2858 443 443 2859 505 505 2860 444 444 2861 443 443 2862 506 506 2863 505 505 2864 443 443 2865 445 445 2866 506 506 2867 452 452 2868 507 507 2869 488 488 2870 452 452 2871 495 495 2872 507 507 2873 470 470 2874 490 490 2875 508 508 2876 470 470 2877 508 508 2878 480 480 2879 445 445 2880 498 498 2881 506 506 2882 467 467 2883 509 509 2884 499 499 2885 467 467 2886 489 489 2887 509 509 2888 481 481 2889 510 510 2890 468 468 2891 481 481 2892 488 488 2893 510 510 2894 459 459 2895 463 463 2896 436 436 2897 459 459 2898 511 511 2899 463 463 2900 459 459 2901 482 482 2902 511 511 2903 425 425 2904 512 512 2905 486 486 2906 425 425 2907 426 426 2908 512 512 2909 417 417 2910 497 497 2911 489 489 2912 463 463 2913 511 511 2914 513 513 2915 463 463 2916 513 513 2917 476 476 2918 461 461 2919 514 514 2920 484 484 2921 461 461 2922 499 499 2923 514 514 2924 484 484 2925 514 514 2926 500 500 2927 490 490 2928 469 469 2929 515 515 2930 490 490 2931 515 515 2932 508 508 2933 480 480 2934 516 516 2935 491 491 2936 480 480 2937 508 508 2938 516 516 2939 458 458 2940 517 517 2941 518 518 2942 458 458 2943 494 494 2944 517 517 2945 458 458 2946 518 518 2947 519 519 2948 458 458 2949 519 519 2950 495 495 2951 444 444 2952 520 520 2953 487 487 2954 444 444 2955 505 505 2956 520 520 2957 495 495 2958 519 519 2959 507 507 2960 489 489 2961 521 521 2962 509 509 2963 489 489 2964 497 497 2965 521 521 2966 468 468 2967 510 510 2968 522 522 2969 468 468 2970 522 522 2971 469 469 2972 482 482 2973 501 501 2974 523 523 2975 482 482 2976 523 523 2977 511 511 2978 478 478 2979 524 524 2980 525 525 2981 478 478 2982 525 525 2983 498 498 2984 478 478 2985 491 491 2986 524 524 2987 469 469 2988 522 522 2989 515 515 2990 500 500 2991 526 526 2992 501 501 2993 500 500 2994 514 514 2995 526 526 2996 508 508 2997 515 515 2998 516 516 2999 462 462 3000 527 527 3001 502 502 3002 462 462 3003 464 464 3004 527 527 3005 474 474 3006 528 528 3007 473 473 3008 474 474 3009 475 475 3010 528 528 3011 442 442 3012 485 485 3013 497 497 3014 499 499 3015 509 509 3016 529 529 3017 499 499 3018 529 529 3019 514 514 3020 501 501 3021 526 526 3022 523 523 3023 491 491 3024 530 530 3025 524 524 3026 491 491 3027 515 515 3028 530 530 3029 491 491 3030 516 516 3031 515 515 3032 472 472 3033 473 473 3034 471 471 3035 473 473 3036 408 408 3037 471 471 3038 473 473 3039 409 409 3040 408 408 3041 473 473 3042 528 528 3043 409 409 3044 485 485 3045 486 486 3046 531 531 3047 485 485 3048 531 531 3049 532 532 3050 485 485 3051 532 532 3052 533 533 3053 485 485 3054 533 533 3055 497 497 3056 476 476 3057 534 534 3058 496 496 3059 476 476 3060 513 513 3061 534 534 3062 487 487 3063 535 535 3064 536 536 3065 487 487 3066 536 536 3067 475 475 3068 487 487 3069 520 520 3070 535 535 3071 497 497 3072 537 537 3073 521 521 3074 497 497 3075 533 533 3076 537 537 3077 511 511 3078 523 523 3079 538 538 3080 511 511 3081 538 538 3082 513 513 3083 492 492 3084 539 539 3085 493 493 3086 492 492 3087 540 540 3088 539 539 3089 492 492 3090 369 369 3091 540 540 3092 475 475 3093 536 536 3094 528 528 3095 507 507 3096 519 519 3097 541 541 3098 507 507 3099 542 542 3100 488 488 3101 507 507 3102 541 541 3103 542 542 3104 505 505 3105 543 543 3106 520 520 3107 505 505 3108 506 506 3109 543 543 3110 498 498 3111 544 544 3112 506 506 3113 498 498 3114 525 525 3115 544 544 3116 510 510 3117 545 545 3118 546 546 3119 510 510 3120 546 546 3121 522 522 3122 510 510 3123 547 547 3124 545 545 3125 510 510 3126 488 488 3127 547 547 3128 523 523 3129 526 526 3130 548 548 3131 523 523 3132 548 548 3133 538 538 3134 514 514 3135 549 549 3136 526 526 3137 514 514 3138 529 529 3139 549 549 3140 515 515 3141 546 546 3142 530 530 3143 515 515 3144 522 522 3145 546 546 3146 420 420 3147 504 504 3148 426 426 3149 464 464 3150 550 550 3151 527 527 3152 464 464 3153 496 496 3154 550 550 3155 493 493 3156 539 539 3157 494 494 3158 488 488 3159 542 542 3160 547 547 3161 506 506 3162 551 551 3163 543 543 3164 506 506 3165 544 544 3166 551 551 3167 526 526 3168 549 549 3169 548 548 3170 486 486 3171 512 512 3172 531 531 3173 519 519 3174 518 518 3175 552 552 3176 519 519 3177 552 552 3178 541 541 3179 520 520 3180 543 543 3181 535 535 3182 513 513 3183 553 553 3184 534 534 3185 513 513 3186 538 538 3187 554 554 3188 513 513 3189 554 554 3190 553 553 3191 524 524 3192 555 555 3193 556 556 3194 524 524 3195 556 556 3196 525 525 3197 524 524 3198 530 530 3199 557 557 3200 524 524 3201 557 557 3202 555 555 3203 369 369 3204 303 303 3205 558 558 3206 369 369 3207 559 559 3208 540 540 3209 369 369 3210 560 560 3211 559 559 3212 369 369 3213 558 558 3214 560 560 3215 494 494 3216 561 561 3217 562 562 3218 494 494 3219 562 562 3220 517 517 3221 494 494 3222 539 539 3223 561 561 3224 496 496 3225 534 534 3226 550 550 3227 509 509 3228 521 521 3229 563 563 3230 509 509 3231 563 563 3232 564 564 3233 509 509 3234 564 564 3235 529 529 3236 525 525 3237 556 556 3238 544 544 3239 545 545 3240 565 565 3241 546 546 3242 545 545 3243 566 566 3244 565 565 3245 545 545 3246 542 542 3247 566 566 3248 545 545 3249 547 547 3250 542 542 3251 546 546 3252 565 565 3253 530 530 3254 530 530 3255 565 565 3256 557 557 3257 426 426 3258 504 504 3259 567 567 3260 426 426 3261 567 567 3262 512 512 3263 528 528 3264 536 536 3265 568 568 3266 528 528 3267 568 568 3268 569 569 3269 570 570 3270 528 528 3271 569 569 3272 528 528 3273 570 570 3274 409 409 3275 517 517 3276 552 552 3277 518 518 3278 517 517 3279 562 562 3280 552 552 3281 529 529 3282 564 564 3283 549 549 3284 548 548 3285 554 554 3286 538 538 3287 548 548 3288 549 549 3289 554 554 3290 549 549 3291 571 571 3292 554 554 3293 549 549 3294 564 564 3295 571 571 3296 539 539 3297 572 572 3298 561 561 3299 539 539 3300 540 540 3301 572 572 3302 536 536 3303 573 573 3304 568 568 3305 536 536 3306 535 535 3307 573 573 3308 535 535 3309 543 543 3310 551 551 3311 535 535 3312 551 551 3313 573 573 3314 534 534 3315 553 553 3316 550 550 3317 521 521 3318 537 537 3319 563 563 3320 544 544 3321 556 556 3322 574 574 3323 544 544 3324 574 574 3325 551 551 3326 565 565 3327 566 566 3328 557 557 3329 512 512 3330 567 567 3331 531 531 3332 533 533 3333 532 532 3334 537 537 3335 552 552 3336 575 575 3337 541 541 3338 552 552 3339 576 576 3340 575 575 3341 552 552 3342 562 562 3343 576 576 3344 541 541 3345 575 575 3346 577 577 3347 541 541 3348 577 577 3349 542 542 3350 542 542 3351 577 577 3352 566 566 3353 557 557 3354 566 566 3355 555 555 3356 527 527 3357 578 578 3358 502 502 3359 527 527 3360 550 550 3361 578 578 3362 502 502 3363 578 578 3364 503 503 3365 503 503 3366 579 579 3367 580 580 3368 503 503 3369 578 578 3370 579 579 3371 503 503 3372 580 580 3373 504 504 3374 556 556 3375 581 581 3376 574 574 3377 556 556 3378 555 555 3379 581 581 3380 555 555 3381 566 566 3382 581 581 3383 540 540 3384 559 559 3385 572 572 3386 550 550 3387 582 582 3388 578 578 3389 550 550 3390 553 553 3391 582 582 3392 531 531 3393 567 567 3394 532 532 3395 554 554 3396 571 571 3397 583 583 3398 554 554 3399 583 583 3400 553 553 3401 551 551 3402 584 584 3403 585 585 3404 551 551 3405 574 574 3406 584 584 3407 551 551 3408 585 585 3409 570 570 3410 551 551 3411 570 570 3412 573 573 3413 564 564 3414 586 586 3415 571 571 3416 564 564 3417 563 563 3418 586 586 3419 566 566 3420 587 587 3421 581 581 3422 566 566 3423 588 588 3424 587 587 3425 566 566 3426 577 577 3427 588 588 3428 504 504 3429 589 589 3430 567 567 3431 504 504 3432 580 580 3433 589 589 3434 562 562 3435 561 561 3436 590 590 3437 562 562 3438 590 590 3439 576 576 3440 575 575 3441 576 576 3442 577 577 3443 563 563 3444 591 591 3445 586 586 3446 563 563 3447 537 537 3448 591 591 3449 571 571 3450 586 586 3451 583 583 3452 561 561 3453 559 559 3454 590 590 3455 561 561 3456 572 572 3457 559 559 3458 568 568 3459 570 570 3460 569 569 3461 568 568 3462 573 573 3463 570 570 3464 532 532 3465 591 591 3466 537 537 3467 532 532 3468 567 567 3469 591 591 3470 577 577 3471 576 576 3472 588 588 3473 567 567 3474 589 589 3475 591 591 3476 553 553 3477 592 592 3478 582 582 3479 553 553 3480 583 583 3481 592 592 3482 576 576 3483 590 590 3484 588 588 3485 574 574 3486 581 581 3487 584 584 3488 581 581 3489 587 587 3490 584 584 3491 578 578 3492 582 582 3493 579 579 3494 582 582 3495 592 592 3496 579 579 3497 586 586 3498 593 593 3499 579 579 3500 586 586 3501 579 579 3502 583 583 3503 586 586 3504 591 591 3505 593 593 3506 588 588 3507 590 590 3508 594 594 3509 588 588 3510 594 594 3511 587 587 3512 591 591 3513 589 589 3514 593 593 3515 583 583 3516 579 579 3517 592 592 3518 584 584 3519 595 595 3520 585 585 3521 584 584 3522 587 587 3523 595 595 3524 587 587 3525 596 596 3526 595 595 3527 587 587 3528 594 594 3529 596 596 3530 590 590 3531 597 597 3532 594 594 3533 590 590 3534 559 559 3535 598 598 3536 590 590 3537 598 598 3538 597 597 3539 559 559 3540 560 560 3541 598 598 3542 589 589 3543 580 580 3544 593 593 3545 570 570 3546 599 599 3547 600 600 3548 570 570 3549 600 600 3550 409 409 3551 570 570 3552 585 585 3553 599 599 3554 579 579 3555 593 593 3556 580 580 3557 594 594 3558 597 597 3559 596 596 3560 585 585 3561 601 601 3562 599 599 3563 585 585 3564 595 595 3565 601 601 3566 596 596 3567 597 597 3568 560 560 3569 596 596 3570 560 560 3571 595 595 3572 595 595 3573 560 560 3574 601 601 3575 599 599 3576 601 601 3577 560 560 3578 599 599 3579 560 560 3580 600 600 3581 560 560 3582 558 558 3583 600 600 3584 560 560 3585 597 597 3586 598 598 3587 275 602 3588 409 602 3589 276 602 3590 276 603 3591 409 603 3592 600 603 3593 276 604 3594 600 604 3595 558 604 3596 276 605 3597 558 605 3598 303 605 3599

-
-
-
-
- - - - - 0.6858805 -0.3173701 0.6548619 7.481132 0.7276338 0.3124686 -0.6106656 -6.50764 -0.01081678 0.8953432 0.4452454 5.343665 0 0 0 1 - - - - -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 - - - - 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 - - - - - - - - - - - - 0.001 0 0 0 0 -1.62921e-10 -0.001 0 0 0.001 -1.62921e-10 0 0 0 0 1 - - - - - - -
diff --git a/cram_pr2/cram_pr2_pick_place_demo/src/demo.lisp b/cram_pr2/cram_pr2_pick_place_demo/src/demo.lisp deleted file mode 100644 index 78b4b13b0f..0000000000 --- a/cram_pr2/cram_pr2_pick_place_demo/src/demo.lisp +++ /dev/null @@ -1,306 +0,0 @@ -;;; -;;; Copyright (c) 2017, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software -;;; without specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :demo) - -(defparameter *object-cad-models* - '(;; (:cup . "cup_eco_orange") - ;; (:bowl . "edeka_red_bowl") - )) - -(defparameter *object-colors* - '((:spoon . "blue") - (:breakfast-cereal . "yellow") - (:milk . "blue"))) - -(defparameter *object-grasps* - '((:spoon . :top) - (:breakfast-cereal . :front) - (:milk . :front) - (:cup . :top) - (:bowl . :top))) - -(cpl:def-cram-function park-robot () - (cpl:with-failure-handling - ((cpl:plan-failure (e) - (declare (ignore e)) - (return))) - (cpl:par - (exe:perform - (desig:an action - (type positioning-arm) - (left-configuration park) - (right-configuration park))) - (let ((?pose (cl-transforms-stamped:make-pose-stamped - cram-tf:*fixed-frame* - 0.0 - (cl-transforms:make-identity-vector) - (cl-transforms:make-identity-rotation)))) - (exe:perform - (desig:an action - (type going) - (target (desig:a location - (pose ?pose)))))) - (exe:perform (desig:an action (type opening-gripper) (gripper (left right)))) - (exe:perform (desig:an action (type looking) (direction forward)))))) - -(defun initialize () - (sb-ext:gc :full t) - - ;;(when ccl::*is-logging-enabled* - ;; (setf ccl::*is-client-connected* nil) - ;; (ccl::connect-to-cloud-logger) - ;; (ccl::reset-logged-owl)) - - ;; (setf proj-reasoning::*projection-checks-enabled* t) - - (btr:detach-all-objects (btr:get-robot-object)) - (btr:detach-all-objects (btr:get-environment-object)) - (btr-utils:kill-all-objects) - (setf (btr:joint-state (btr:get-environment-object) - "sink_area_left_upper_drawer_main_joint") - 0.0 - (btr:joint-state (btr:get-environment-object) - "sink_area_left_middle_drawer_main_joint") - 0.0 - (btr:joint-state (btr:get-environment-object) - "iai_fridge_door_joint") - 0.0 - (btr:joint-state (btr:get-environment-object) - "oven_area_area_right_drawer_main_joint") - 0.0 - (btr:joint-state (btr:get-environment-object) - "sink_area_trash_drawer_main_joint") - 0) - (btr-belief::publish-environment-joint-state - (btr:joint-states (btr:get-environment-object))) - - (setf desig::*designators* (tg:make-weak-hash-table :weakness :key)) - - (coe:clear-belief) - - (btr:clear-costmap-vis-object) - - ;; (setf cram-robot-pose-guassian-costmap::*orientation-samples* 3) - ) - -(defun finalize () - ;; (setf proj-reasoning::*projection-reasoning-enabled* nil) - - ;;(when ccl::*is-logging-enabled* - ;; (ccl::export-log-to-owl "ease_milestone_2018.owl") - ;; (ccl::export-belief-state-to-owl "ease_milestone_2018_belief.owl")) - (sb-ext:gc :full t)) - - -(cpl:def-cram-function demo-random (&optional - (random t) - (list-of-objects '(:bowl :spoon :cup :milk :breakfast-cereal))) - - (initialize) - (when cram-projection:*projection-environment* - (spawn-objects-on-sink-counter :random random)) - - (park-robot) - - (let ((object-fetching-locations - `((:breakfast-cereal . ,(desig:a location - (on (desig:an object - (type counter-top) - (urdf-name sink-area-surface) - (owl-name "kitchen_sink_block_counter_top") - (part-of kitchen))) - (side left) - (side front) - (range 0.5))) - (:cup . ,(desig:a location - (side left) - (on (desig:an object - (type counter-top) - (urdf-name sink-area-surface) - (owl-name "kitchen_sink_block_counter_top") - (part-of kitchen))))) - (:bowl . ,(desig:a location - (on (desig:an object - (type counter-top) - (urdf-name sink-area-surface) - (owl-name "kitchen_sink_block_counter_top") - (part-of kitchen))) - (side left) - (side front) - (range-invert 0.5))) - (:spoon . ,(desig:a location - (in (desig:an object - (type drawer) - (urdf-name sink-area-left-upper-drawer-main) - (owl-name "drawer_sinkblock_upper_open") - (part-of kitchen))) - (side front))) - (:milk . ,(desig:a location - (side left) - (side front) - (range 0.5) - (on;; in - (desig:an object - (type counter-top) - (urdf-name sink-area-surface ;; iai-fridge-main - ) - (owl-name "kitchen_sink_block_counter_top" - ;; "drawer_fridge_upper_interior" - ) - (part-of kitchen))))))) - (object-placing-locations - (let ((?pose - (cl-transforms-stamped:make-pose-stamped - "map" - 0.0 - (cl-transforms:make-3d-vector -0.78 0.8 0.95) - (cl-transforms:make-quaternion 0 0 0.6 0.4)))) - `((:breakfast-cereal . ,(desig:a location - (pose ?pose) - ;; (left-of (an object (type bowl))) - ;; (far-from (an object (type bowl))) - ;; (for (an object (type breakfast-cereal))) - ;; (on (desig:an object - ;; (type counter-top) - ;; (urdf-name kitchen-island-surface) - ;; (owl-name "kitchen_island_counter_top") - ;; (part-of kitchen))) - ;; (side back) - )) - (:cup . ,(desig:a location - (right-of (an object (type bowl))) - (behind (an object (type bowl))) - (near (an object (type bowl))) - (for (an object (type cup))))) - (:bowl . ,(desig:a location - (on (desig:an object - (type counter-top) - (urdf-name kitchen-island-surface) - (owl-name "kitchen_island_counter_top") - (part-of kitchen))) - (context table-setting) - (for (an object (type bowl))) - (object-count 3) - (side back) - (side right) - (range-invert 0.5))) - (:spoon . ,(desig:a location - (right-of (an object (type bowl))) - (near (an object (type bowl))) - (for (an object (type spoon))) - (orientation support-aligned))) - (:milk . ,(desig:a location - (left-of (an object (type bowl))) - (far-from (an object (type bowl))) - (for (an object (type milk))))))))) - - ;; (an object - ;; (obj-part "drawer_sinkblock_upper_handle")) - - (dolist (?object-type list-of-objects) - (let* ((?fetching-location - (cdr (assoc ?object-type object-fetching-locations))) - (?delivering-location - (cdr (assoc ?object-type object-placing-locations))) - (?arm-to-use - (cdr (assoc ?object-type *object-grasping-arms*))) - (?cad-model - (cdr (assoc ?object-type *object-cad-models*))) - (?color - (cdr (assoc ?object-type *object-colors*))) - (?object-to-fetch - (desig:an object - (type ?object-type) - (location ?fetching-location) - (desig:when ?cad-model - (cad-model ?cad-model)) - (desig:when ?color - (color ?color))))) - - ;; (when (eq ?object-type :bowl) - ;; (cpl:with-failure-handling - ;; ((common-fail:high-level-failure (e) - ;; (roslisp:ros-warn (pp-plans demo) "Failure happened: ~a~%Skipping the search" e) - ;; (return))) - ;; (let ((?loc (cdr (assoc :breakfast-cereal object-fetching-locations)))) - ;; (exe:perform - ;; (desig:an action - ;; (type searching) - ;; (object (desig:an object (type breakfast-cereal))) - ;; (location ?loc)))))) - - (cpl:with-failure-handling - ((common-fail:high-level-failure (e) - (roslisp:ros-warn (pp-plans demo) "Failure happened: ~a~%Skipping..." e) - (return))) - (exe:perform - (desig:an action - (type transporting) - (object ?object-to-fetch) - (location ?fetching-location) - (target ?delivering-location) - (desig:when ?arm-to-use - (arms (?arm-to-use))))) - ;; (if (eq ?object-type :bowl) - ;; (exe:perform - ;; (desig:an action - ;; (type transporting) - ;; (object ?object-to-fetch) - ;; ;; (arm right) - ;; (location ?fetching-location) - ;; (target ?delivering-location))) - ;; (if (eq ?object-type :breakfast-cereal) - ;; (exe:perform - ;; (desig:an action - ;; (type transporting) - ;; (object ?object-to-fetch) - ;; ;; (arm right) - ;; (location ?fetching-location) - ;; (target ?delivering-location))) - ;; (exe:perform - ;; (desig:an action - ;; (type transporting) - ;; (object ?object-to-fetch) - ;; (desig:when ?arm-to-use - ;; (arm ?arm-to-use)) - ;; (location ?fetching-location) - ;; (target ?delivering-location))))) - ) - - ;; (setf proj-reasoning::*projection-reasoning-enabled* nil) - ))) - - ;; (setf proj-reasoning::*projection-reasoning-enabled* nil) - - (park-robot) - - (finalize) - - cpl:*current-path*) diff --git a/cram_pr2/cram_pr2_pick_place_demo/src/milestone-projection-demo.lisp b/cram_pr2/cram_pr2_pick_place_demo/src/milestone-projection-demo.lisp deleted file mode 100644 index 83bdf285dd..0000000000 --- a/cram_pr2/cram_pr2_pick_place_demo/src/milestone-projection-demo.lisp +++ /dev/null @@ -1,452 +0,0 @@ -;;; -;;; Copyright (c) 2017, Gayane Kazhoyan -;;; Amar Fayaz -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software -;;; without specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :demo) - -(defparameter *demo-object-spawning-poses* - '((:bowl . ((1.45 1.05 0.48) (0 0 0 1))) ; left-middle-drawer - (:cup . ((1.42 0.7 0.48) (0 0 0 1))) ; left-middle-drawer - (:spoon . ((1.43 0.9 0.74132) (0 0 0 1))) ;; left-upper-drawer - ;; So far only this orientation works - (:breakfast-cereal . ((1.412 1.490 1.2558) (0 0 -0.55557d0 0.83147d0))) - ;; ((:breakfast-cereal . ((1.398 1.490 1.2558) (0 0 0.7071 0.7071))) - ;; (:breakfast-cereal . ((1.1 1.49 1.25) (0 0 0.7071 0.7071))) - (:milk . ((1.45 -1.04 0.955) (0 0 0 1))))) - -(defparameter *object-attachment-links* - '((:breakfast-cereal . "oven_area_area_right_drawer_board_3_link") - ;; (:milk . "sink_area_left_middle_drawer_main") - (:cup . "sink_area_left_middle_drawer_main") - (:bowl . "sink_area_left_middle_drawer_main") - ;; (:cup . "sink_area_left_middle_drawer_main") - (:spoon . "sink_area_left_upper_drawer_main") - ;; (:spoon . "oven_area_area_middle_upper_drawer_main") - )) - -(defparameter *fetch-locations* - `((:bowl . ,(a location - (in (an object - (type drawer) - (urdf-name sink-area-left-middle-drawer-main) - (owl-name "drawer_sinkblock_middle_open") - (part-of kitchen))))) - (:cup . ,(a location - (in (an object - (type drawer) - (urdf-name sink-area-left-middle-drawer-main) - (owl-name "drawer_sinkblock_middle_open") - (part-of kitchen))))) - (:spoon . ,(desig:a location - (in (desig:an object - (type drawer) - (urdf-name sink-area-left-upper-drawer-main) - (owl-name "drawer_sinkblock_upper_open") - (part-of kitchen))) - (side front))) - (:breakfast-cereal . ,(a location - (in (an object - (type drawer) - (urdf-name oven-area-area-right-drawer-main) - (owl-name "drawer_oven_right_open") - (part-of kitchen) - (level topmost))) - ;; (side front) - )) - (:milk . ,(a location (in (an object - (type fridge) - (urdf-name iai-fridge-main) - (owl-name "drawer_fridge_upper_interior") - (part-of kitchen) - (level topmost))))))) - - -(defparameter *delivery-locations* - `((:bowl . ,(a location - (on (an object - (type counter-top) - (urdf-name kitchen-island-surface) - (part-of kitchen))) - (for (an object - (type bowl))) - (side back) - (context table-setting) - (object-count 3) - (range-invert 0.5) - (side right))) - (:cup . ,(a location - (left-of (an object (type bowl))) - (near (an object (type bowl))) - (for (an object (type cup))))) - (:spoon . ,(a location - (right-of (an object (type bowl))) - (near (an object (type bowl))) - (for (an object (type spoon))) - (orientation support-aligned))) - (:milk . ,(desig:a location - (left-of (an object (type bowl))) - (far-from (an object (type bowl))) - (for (an object (type milk))))) - (:breakfast-cereal . ,(a location - (on - (an object - (type counter-top) - (urdf-name kitchen-island-surface) - (part-of kitchen))) - (for (an object (type breakfast-cereal))) - (side back) - (orientation axis-aligned) - (side right))))) - - -(defparameter *delivery-poses* - `((:bowl . ((-0.8399440765380859d0 1.2002920786539713d0 0.8932199478149414d0) - (0.0 0.0 0.33465 0.94234))) - (:cup . ((-0.8908212025960287d0 1.4991984049479166d0 0.9027448018391927d0) - (0.0 0.0 0.33465 0.94234))) - (:spoon . ((-0.8409400304158529d0 1.38009208679199219d0 0.8673268000284831d0) - (0.0 0.0 1 0))) - (:milk . ((-0.8495257695515951d0 1.6991498311360678d0 0.9483174006144206d0) - (0.0 0.0 -0.9 0.7))) - (:breakfast-cereal . ((-0.8497650782267253d0 0.8972648620605469d0 0.9625186920166016d0) - (0 0 0 1))))) - -(defparameter *cleaning-deliver-poses* - `((:bowl . ((1.45 -0.4 1.0) (0 0 0 1))) - (:cup . ((1.45 -0.4 1.0) (0 0 0 1))) - (:spoon . ((1.45 -0.4 1.0) (0 0 0 1))) - (:milk . ((1.2 -0.5 0.8) (0 0 1 0))) - (:breakfast-cereal . ((1.15 -0.5 0.8) (0 0 1 0))))) - - - - -(defun attach-objects-to-the-world (object-type) - (when (assoc object-type *object-attachment-links*) - (btr:attach-object (btr:object btr:*current-bullet-world* :kitchen) - (btr:object btr:*current-bullet-world* - (intern (format nil "~a-1" object-type) :keyword)) - :link (cdr (assoc object-type *object-attachment-links*))))) - -(defun spawn-objects-on-fixed-spots (&key (spawning-poses *demo-object-spawning-poses*) - (object-types '(:breakfast-cereal :cup :bowl :spoon :milk))) - (btr-utils:kill-all-objects) - (btr:add-objects-to-mesh-list "cram_pr2_pick_place_demo") - (btr:detach-all-objects (btr:get-robot-object)) - ;; spawn objects at default poses - (let ((objects (mapcar (lambda (object-type) - (btr-utils:spawn-object - (intern (format nil "~a-1" object-type) :keyword) - object-type - :pose (cdr (assoc object-type spawning-poses)))) - object-types))) - ;; stabilize world - ;; (btr:simulate btr:*current-bullet-world* 100) - objects) - - (mapcar #'attach-objects-to-the-world object-types)) - - - -(defun setup-for-demo (object-list) - (initialize) - (when cram-projection:*projection-environment* - (spawn-objects-on-fixed-spots :object-types object-list :spawning-poses *delivery-poses*)) - ;; (park-robot) - ) - -;; Open the fridge manually - ;; Uncomment and include in `setup-for-demo' to get it working as long as the - ;; automatic opening of the fridge door when referring to container is still in work - ;; Can only be used with the milk situation right now, as keeping the fridge opened will block pr2 from - ;; accessing other drawers - - ;; (exe:perform - ;; (an action - ;; (type accessing) - ;; (arm right) - ;; (distance 1.4) - ;; (location - ;; (a location - ;; (in - ;; (an object - ;; (type container-revolute) - ;; ;; (urdf-name :iai_fridge_door) - ;; (urdf-name :iai_fridge_door_handle) - ;; (part-of kitchen)))))))) - -(defun projection-init () - (setf btr:*visibility-threshold* 0.7) - (setf cram-urdf-projection:*debug-short-sleep-duration* 0.5) - (setf cram-urdf-projection:*debug-long-sleep-duration* 1.0) - (setf cram-urdf-projection-reasoning::*projection-checks-enabled* t) - (spawn-objects-on-fixed-spots)) - -(defun perform-demo (&optional (object-list '(:milk))) - "Generic implementation, ideally this should work for all objects together. -Right now, only works with '(:milk) and '(:bowl :cup :spoon). There is a separate method -for :breakfast-cereal in the bottom. -To get this working with milk, all the code of accessing and sealing inside the transport plan has to be -commented out " - ;; (setup-for-demo object-list) - - (dolist (?object-type object-list) - (let* (;; (?deliver-location (cdr (assoc ?object-type *delivery-locations*))) - (?deliver-pose (cram-tf:ensure-pose-in-frame - (btr:ensure-pose - (cdr (assoc ?object-type *delivery-poses*))) - cram-tf:*fixed-frame*)) - (?deliver-location (a location (pose ?deliver-pose))) - (?fetch-location (cdr (assoc ?object-type *fetch-locations*))) - (?color (cdr (assoc ?object-type *object-colors*))) - (?grasp (cdr (assoc ?object-type *object-grasps*))) - (?object (an object - (type ?object-type) - (location ?fetch-location) - (desig:when ?color - (color ?color))))) - (exe:perform - (an action - (type transporting) - (object ?object) - (desig:when ?color - (color ?color)) - (grasps (:back :top :front)) - (arms (left right)) - ;; (desig:when ?grasp - ;; (grasp ?grasp)) - (location ?fetch-location) - (target ?deliver-location)))))) - -(defun cleaning-demo (&optional (object-list '(:milk))) - "Generic implementation, ideally this should work for all objects together. -Right now, only works with '(:milk) and '(:bowl :cup :spoon). There is a separate method -for :breakfast-cereal in the bottom. -To get this working with milk, all the code of accessing and sealing inside the transport plan has to be -commented out " - ;; (setup-for-demo object-list) - - (dolist (?object-type object-list) - (let* ((?deliver-pose (cram-tf:ensure-pose-in-frame - (btr:ensure-pose - (cdr (assoc ?object-type *cleaning-deliver-poses*))) - cram-tf:*fixed-frame*)) - (?deliver-location (a location (pose ?deliver-pose))) - (?fetch-location (a location - (on (an object - (type counter-top) - (urdf-name kitchen-island-surface) - (owl-name "kitchen_island_counter_top") - (part-of kitchen))) - (side back) - (side right))) - (?color (cdr (assoc ?object-type *object-colors*))) - (?grasp (cdr (assoc ?object-type *object-grasps*))) - (?object (an object - (type ?object-type) - (location ?fetch-location) - (desig:when ?color - (color ?color))))) - (when (or (eql ?object-type :milk) - (eql ?object-type :breakfast-cereal)) - (exe:perform (an action - (type accessing) - (arm left) - (location - (desig:a location - (in (an object - (type drawer) - (urdf-name sink-area-trash-drawer-main) - (owl-name "drawer_sinkblock_middle_open") - (part-of kitchen)))))))) - (let ((?obj (exe:perform - (an action - (type searching) - (object ?object) - (location ?fetch-location))))) - (exe:perform (desig:an action - (type fetching) - (object ?obj) - (grasps (?grasp)) - (arms (right)))) - (exe:perform (desig:an action - (type delivering) - (object ?obj) - (target ?deliver-location))) - (setf (btr:pose (btr:object btr:*current-bullet-world* - (desig:desig-prop-value ?obj :name))) - (cram-tf:translate-pose - (btr:pose (btr:object btr:*current-bullet-world* - (desig:desig-prop-value ?obj :name))) - :z-offset -0.3)) - (when (or (eql ?object-type :milk) - (eql ?object-type :breakfast-cereal)) - (btr:attach-object (btr:get-environment-object) - (btr:object btr:*current-bullet-world* - (desig:desig-prop-value ?obj :name)) - :link "sink_area_trash_drawer_main"))) - (when (or (eql ?object-type :milk) - (eql ?object-type :breakfast-cereal)) - (exe:perform (an action - (type sealing) - (arm left) - (location - (desig:a location - (in (an object - (type drawer) - (urdf-name sink-area-trash-drawer-main) - (owl-name "drawer_sinkblock_middle_open") - (part-of kitchen))))))))))) - - -(cpl:def-cram-function get-from-vertical-drawer (&optional ?open (?object :breakfast-cereal)) - "Grabbing the object (breakfast-cereal) from vertical drawer. -It doesn't seal the vertical drawer now -because there is some error when trying to close the drawer" - (when ?open - (perform - (an action - (type accessing) - (location (a location - (in (an object - (type drawer) - (urdf-name oven-area-area-right-drawer-handle) - ;;This should be referencing the container itself - (part-of kitchen))))) - (distance 0.35)))) - - ;; This plan is rudimentary and just aims to increase the fetch retries - (let* ((?f-loc (cdr (assoc ?object *fetch-locations*))) - (?perceived-object-designator - (perform (an action - (type searching) - (object (an object (type ?object))) - (location ?f-loc))))) - - (let ((?fetched-object - (cpl:with-retry-counters ((fetching-retry 3)) - (cpl:with-failure-handling - ((common-fail:object-unfetchable (e) - (declare (ignore e)) - (cpl:do-retry fetching-retry - (roslisp:ros-warn (milestone fetch-fail) - "~%Failed fetch from vertical drawer~%") - (cpl:retry)) - (roslisp:ros-warn (milestone fetch-fail) - "~%No more retries~%"))) - (perform - (an action - (type fetching) - (object ?perceived-object-designator)))))) - (?destination (cdr (assoc ?object *delivery-locations*)))) - - (perform (an action - (type delivering) - (object ?fetched-object) - (target ?destination)))))) - - - -(cpl:def-cram-function put-into-trash (&optional (?object :bowl)) - "Interim put into trash method as long as the dropping plan is not complete. - This will work only as long as the stability check inside deliver plan is commented out" - (let ((?perceived-object-designator - (perform (an action - (type searching) - (object (an object - (type ?object))) - (location (a location - (on (an object - (type counter-top) - (urdf-name kitchen-island-surface) - (part-of kitchen))) - (side back) - (side right))))))) - (let ((?fetched-object - (perform (an action - (type fetching) - (object ?perceived-object-designator))))) - (perform (an action - (type accessing) - (location (a location - (in (an object - (type drawer) - (urdf-name sink-area-trash-drawer-main) - (part-of kitchen))))) - (distance 0.4))) - - (perform (an action - (type delivering) - (object ?fetched-object) - (target (a location - (on (an object - (type drawer) - (urdf-name sink-area-trash-drawer-main) - (part-of kitchen))) - (side front) - (side right) - (for (an object (type ?object))) - (range 0.2)))))))) - ;; Sealing the trash drawer after putting in the trash. Doesn't work now as the dropped trash - ;; doesn't fall into the drawer, preventing the drawer from closing. Uncomment and include - ;; into `put-into-trash' as soon as this bug is fixed. - ;; (perform (an action - ;; (type sealing) - ;; (location (a location - ;; (in (an object - ;; (type drawer) - ;; (urdf-name sink-area-trash-drawer-main) - ;; (part-of-kitchen))))) - ;; (distance 0.4)))))) - -;; Ideal working for clean up (tried for fridge, doesn't work now) -;; (cpl:def-cram-function clean-up-demo (&optional (object-list '(:milk))) -;; -;; (dolist (?object object-list) -;; (let* ((f-loc `((:milk . ,(a location (in (an object -;; (type container) -;; (urdf-name iai-fridge-main) -;; (part-of kitchen) -;; (level topmost))) -;; (for (an object -;; (type milk))) -;; (side left) -;; (side front))))) -;; (?f (cdr (assoc ?object *delivery-locations*))) -;; (?d (cdr (assoc ?object f-loc))) -;; (?obj (an object -;; (type ?object) -;; (location ?f)))) -;; (exe:perform -;; (an action -;; ;; (arm left) -;; (type transporting) -;; (object ?obj) -;; (location ?f) -;; (target ?d)))))) diff --git a/cram_pr2/cram_pr2_process_modules/cram-pr2-process-modules.asd b/cram_pr2/cram_pr2_process_modules/cram-pr2-process-modules.asd index c68fceed61..ee8e466ecb 100644 --- a/cram_pr2/cram_pr2_process_modules/cram-pr2-process-modules.asd +++ b/cram_pr2/cram_pr2_process_modules/cram-pr2-process-modules.asd @@ -52,4 +52,5 @@ (:file "designators" :depends-on ("package")) (:file "grippers" :depends-on ("package")) (:file "ptu" :depends-on ("package")) - (:file "with-real-robot" :depends-on ("package")))))) + (:file "giskard" :depends-on ("package")) + (:file "with-real-robot" :depends-on ("package" "grippers" "ptu" "giskard")))))) diff --git a/cram_pr2/cram_pr2_projection/src/package.lisp b/cram_pr2/cram_pr2_process_modules/src/giskard.lisp similarity index 67% rename from cram_pr2/cram_pr2_projection/src/package.lisp rename to cram_pr2/cram_pr2_process_modules/src/giskard.lisp index 252d0d60a7..51dba06942 100644 --- a/cram_pr2/cram_pr2_projection/src/package.lisp +++ b/cram_pr2/cram_pr2_process_modules/src/giskard.lisp @@ -1,5 +1,5 @@ ;;; -;;; Copyright (c) 2017, Gayane Kazhoyan +;;; Copyright (c) 2016, Gayane Kazhoyan ;;; All rights reserved. ;;; ;;; Redistribution and use in source and binary forms, with or without @@ -27,24 +27,18 @@ ;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE ;;; POSSIBILITY OF SUCH DAMAGE. -(defpackage cram-pr2-projection - (:nicknames #:pr2-proj) - (:use #:common-lisp - #:cram-prolog - ;; #:cram-bullet-reasoning - ;; #:cram-process-modules - ;; #:cram-projection - ;; #:cl-transforms-stamped - ;; #:cram-robot-interfaces - ;; #:cram-tf - ) - (:export - ;; projection-clock - #:action-duration #:projection-timestamp-function #:execute-as-action - ;; ik - #:*torso-step* - ;; projection-environment - #:with-simulated-robot #:with-projected-robot - #:pr2-bullet-projection-environment - ;; low-level - #:*debug-short-sleep-duration* #:*debug-long-sleep-duration*)) +(in-package :pr2-pms) + +(prolog:def-fact-group giskard-pm (cpm:matching-process-module + cpm:available-process-module) + + (prolog:<- (cpm:matching-process-module ?motion-designator giskard:giskard-pm) + (or (desig:desig-prop ?motion-designator (:type :moving-tcp)) + (desig:desig-prop ?motion-designator (:type :moving-arm-joints)) + (desig:desig-prop ?motion-designator (:type :pulling)) + (desig:desig-prop ?motion-designator (:type :pushing)) + (desig:desig-prop ?motion-designator (:type :going)) + (desig:desig-prop ?motion-designator (:type :moving-torso)))) + + (prolog:<- (cpm:available-process-module giskard:giskard-pm) + (prolog:not (cpm:projection-running ?_)))) diff --git a/cram_pr2/cram_pr2_process_modules/src/with-real-robot.lisp b/cram_pr2/cram_pr2_process_modules/src/with-real-robot.lisp index 87c1b711b1..f8183e04ec 100644 --- a/cram_pr2/cram_pr2_process_modules/src/with-real-robot.lisp +++ b/cram_pr2/cram_pr2_process_modules/src/with-real-robot.lisp @@ -31,7 +31,7 @@ (defmacro with-real-robot (&body body) `(cram-process-modules:with-process-modules-running - (rs:robosherlock-perception-pm giskard:giskard-pm ;; navp:navp-pm - pr2-pms::pr2-grippers-pm pr2-pms::pr2-ptu-pm) + (rs:robosherlock-perception-pm ;; navp:navp-pm + pr2-grippers-pm pr2-ptu-pm giskard:giskard-pm) (cpl-impl::named-top-level (:name :top-level) ,@body))) diff --git a/cram_pr2/cram_pr2_projection/CATKIN_IGNORE b/cram_pr2/cram_pr2_projection/CATKIN_IGNORE deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/cram_pr2/cram_pr2_projection/THIS_PACKAGE_IS_DEPRECATED b/cram_pr2/cram_pr2_projection/THIS_PACKAGE_IS_DEPRECATED deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/cram_pr2/cram_pr2_projection/package.xml b/cram_pr2/cram_pr2_projection/package.xml deleted file mode 100644 index 2af5c2a34e..0000000000 --- a/cram_pr2/cram_pr2_projection/package.xml +++ /dev/null @@ -1,38 +0,0 @@ - - cram_pr2_projection - 0.7.0 - - Projection process modules for PR2 - - Gayane Kazhoyan - Gayane Kazhoyan - BSD - http://cram-system.org - https://github.com/cram2/cram_pr2/issues - https://github.com/cram2/cram_pr2 - - catkin - - cram_projection - cram_prolog - cram_designators - cram_utilities - cram_bullet_reasoning - cram_bullet_reasoning_belief_state - cram_tf - cram_robot_interfaces - cl_transforms - cl_transforms_stamped - cl_tf - cram_occasions_events - cram_plan_occasions_events - cram_pr2_description - cram_common_designators - cram_common_failures - cram_process_modules - roslisp_utilities - alexandria - moveit_msgs - - - diff --git a/cram_pr2/cram_pr2_projection/src/ik.lisp b/cram_pr2/cram_pr2_projection/src/ik.lisp deleted file mode 100644 index 7c645661bf..0000000000 --- a/cram_pr2/cram_pr2_projection/src/ik.lisp +++ /dev/null @@ -1,366 +0,0 @@ -;;; -;;; Copyright (c) 2016, Gayane Kazhoyan -;;; 2017, Christopher Pollok -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Institute for Artificial Intelligence/ -;;; Universitaet Bremen nor the names of its contributors may be used to -;;; endorse or promote products derived from this software without -;;; specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :pr2-proj) - - -(defparameter *ik-service-namespaces* '(:left "pr2_left_arm_kinematics" - :right "pr2_right_arm_kinematics")) - -(defvar *ik-persistent-services* '(:left nil :right nil) - "a persistent service for ik requests") - -(defvar *ik-solver-infos* '(:left nil :right nil) - "ik solver infos for the left and right arm ik solvers") - -(defvar *fk-solver-infos* '(:left nil :right nil) - "fk solver infos for the left and right arm fk solvers") - -(defun get-ik-persistent-service (left-or-right) - (declare (type keyword left-or-right)) - (let ((service (getf *ik-persistent-services* left-or-right))) - (if (and service (roslisp:persistent-service-ok service)) - service - (setf (getf *ik-persistent-services* left-or-right) - (make-instance 'roslisp:persistent-service - :service-name (concatenate 'string - (getf *ik-service-namespaces* left-or-right) - "/get_ik") - :service-type "moveit_msgs/GetPositionIK"))))) - -;; (defun get-ik-solver-info (left-or-right) -;; (or (getf *ik-solver-infos* left-or-right) -;; (setf (getf *ik-solver-infos* left-or-right) -;; (roslisp:with-fields (kinematic_solver_info) -;; (roslisp:call-service -;; (concatenate 'string -;; (getf *ik-service-namespaces* left-or-right) -;; "/get_ik_solver_info") -;; "pr2_arm_kinematics/GetKinematicSolverInfo") -;; kinematic_solver_info)))) - -(defun get-ik-solver-joints (left-or-right) - ;; (roslisp:with-fields (joint_names) - ;; (get-ik-solver-info left-or-right) - ;; joint_names) - (ecase left-or-right - (:left - #("l_shoulder_pan_joint" "l_shoulder_lift_joint" "l_upper_arm_roll_joint" - "l_elbow_flex_joint" "l_forearm_roll_joint" "l_wrist_flex_joint" - "l_wrist_roll_joint")) - (:right - #("r_shoulder_pan_joint" "r_shoulder_lift_joint" "r_upper_arm_roll_joint" - "r_elbow_flex_joint" "r_forearm_roll_joint" "r_wrist_flex_joint" - "r_wrist_roll_joint")))) - -(defun get-ik-solver-link (left-or-right) - ;; (roslisp:with-fields (link_names) - ;; (get-ik-solver-info left-or-right) - ;; (aref link_names 0)) - (ecase left-or-right - (:left "l_wrist_roll_link") - (:right "r_wrist_roll_link"))) - -;; (defun get-fk-solver-info (left-or-right) -;; (or (getf *fk-solver-infos* left-or-right) -;; (setf (getf *fk-solver-infos* left-or-right) -;; (roslisp:with-fields (kinematic_solver_info) -;; (roslisp:call-service -;; (concatenate 'string -;; (getf *ik-service-namespaces* left-or-right) -;; "/get_fk_solver_info") -;; "pr2_arm_kinematics/GetKinematicSolverInfo") -;; kinematic_solver_info)))) - -(defun get-fk-solver-joints (left-or-right) - ;; (roslisp:with-fields (joint_names) - ;; (get-fk-solver-info left-or-right) - ;; joint_names) - (get-ik-solver-joints left-or-right)) - -(defun get-fk-links (left-or-right) - (ecase left-or-right - (:left (vector "l_wrist_roll_link" "l_elbow_flex_link")) - (:right (vector "r_wrist_roll_link" "r_elbow_flex_link")))) - -(defun make-zero-seed-state (left-or-right) - (let* ((joint-names (get-ik-solver-joints left-or-right)) - (zero-vector (apply #'vector (make-list - (length joint-names) - :initial-element 0.0)))) - (roslisp:make-message - "sensor_msgs/JointState" - name joint-names - position zero-vector - velocity zero-vector - effort zero-vector))) - -;; (defun make-current-seed-state (left-or-right) -;; (let* ((joint-names-vector (get-ik-solver-joints left-or-right)) -;; (joint-names (map 'list #'identity joint-names-vector)) -;; (joint-states (map 'vector #'joint-state-position (joint-states joint-names))) -;; (zero-vector (apply #'vector (make-list -;; (length joint-names) -;; :initial-element 0.0)))) -;; (roslisp:make-message -;; "sensor_msgs/JointState" -;; name joint-names-vector -;; position joint-states -;; velocity zero-vector -;; effort zero-vector))) -;; TODO: use bullet instead - -(defun call-ik-persistent-service (left-or-right cartesian-pose - &optional (ik-base-frame "torso_lift_link")) - (declare (type keyword left-or-right) - (type cl-transforms:pose cartesian-pose)) - (let ((ik-link (get-ik-solver-link left-or-right))) - (roslisp:with-fields ((error-code error_code) - (joint-state (joint_state solution))) - (roslisp:call-persistent-service - (get-ik-persistent-service left-or-right) - (roslisp:make-request - "moveit_msgs/GetPositionIK" - (:ik_link_name :ik_request) ik-link - (:pose_stamped :ik_request) (cl-tf:to-msg - (cl-tf:pose->pose-stamped ik-base-frame 0.0 cartesian-pose)) - (:joint_state :robot_state :ik_request) (make-zero-seed-state left-or-right) - (:timeout :ik_request) 1.0)) - (cond ((eql error-code - (roslisp-msg-protocol:symbol-code - 'moveit_msgs-msg:moveiterrorcodes - :success)) joint-state) - ((eql error-code - (roslisp-msg-protocol:symbol-code - 'moveit_msgs-msg:moveiterrorcodes - :no_ik_solution)) nil) - (t (error 'simple-error - "IK service failed: ~a" - (roslisp-msg-protocol:code-symbol - 'moveit_msgs-msg:moveiterrorcodes - error-code))))))) - -(defun call-ik-service (left-or-right cartesian-pose &optional seed-state) - (declare (type keyword left-or-right) - (type cl-transforms-stamped:pose-stamped cartesian-pose)) - (let ((ik-link (get-ik-solver-link left-or-right))) - (handler-case - (roslisp:with-fields ((response-error-code (val error_code)) - (joint-state (joint_state solution))) - (progn - (roslisp:wait-for-service (concatenate 'string - (getf *ik-service-namespaces* left-or-right) - "/get_ik") 10.0) - (roslisp:call-service - (concatenate 'string (getf *ik-service-namespaces* left-or-right) "/get_ik") - "moveit_msgs/GetPositionIK" - (roslisp:make-request - "moveit_msgs/GetPositionIK" - (:ik_link_name :ik_request) ik-link - (:pose_stamped :ik_request) (cl-transforms-stamped:to-msg - (cram-tf:ensure-pose-in-frame - cartesian-pose - cram-tf:*robot-torso-frame* - :use-zero-time T)) - (:joint_state :robot_state :ik_request) (or seed-state - (make-zero-seed-state left-or-right)) - (:timeout :ik_request) 1.0))) - (cond ((eql response-error-code - (roslisp-msg-protocol:symbol-code - 'moveit_msgs-msg:moveiterrorcodes - :success)) - joint-state) - ((eql response-error-code - (roslisp-msg-protocol:symbol-code - 'moveit_msgs-msg:moveiterrorcodes - :no_ik_solution)) - nil) - (T - (error 'simple-error - :format-control "IK service failed: ~a" - :format-arguments (list - (roslisp-msg-protocol:code-symbol - 'moveit_msgs-msg:moveiterrorcodes - response-error-code)))))) - (simple-error (e) - (declare (ignore e)) - nil)))) - - - -(defun arm-pose-hash-code (arm-pose-list) - (let* ((pose (second arm-pose-list)) - (pose-list (cram-tf:pose->flat-list pose)) - (sum (abs (apply #'+ pose-list))) - (sum-big-precise-num (* sum 100000000)) - (pose-hash-code (floor sum-big-precise-num)) - (arm (first arm-pose-list)) - (overall-hash-code (ecase arm - (:left (+ pose-hash-code 10000)) - (:right (+ pose-hash-code 20000))))) - overall-hash-code)) -(defun arm-poses-equal-accurate (arm-pose-list-1 arm-pose-list-2) - (let* ((pose-1 (second arm-pose-list-1)) - (pose-2 (second arm-pose-list-2)) - (arm-1 (first arm-pose-list-1)) - (arm-2 (first arm-pose-list-2))) - (if (eql arm-1 arm-2) - (cram-tf:poses-equal-p pose-1 pose-2 0.000001d0 0.000010d0) - nil))) -(sb-ext:define-hash-table-test arm-poses-equal-accurate arm-pose-hash-code) -(defvar *ik-solution-cache* (make-hash-table :test 'arm-poses-equal-accurate)) - -(defparameter *torso-step* 0.01) - -(defun call-ik-service-with-torso-resampling (left-or-right cartesian-pose - &key seed-state test-angle torso-angle - torso-lower-limit torso-upper-limit) - (labels ((call-ik-service-with-torso-resampling-inner (left-or-right cartesian-pose - &key seed-state test-angle - torso-angle - torso-lower-limit torso-upper-limit) - (let ((ik-solution-msg (call-ik-service left-or-right cartesian-pose seed-state))) - (if ik-solution-msg - (let ((ik-solution-position - (map 'list #'identity - (roslisp:msg-slot-value - ik-solution-msg 'sensor_msgs-msg:position))) - (resulting-torso-angle (or test-angle torso-angle))) - (setf (gethash (list left-or-right cartesian-pose) *ik-solution-cache*) - (list ik-solution-position resulting-torso-angle)) - (values ik-solution-position resulting-torso-angle)) - (when (or (not test-angle) (> test-angle torso-lower-limit)) - ;; When we have no ik solution and have a valid torso angle to try, - ;; use it to resample. - (let* ((next-test-angle - (if test-angle - (max torso-lower-limit (- test-angle *torso-step*)) - torso-upper-limit)) - (torso-offset - (if test-angle - (- test-angle torso-angle) - 0)) - (next-torso-offset - (- next-test-angle torso-angle)) - (pseudo-pose - (cram-tf:translate-pose cartesian-pose - :z-offset (- torso-offset - next-torso-offset)))) - (call-ik-service-with-torso-resampling-inner - left-or-right pseudo-pose - :seed-state seed-state - :test-angle next-test-angle - :torso-angle torso-angle - :torso-lower-limit torso-lower-limit - :torso-upper-limit torso-upper-limit))))))) - - (let ((hashed-result - (gethash (list left-or-right cartesian-pose) *ik-solution-cache*))) - (if hashed-result - (values (first hashed-result) (second hashed-result)) - (let ((old-debug-lvl (roslisp:debug-level NIL))) - (unwind-protect - (progn - (roslisp:set-debug-level NIL 9) - (call-ik-service-with-torso-resampling-inner - left-or-right cartesian-pose - :seed-state seed-state - :test-angle test-angle - :torso-angle torso-angle - :torso-lower-limit torso-lower-limit - :torso-upper-limit torso-upper-limit)) - (roslisp:set-debug-level NIL old-debug-lvl))))))) - - -(defun call-fk-service (left-or-right link-names-vector - &optional (fk-base-frame "torso_lift_link")) - (declare (type keyword left-or-right)) - (handler-case - (roslisp:with-fields ((response-error-code (val error_code)) - pose_stamped fk_link_names) - (progn - (roslisp:wait-for-service (concatenate 'string - (getf *ik-service-namespaces* left-or-right) - "/get_fk_solver_info") 10.0) - (roslisp:call-service - (concatenate 'string (getf *ik-service-namespaces* left-or-right) "/get_fk") - "moveit_msgs/GetPositionFK" - (roslisp:make-request - 'moveit_msgs-srv:getpositionfk - (:frame_id :header) fk-base-frame - :fk_link_names (or link-names-vector (get-fk-links left-or-right)) - (:joint_state :robot_state) ;; (make-current-seed-state left-or-right) - (make-zero-seed-state left-or-right)))) - (cond ((eql response-error-code - (roslisp-msg-protocol:symbol-code - 'moveit_msgs-msg:moveiterrorcodes - :success)) - (map 'list - (lambda (name pose-stamped-msg) - (list name (cl-transforms-stamped:from-msg pose-stamped-msg))) - fk_link_names - pose_stamped)) - (t (error 'simple-error - :format-control "FK service failed: ~a" - :format-arguments (list - (roslisp-msg-protocol:code-symbol - 'moveit_msgs-msg:moveiterrorcodes - response-error-code)))))) - (simple-error (e) - (format t "~a~%FK service call freaked out. Hmmm...~%" e)))) - -(defmethod cram-robot-interfaces:compute-iks (pose-stamped - &key link-name arm robot-state seed-state - (pose-stamped-frame - cram-tf:*robot-torso-frame*) - (tcp-in-ee-pose - (cl-transforms:make-identity-pose))) - (declare (ignore link-name robot-state)) - (let* ((tcp-pose (cl-transforms-stamped:transform-pose-stamped - cram-tf:*transformer* - :pose (cl-transforms-stamped:copy-pose-stamped - pose-stamped :stamp 0.0) - :target-frame pose-stamped-frame - :timeout cram-tf:*tf-default-timeout*)) - (goal-trans (cl-transforms:transform* - (cl-transforms:reference-transform tcp-pose) - (cl-transforms:transform-inv - (cl-transforms:reference-transform tcp-in-ee-pose)))) - (ee-pose (cl-transforms-stamped:make-pose-stamped - (cl-transforms-stamped:frame-id tcp-pose) - (cl-transforms-stamped:stamp tcp-pose) - (cl-transforms:translation goal-trans) - (cl-transforms:rotation goal-trans))) - (solution - (call-ik-service arm - ee-pose - seed-state))) - (when solution - (list solution)))) diff --git a/cram_pr2/cram_pr2_projection/src/low-level.lisp b/cram_pr2/cram_pr2_projection/src/low-level.lisp deleted file mode 100644 index 441aa9ee8a..0000000000 --- a/cram_pr2/cram_pr2_projection/src/low-level.lisp +++ /dev/null @@ -1,527 +0,0 @@ -;;; -;;; Copyright (c) 2011, Lorenz Moesenlechner -;;; 2017, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software -;;; without specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :pr2-proj) - -(defparameter *debug-short-sleep-duration* 0.0 - "in seconds, sleeps after each movement during reasoning") -(defparameter *debug-long-sleep-duration* 0.0 - "in seconds, sleeps to show colliding configurations") - -(defparameter *be-strict-with-collisions* nil - "when grasping a spoon from table, fingers can collide with kitchen, so we might allow this") - -(defun robot-transform-in-map () - (let ((pose-in-map - (cut:var-value - '?pose - (car (prolog:prolog - `(and (cram-robot-interfaces:robot ?robot) - (btr:bullet-world ?w) - (btr:object-pose ?w ?robot ?pose))))))) - (cram-tf:pose->transform-stamped - cram-tf:*fixed-frame* - cram-tf:*robot-base-frame* - (cut:current-timestamp) - pose-in-map))) - -;;;;;;;;;;;;;;;;; NAVIGATION ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(defun drive (target) - (declare (type cl-transforms-stamped:pose-stamped target)) - (let* ((world btr:*current-bullet-world*) - (world-state (btr::get-state world))) - (unwind-protect - (assert - (prolog:prolog - `(and (cram-robot-interfaces:robot ?robot) - (btr:bullet-world ?w) - (btr:assert ?w (btr:object-pose ?robot ,target))))) - (when (btr:robot-colliding-objects-without-attached) - (unless (< (abs *debug-short-sleep-duration*) 0.0001) - (cpl:sleep *debug-short-sleep-duration*)) - (btr::restore-world-state world-state world) - (cpl:fail 'common-fail:navigation-pose-unreachable :pose-stamped target))))) - -;;;;;;;;;;;;;;;;; TORSO ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(defun move-torso (joint-angle) - (declare (type number joint-angle)) - (let* ((bindings - (car - (prolog:prolog - `(and (cram-robot-interfaces:robot ?robot) - (btr:bullet-world ?w) - (cram-robot-interfaces:robot-torso-link-joint ?robot ?_ ?joint) - (cram-robot-interfaces:joint-lower-limit ?robot ?joint ?lower) - (cram-robot-interfaces:joint-upper-limit ?robot ?joint ?upper))))) - (lower-limit - (cut:var-value '?lower bindings)) - (upper-limit - (cut:var-value '?upper bindings)) - (cropped-joint-angle - (if (< joint-angle lower-limit) - lower-limit - (if (> joint-angle upper-limit) - upper-limit - joint-angle)))) - (prolog:prolog - `(btr:assert (btr:joint-state ?w ?robot ((?joint ,cropped-joint-angle)))) - bindings) - (unless (< (abs (- joint-angle cropped-joint-angle)) 0.0001) - (cpl:fail 'common-fail:torso-goal-not-reached - :description (format nil "Torso goal ~a was out of joint limits" joint-angle) - :torso joint-angle)))) - -;;;;;;;;;;;;;;;;; PTU ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(defun look-at-pose-stamped (pose-stamped) - (declare (type cl-transforms-stamped:pose-stamped pose-stamped)) - (let* ((bindings - (car - (prolog:prolog - '(and - (cram-robot-interfaces:robot ?robot) - (cram-robot-interfaces:robot-neck-links ?robot ?pan-link ?tilt-link) - (cram-robot-interfaces:robot-neck-joints ?robot ?pan-joint ?tilt-joint) - (cram-robot-interfaces:joint-lower-limit ?robot ?pan-joint ?pan-lower) - (cram-robot-interfaces:joint-upper-limit ?robot ?pan-joint ?pan-upper) - (cram-robot-interfaces:joint-lower-limit ?robot ?tilt-joint ?tilt-lower) - (cram-robot-interfaces:joint-upper-limit ?robot ?tilt-joint ?tilt-upper))))) - (pan-link - (cut:var-value '?pan-link bindings)) - (tilt-link - (cut:var-value '?tilt-link bindings)) - (pan-joint - (cut:var-value '?pan-joint bindings)) - (tilt-joint - (cut:var-value '?tilt-joint bindings)) - (pan-lower-limit - (cut:var-value '?pan-lower bindings)) - (pan-upper-limit - (cut:var-value '?pan-upper bindings)) - (tilt-lower-limit - (cut:var-value '?tilt-lower bindings)) - (tilt-upper-limit - (cut:var-value '?tilt-upper bindings)) - (pose-in-world - (cram-tf:ensure-pose-in-frame - pose-stamped - cram-tf:*fixed-frame* - :use-zero-time t)) - (pan-tilt-angles - (btr:calculate-pan-tilt (btr:get-robot-object) pan-link tilt-link pose-in-world)) - (pan-angle - (first pan-tilt-angles)) - (tilt-angle - (second pan-tilt-angles)) - (cropped-pan-angle - (if (< pan-angle pan-lower-limit) - pan-lower-limit - (if (> pan-angle pan-upper-limit) - pan-upper-limit - pan-angle))) - (cropped-tilt-angle - (if (< tilt-angle tilt-lower-limit) - tilt-lower-limit - (if (> tilt-angle tilt-upper-limit) - tilt-upper-limit - tilt-angle)))) - (prolog:prolog - `(and (btr:bullet-world ?w) - (cram-robot-interfaces:robot ?robot) - (btr:%object ?w ?robot ?robot-object) - (assert ?world - (btr:joint-state - ?robot ((,pan-joint ,cropped-pan-angle) - (,tilt-joint ,cropped-tilt-angle)))))) - (unless (and (< (abs (- pan-angle cropped-pan-angle)) 0.00001) - (< (abs (- tilt-angle cropped-tilt-angle)) 0.00001)) - (cpl:fail 'common-fail:ptu-goal-not-reached - :description "Look action wanted to twist the neck")))) - -(defun look-at (?goal-pose ?goal-configuration) - (if ?goal-configuration - (prolog:prolog - `(and (rob-int:robot ?robot) - (btr:bullet-world ?world) - (assert ?world (btr:joint-state ?robot ,?goal-configuration)))) - (look-at-pose-stamped ?goal-pose))) - -;;;;;;;;;;;;;;;;; PERCEPTION ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(defun extend-perceived-object-designator (input-designator name-pose-type-list) - (destructuring-bind (name pose type) name-pose-type-list - (let* ((pose-stamped-in-fixed-frame - (cl-transforms-stamped:make-pose-stamped - cram-tf:*fixed-frame* - (cut:current-timestamp) - (cl-transforms:origin pose) - (cl-transforms:orientation pose))) - (transform-stamped-in-fixed-frame - (cram-tf:pose-stamped->transform-stamped - pose-stamped-in-fixed-frame - (roslisp-utilities:rosify-underscores-lisp-name name))) - (pose-stamped-in-base-frame - (cram-tf:multiply-transform-stampeds - cram-tf:*robot-base-frame* - (roslisp-utilities:rosify-underscores-lisp-name name) - (cram-tf:transform-stamped-inv (robot-transform-in-map)) - transform-stamped-in-fixed-frame - :result-as-pose-or-transform :pose)) - (transform-stamped-in-base-frame - (cram-tf:multiply-transform-stampeds - cram-tf:*robot-base-frame* - (roslisp-utilities:rosify-underscores-lisp-name name) - (cram-tf:transform-stamped-inv (robot-transform-in-map)) - transform-stamped-in-fixed-frame - :result-as-pose-or-transform :transform))) - (let ((output-designator - (desig:copy-designator - input-designator - :new-description - `((:type ,type) - (:name ,name) - (:pose ((:pose ,pose-stamped-in-base-frame) - (:transform ,transform-stamped-in-base-frame) - (:pose-in-map ,pose-stamped-in-fixed-frame) - (:transform-in-map ,transform-stamped-in-fixed-frame))))))) - (setf (slot-value output-designator 'desig:data) - (make-instance 'desig:object-designator-data - :object-identifier name - :pose pose-stamped-in-fixed-frame)) - ;; (desig:equate input-designator output-designator) - output-designator)))) - -(defun detect (input-designator) - (declare (type desig:object-designator input-designator)) - - (let* ((object-name (desig:desig-prop-value input-designator :name)) - (object-type (desig:desig-prop-value input-designator :type)) - (quantifier (desig:quantifier input-designator)) - - ;; find all visible objects with name `object-name' and of type `object-type' - (name-pose-type-lists ; e.g.: ((mondamin-1 :mondamin ) (mug-2 :mug )) - (cut:force-ll - (cut:lazy-mapcar - (lambda (solution-bindings) - (cut:with-vars-strictly-bound (?object-name ?object-pose ?object-type) - solution-bindings - (list ?object-name ?object-pose ?object-type))) - (prolog:prolog `(and (cram-robot-interfaces:robot ?robot) - (btr:bullet-world ?world) - ,@(when object-name - `((prolog:== ?object-name ,object-name))) - (btr:object ?world ?object-name) - ,@(when object-type - `((prolog:== ?object-type ,object-type))) - (btr:item-type ?world ?object-name ?object-type) - (btr:visible ?world ?robot ?object-name) - (btr:pose ?world ?object-name ?object-pose))))))) - - ;; check if objects were found - (unless name-pose-type-lists - (cpl:fail 'common-fail:perception-object-not-found :object input-designator - :description (format nil "Could not find object ~a." input-designator))) - - ;; Extend the input-designator with the information found through visibility check: - ;; name & pose & type of the object, - ;; equate the input-designator to the new output-designator. - ;; If multiple objects are visible, return multiple equated objects, - ;; otherwise only take first found object. I.e. need to find :an object (not :all objects) - (case quantifier - (:all (mapcar (alexandria:curry #'extend-perceived-object-designator input-designator) - name-pose-type-lists)) - ((:a :an) (extend-perceived-object-designator - input-designator - (first name-pose-type-lists))) - (t (error "[PROJECTION DETECT]: Quantifier can only be a/an or all."))))) - -;;;;;;;;;;;;;;;;; GRIPPERS ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(defun one-gripper-action (action-type arm &optional maximum-effort) - (declare (ignore maximum-effort)) - "Opens or closes the specific gripper." - (mapc - - (lambda (solution-bindings) - (prolog:prolog - `(and - (btr:bullet-world ?world) - (assert ?world (btr:joint-state ?robot ((?joint ,(case action-type - (:open '?max-limit) - ((:close :grip) '?min-limit) - (t (if (numberp action-type) - (* action-type 5.0) - ;; commanded with meters - ;; but asserted with rads - (error "[PROJ GRIP] failed"))))))))) - solution-bindings)) - - (cut:force-ll - (prolog:prolog - `(and (cram-robot-interfaces:robot ?robot) - (cram-robot-interfaces:gripper-joint ?robot ,arm ?joint) - (cram-robot-interfaces:joint-lower-limit ?robot ?joint ?min-limit) - (cram-robot-interfaces:joint-upper-limit ?robot ?joint ?max-limit))))) - - ;; check if there is an object to grip - (when (eql action-type :grip) ; if action was gripping check if gripper collided with an item - (unless (prolog:prolog - `(and (btr:bullet-world ?world) - (cram-robot-interfaces:robot ?robot) - (btr:contact ?world ?robot ?object-name ?link) - (cram-robot-interfaces:gripper-link ?robot ,arm ?link) - (btr:%object ?world ?object-name ?object-instance) - ;; (or (prolog:lisp-type ?object-instance btr:item) - ;; (prolog:lisp-type ?object-instance btr:semantic-map-object)) - )) - (cpl:fail 'common-fail:gripper-closed-completely - :description "There was no object to grip")))) - -(defun gripper-action (action-type arm &optional maximum-effort) - (if (and arm (listp arm)) - (cpl:par - (one-gripper-action action-type (first arm) maximum-effort) - (one-gripper-action action-type (second arm) maximum-effort)) - (one-gripper-action action-type arm maximum-effort))) - -;;;;;;;;;;;;;;;;; ARMS ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -;;; joint movement - -(defun move-joints (left-configuration right-configuration) - (declare (type list left-configuration right-configuration)) - (flet ((set-configuration (arm joint-values) - (when joint-values - (let ((joint-name-value-list - (if (listp (car joint-values)) - joint-values - (let ((joint-names - (cut:var-value - '?joints - (car (prolog:prolog - `(and (cram-robot-interfaces:robot ?robot) - (cram-robot-interfaces:arm-joints ?robot ,arm - ?joints))))))) - (unless (= (length joint-values) (length joint-names)) - (error "[PROJECTION MOVE-JOINTS] length of joints list is incorrect")) - (mapcar (lambda (name value) - (list name (* value 1.0d0))) - joint-names joint-values))))) - (assert - (prolog:prolog - `(and - (btr:bullet-world ?world) - (cram-robot-interfaces:robot ?robot) - (assert ?world (btr:joint-state ?robot ,joint-name-value-list))))))))) - (set-configuration :left left-configuration) - (set-configuration :right right-configuration))) - -;;; cartesian movement - -(defparameter *gripper-length* 0.2 "PR2's gripper length in meters, for calculating TCP -> EE") - -(defun tcp-pose->ee-pose (tcp-pose) - (when tcp-pose - (cl-transforms-stamped:pose->pose-stamped - (cl-transforms-stamped:frame-id tcp-pose) - (cl-transforms-stamped:stamp tcp-pose) - (cl-transforms:transform-pose - (cl-transforms:pose->transform tcp-pose) - (cl-transforms:make-pose - (cl-transforms:make-3d-vector (- *gripper-length*) 0 0) - (cl-transforms:make-identity-rotation)))))) - -(defun ee-pose-in-base->ee-pose-in-torso (ee-pose-in-base) - (when ee-pose-in-base - (if (string-equal - (cl-transforms-stamped:frame-id ee-pose-in-base) - cram-tf:*robot-base-frame*) - ;; tPe: tTe = tTb * bTe = tTm * mTb * bTe = (mTt)-1 * mTb * bTe - (let* ((map-torso-transform - (cram-tf:pose->transform-stamped - cram-tf:*fixed-frame* - cram-tf:*robot-torso-frame* - 0.0 - (btr:link-pose - (btr:get-robot-object) - cram-tf:*robot-torso-frame*))) - (torso-map-transform - (cram-tf:transform-stamped-inv map-torso-transform)) - (map-base-transform - (cram-tf:pose->transform-stamped - cram-tf:*fixed-frame* - cram-tf:*robot-base-frame* - 0.0 - (btr:pose (btr:get-robot-object)))) - (torso-base-transform - (cram-tf:multiply-transform-stampeds - cram-tf:*robot-torso-frame* - cram-tf:*robot-base-frame* - torso-map-transform - map-base-transform)) - (base-ee-transform - (cram-tf:pose-stamped->transform-stamped - ee-pose-in-base - ;; dummy link name for T x T to work - "end_effector_link"))) - (cram-tf:multiply-transform-stampeds - cram-tf:*robot-torso-frame* - "end_effector_link" - torso-base-transform - base-ee-transform - :result-as-pose-or-transform :pose)) - (error "Arm movement goals should be given in robot base frame")))) - -(defun get-ik-joint-positions (arm ee-pose) - (when ee-pose - (multiple-value-bind (ik-solution torso-angle) - (cut:with-vars-bound (?torso-angle ?lower-limit ?upper-limit) - (car (prolog:prolog - `(and - (cram-robot-interfaces:robot ?robot) - (cram-robot-interfaces:robot-torso-link-joint ?robot - ?_ ?torso-joint) - (cram-robot-interfaces:joint-lower-limit ?robot ?torso-joint - ?lower-limit) - (cram-robot-interfaces:joint-upper-limit ?robot ?torso-joint - ?upper-limit) - (btr:bullet-world ?world) - (btr:joint-state ?world ?robot ?torso-joint ?torso-angle)))) - (call-ik-service-with-torso-resampling - arm ee-pose - :torso-angle ?torso-angle - :torso-lower-limit ?lower-limit - :torso-upper-limit ?upper-limit - ;; seed-state ; is todo - )) - (unless ik-solution - (cpl:fail 'common-fail:manipulation-pose-unreachable - :description (format nil "~a is unreachable for EE." ee-pose))) - (values ik-solution torso-angle)))) - -(defun perform-collision-check (collision-mode left-tcp-pose right-tcp-pose) - (unless collision-mode - (setf collision-mode :avoid-all)) - (ecase collision-mode - (:allow-all - nil) - (:allow-attached - ;; allow-attached means the robot is not allowed to hit anything - ;; (except the object it is holding), - ;; but the object it is holding can create collisions with environment etc. - (when (and *be-strict-with-collisions* - (btr:robot-colliding-objects-without-attached)) - (cpl:fail 'common-fail:manipulation-goal-not-reached - :description "Robot is in collision with environment."))) - (:allow-hand - ;; allow hand allows collisions between the hand and anything - ;; but not the rest of the robot - ;; therefore, we take a list of all links of the robot that are colliding - ;; with something, remove attached object collisions from this list, - ;; and then remove the hand links from the list. - ;; if the list is still not empty, there is a collision between - ;; a robot non-hand link and something else - (when (and *be-strict-with-collisions* - (set-difference - (mapcar #'cdr - (reduce (lambda (link-contacts attachment) - (remove (btr:object - btr:*current-bullet-world* - (car attachment)) - link-contacts - :key #'car)) - (append - (list (btr:link-contacts (btr:get-robot-object))) - (btr:attached-objects (btr:get-robot-object))))) - (append (when left-tcp-pose - (cut:var-value - '?hand-links - (car (prolog:prolog - `(and (rob-int:robot ?robot) - (rob-int:hand-links ?robot :left ?hand-links)))))) - (when right-tcp-pose - (cut:var-value - '?hand-links - (car (prolog:prolog - `(and (rob-int:robot ?robot) - (rob-int:hand-links ?robot :right ?hand-links))))))) - :test #'string-equal)) - (cpl:fail 'common-fail:manipulation-goal-not-reached - :description "Robot is in collision with environment."))) - (:avoid-all - ;; avoid all means the robot is not colliding with anything except the - ;; objects it is holding, and the objects it is holding only collides with robot - (when (or (btr:robot-colliding-objects-without-attached) - (some #'identity - (mapcar (lambda (attachment) - (remove (btr:get-robot-object) - (btr:find-objects-in-contact - btr:*current-bullet-world* - (btr:object - btr:*current-bullet-world* - (car attachment))))) - (btr:attached-objects (btr:get-robot-object))))) - (cpl:fail 'common-fail:manipulation-goal-not-reached - :description "Robot is in collision with environment."))))) - -(defun move-tcp (left-tcp-pose right-tcp-pose &optional collision-mode - collision-object-b collision-object-b-link collision-object-a) - (declare (type (or cl-transforms-stamped:pose-stamped null) left-tcp-pose right-tcp-pose)) - (multiple-value-bind (left-ik left-torso-angle) - (get-ik-joint-positions :left - (ee-pose-in-base->ee-pose-in-torso - (tcp-pose->ee-pose left-tcp-pose))) - (multiple-value-bind (right-ik right-torso-angle) - (get-ik-joint-positions :right - (ee-pose-in-base->ee-pose-in-torso - (tcp-pose->ee-pose right-tcp-pose))) - (cond - ((and left-torso-angle right-torso-angle) - (when (not (eq left-torso-angle right-torso-angle)) - (cpl:fail 'common-fail:manipulation-pose-unreachable - :description (format nil "In MOVE-TCP goals for the two arms ~ - require different torso angles)."))) - (move-torso left-torso-angle)) - (left-torso-angle (move-torso left-torso-angle)) - (right-torso-angle (move-torso right-torso-angle))) - (move-joints left-ik right-ik) - (perform-collision-check collision-mode left-tcp-pose right-tcp-pose)))) - -;;; constraint-based movement - -(defun move-with-constraints (constraints-string) - (declare (ignore constraints-string)) - (warn "Moving with constraints is not supported in projection! Ignoring.")) - - - - diff --git a/cram_pr2/cram_pr2_projection/src/process-modules.lisp b/cram_pr2/cram_pr2_projection/src/process-modules.lisp deleted file mode 100644 index bc39ed818f..0000000000 --- a/cram_pr2/cram_pr2_projection/src/process-modules.lisp +++ /dev/null @@ -1,103 +0,0 @@ -;;; -;;; Copyright (c) 2017, Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software -;;; without specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :pr2-proj) - -;;;;;;;;;;;;;;;;; NAVIGATION ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(cpm:def-process-module pr2-proj-navigation (motion-designator) - (destructuring-bind (command argument) (desig:reference motion-designator) - (ecase command - (cram-common-designators:move-base (drive argument))))) - -;;;;;;;;;;;;;;;;; TORSO ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(cpm:def-process-module pr2-proj-torso (motion-designator) - (destructuring-bind (command argument) (desig:reference motion-designator) - (ecase command - (cram-common-designators:move-torso (move-torso argument))))) - -;;;;;;;;;;;;;;;;; PTU ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(cpm:def-process-module pr2-proj-ptu (motion-designator) - (destructuring-bind (command goal-pose goal-configuration) (desig:reference motion-designator) - (ecase command - (cram-common-designators:move-head (look-at goal-pose goal-configuration))))) - -;;;;;;;;;;;;;;;;; PERCEPTION ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(cpm:def-process-module pr2-proj-perception (motion-designator) - (destructuring-bind (command argument-1) (desig:reference motion-designator) - (ecase command - (cram-common-designators:detect (detect argument-1))))) - -;;;;;;;;;;;;;;;;; GRIPPERS ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(cpm:def-process-module pr2-proj-grippers (motion-designator) - (destructuring-bind (command arg-1 arg-2 &rest arg-3) (desig:reference motion-designator) - (ecase command - (cram-common-designators:move-gripper-joint (gripper-action arg-1 arg-2 (car arg-3)))))) - -;;;;;;;;;;;;;;;;; ARMS ;;;;;;;;;;;;;;;;;;;;;;;;;;;;;;; - -(cpm:def-process-module pr2-proj-arms (motion-designator) - (destructuring-bind (command arg-1 &rest arg-2) (desig:reference motion-designator) - (ecase command - (cram-common-designators:move-tcp (move-tcp arg-1 (first arg-2) (second arg-2) - (third arg-2) (fourth arg-2) (fifth arg-2))) - (cram-common-designators::move-joints (move-joints arg-1 (car arg-2))) - (cram-common-designators::move-with-constraints (move-with-constraints arg-1))))) - - -;;;;;;;;;;;;;;;;;;;;; PREDICATES ;;;;;;;;;;;;;;;;;;;;;;;; - -(def-fact-group pr2-matching-pms (cpm:matching-process-module) - - (<- (cpm:matching-process-module ?motion-designator pr2-proj-navigation) - (desig:desig-prop ?motion-designator (:type :going))) - - (<- (cpm:matching-process-module ?motion-designator pr2-proj-torso) - (desig:desig-prop ?motion-designator (:type :moving-torso))) - - (<- (cpm:matching-process-module ?motion-designator pr2-proj-ptu) - (desig:desig-prop ?motion-designator (:type :looking))) - - (<- (cpm:matching-process-module ?motion-designator pr2-proj-perception) - (desig:desig-prop ?motion-designator (:type :detecting))) - - (<- (cpm:matching-process-module ?motion-designator pr2-proj-grippers) - (or (desig:desig-prop ?motion-designator (:type :gripping)) - (desig:desig-prop ?motion-designator (:type :moving-gripper-joint)) - (desig:desig-prop ?motion-designator (:type :opening-gripper)) - (desig:desig-prop ?motion-designator (:type :closing-gripper)))) - - (<- (cpm:matching-process-module ?motion-designator pr2-proj-arms) - (or (desig:desig-prop ?motion-designator (:type :moving-tcp)) - (desig:desig-prop ?motion-designator (:type :moving-arm-joints)) - (desig:desig-prop ?motion-designator (:type :moving-with-constraints))))) diff --git a/cram_pr2/cram_pr2_projection/src/projection-clock.lisp b/cram_pr2/cram_pr2_projection/src/projection-clock.lisp deleted file mode 100644 index 0f19bd7f7e..0000000000 --- a/cram_pr2/cram_pr2_projection/src/projection-clock.lisp +++ /dev/null @@ -1,70 +0,0 @@ -;;; Copyright (c) 2012, Lorenz Moesenlechner -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software -;;; without specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -;;; The projection clock is used to generate timelines. -;;; Currently we are not using timelines, so this is disabled. - -(in-package :pr2-proj) - -(defvar *projection-clock* nil) - -(prolog:def-fact-group action-facts (action-duration) - ;; Declaration of the action-duration predicate - (prolog:<- (action-duration ?designator ?duration) - (prolog:fail))) - -(defun projection-timestamp-function () - (proj:clock-time *projection-clock*)) - -(defun action-duration (designator &key (default 0)) - (declare (type desig:action-designator designator)) - "Returns the duration of the action as a number. Please note that no - unit is given. This value is mainly used for ordering events and - blocking until an action is terminated." - (cut:with-vars-bound (?duration) - (cut:lazy-car (prolog:prolog `(action-duration ,designator ?duration))) - (if (cut:is-var ?duration) default ?duration))) - -(defun execute-as-action (designator action-function) - "Executes `action-function' as an action. First, it - generates an event for the action to be started. Then, waits for the - duration of the action as returned by ACTION-DURATION using - *PROJECTION-CLOCK*. Finally, calls `action-function' to trigger all - updates in the world." - (declare (type desig:action-designator designator) - (type function action-function)) - (let ((duration (action-duration designator))) - (btr:timeline-advance - btr:*current-timeline* - (btr:make-event btr:*current-bullet-world* `(action-started ,designator))) - (proj:clock-wait *projection-clock* duration) - (unwind-protect - (funcall action-function) - (btr:timeline-advance - btr:*current-timeline* - (btr:make-event btr:*current-bullet-world* `(action-finished ,designator)))))) diff --git a/cram_pr2/cram_pr2_projection/src/projection-environment.lisp b/cram_pr2/cram_pr2_projection/src/projection-environment.lisp deleted file mode 100644 index a047c64a47..0000000000 --- a/cram_pr2/cram_pr2_projection/src/projection-environment.lisp +++ /dev/null @@ -1,135 +0,0 @@ -;;; Copyright (c) 2012, Lorenz Moesenlechner -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software -;;; without specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :pr2-proj) - -(defvar *last-timeline* nil) - -;; (defmethod desig:resolve-designator :around (designator (role (eql 'projection-role))) -;; (cram-projection:with-partially-ordered-clock-disabled *projection-clock* -;; (call-next-method))) - -(cram-projection:define-projection-environment pr2-bullet-projection-environment - :special-variable-initializers - ((cram-tf:*transformer* - (make-instance 'cl-tf:transformer)) - ;; TODO: use custom tf topic "tf_sim" - ;; For that first change tf2_ros/TransformListener to accept custom topic names - (cram-tf:*broadcaster* - (cram-tf:make-tf-broadcaster - "tf_projection" - cram-tf:*tf-broadcasting-interval*)) - ;; (*current-bullet-world* (cl-bullet:copy-world btr:*current-bullet-world*)) - (cram-bullet-reasoning:*current-timeline* - (btr:timeline-init btr:*current-bullet-world*)) - (desig:*default-role* - 'projection-role) - (*projection-clock* - (make-instance 'cram-projection:partially-ordered-clock)) - ;; (cut:*timestamp-function* #'projection-timestamp-function) - (cram-bullet-reasoning-belief-state::*object-identifier-to-instance-mappings* - (alexandria:copy-hash-table - cram-bullet-reasoning-belief-state::*object-identifier-to-instance-mappings*)) - ;; (cram-semantic-map::*semantic-map* - ;; (sem-map-utils:copy-semantic-map-object (cram-semantic-map:get-semantic-map))) - (cet:*episode-knowledge* - cet:*episode-knowledge*)) - :process-module-definitions - (pr2-proj-navigation pr2-proj-torso pr2-proj-ptu pr2-proj-perception - pr2-proj-grippers pr2-proj-arms btr-belief:world-state-detecting-pm) - :startup (progn - (cram-bullet-reasoning-belief-state:set-tf-from-bullet) - (cram-bullet-reasoning-belief-state:update-bullet-transforms) - (cram-tf:start-publishing-transforms cram-tf:*broadcaster*)) - :shutdown (progn - (setf *last-timeline* cram-bullet-reasoning:*current-timeline*) - (cram-tf:stop-publishing-transforms cram-tf:*broadcaster*))) - - -(def-fact-group pr2-available-pms (cpm:available-process-module - cpm:projection-running) - - (<- (cpm:available-process-module ?pm) - (bound ?pm) - (once (member ?pm (pr2-proj-navigation pr2-proj-torso pr2-proj-ptu pr2-proj-perception - pr2-proj-grippers pr2-proj-arms btr-belief:world-state-detecting-pm))) - (symbol-value cram-projection:*projection-environment* pr2-bullet-projection-environment)) - - (<- (cpm::projection-running ?pm) - ;; (bound ?pm) - (once (member ?pm (pr2-proj-navigation pr2-proj-torso pr2-proj-ptu pr2-proj-perception - pr2-proj-grippers pr2-proj-arms btr-belief:world-state-detecting-pm))) - (symbol-value cram-projection:*projection-environment* pr2-bullet-projection-environment))) - - -(defmacro with-simulated-robot (&body body) - `(let ((results - (proj:with-projection-environment pr2-bullet-projection-environment - (cpl-impl::named-top-level (:name :top-level) - ,@body)))) - (car (cram-projection::projection-environment-result-result results)))) - -(defmacro with-projected-robot (&rest args) - "Alias for WITH-SIMULATED-ROBOT." - `(with-simulated-robot ,@args)) - - - - -#+below-is-a-very-simple-example-of-how-to-use-projection -( - (let ((robot (cl-urdf:parse-urdf (roslisp:get-param "robot_description"))) - (kitchen (cl-urdf:parse-urdf (roslisp:get-param "kitchen_description")))) - (prolog:prolog `(and - (btr:bullet-world ?w) - (btr:debug-window ?w) - (assert ?w (btr:object :static-plane floor ((0 0 0) (0 0 0 1)) - :normal (0 0 1) :constant 0)) - (assert ?w (btr:object :semantic-map sem-map ((0 0 0) (0 0 0 1)) - :urdf ,kitchen)) - (cram-robot-interfaces:robot ?robot) - (assert ?w (btr:object :urdf ?robot ((0 0 0) (0 0 0 1)) - :urdf ,robot))))) - - (ros-load-manifest:load-system "cram_executive" :cram-executive) - - (proj:with-projection-environment pr2-proj::pr2-bullet-projection-environment - (cpl:top-level - (exe:perform - (let ((?pose (cl-tf:make-pose-stamped - cram-tf:*robot-base-frame* 0.0 - (cl-transforms:make-3d-vector -4 -5 0) - (cl-transforms:make-identity-rotation)))) - (desig:a motion (type going) (pose ?pose)))) - (exe:perform - (let ((?pose (cl-tf:make-pose-stamped - cram-tf:*robot-base-frame* 0.0 - (cl-transforms:make-3d-vector 0.5 0.3 1.0) - (cl-transforms:make-identity-rotation)))) - (desig:a motion (type moving-tcp) (left-pose ?pose)))))) -) diff --git a/cram_pr2/cram_pr2_projection/src/tf.lisp b/cram_pr2/cram_pr2_projection/src/tf.lisp deleted file mode 100644 index ee6e6ca503..0000000000 --- a/cram_pr2/cram_pr2_projection/src/tf.lisp +++ /dev/null @@ -1,43 +0,0 @@ -;;; Copyright (c) 2012, Lorenz Moesenlechner -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software -;;; without specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :pr2-proj) - -(defmethod cram-occasions-events:on-event - update-tf ((event cram-plan-occasions-events:robot-state-changed)) - (when (eql cram-projection:*projection-environment* - 'pr2-bullet-projection-environment) - (cram-bullet-reasoning-belief-state:set-tf-from-bullet))) - -(defmethod cram-robot-interfaces:compute-iks - :before (pose-stamped &key link-name arm robot-state seed-state - pose-stamped-frame tcp-in-ee-pose) - (declare (ignore pose-stamped link-name arm robot-state seed-state - pose-stamped-frame tcp-in-ee-pose)) - (cram-bullet-reasoning-belief-state:set-tf-from-bullet)) - diff --git a/cram_pr2/cram_pr2_shopping_demo/launch/world.launch b/cram_pr2/cram_pr2_shopping_demo/launch/world.launch deleted file mode 100644 index d804c31a0d..0000000000 --- a/cram_pr2/cram_pr2_shopping_demo/launch/world.launch +++ /dev/null @@ -1,53 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/cram_pr2/cram_pr2_shopping_demo/src/grasping.lisp b/cram_pr2/cram_pr2_shopping_demo/src/grasping.lisp deleted file mode 100644 index 9d7a1d6098..0000000000 --- a/cram_pr2/cram_pr2_shopping_demo/src/grasping.lisp +++ /dev/null @@ -1,80 +0,0 @@ -;;; -;;; Copyright (c) 2019, Jonas Dech -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Institute for Artificial Intelligence / -;;; University of Bremen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software -;;; without specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :cram-pr2-shopping-demo) - -(defparameter *lift-z-offset* 0.05 "in meters") -(defparameter *default-lift-offsets* `(0 0 ,*lift-z-offset*)) - -(defmethod man-int:get-action-gripping-effort :heuristics 20 ((object-type (eql :denkmit))) 50) -(defmethod man-int:get-action-gripping-effort :heuristics 20 ((object-type (eql :dove))) 50) -(defmethod man-int:get-action-gripping-effort :heuristics 20 ((object-type (eql :heitmann))) 50) -(defmethod man-int:get-action-gripping-effort :heuristics 20 ((object-type (eql :somat))) 50) - -(defmethod man-int:get-action-gripper-opening :heuristics 20 ((object-type (eql :denkmit))) 0.1) -(defmethod man-int:get-action-gripper-opening :heuristics 20 ((object-type (eql :dove))) 0.1) -(defmethod man-int:get-action-gripper-opening :heuristics 20 ((object-type (eql :heitmann))) 0.1) -(defmethod man-int:get-action-gripper-opening :heuristics 20 ((object-type (eql :somat))) 0.1) - -(defparameter *denkmit-pregrasp-xy-offste* 0.00 "in meters") -(defparameter *denkmit-grasp-xy-offset* 0.00 "in meters") -(defparameter *denkmit-grasp-z-offset* 0.00 "in meters") - -(man-int:def-object-type-to-gripper-transforms :denkmit '(:left :right) :left-side - :grasp-translation `(0.0d0 ,*denkmit-grasp-xy-offset* ,*denkmit-grasp-z-offset*) - :grasp-rot-matrix man-int:*y-across-z-grasp-rotation* - :pregrasp-offsets `(0.0 ,*denkmit-pregrasp-xy-offste* ,*lift-z-offset*) - :2nd-pregrasp-offsets `(0.0 ,*denkmit-pregrasp-xy-offste* 0.0) - :lift-offsets *default-lift-offsets* - :2nd-lift-offsets *default-lift-offsets*) - -(man-int:def-object-type-to-gripper-transforms :dove '(:left :right) :left-side - :grasp-translation `(0.0d0 ,*denkmit-grasp-xy-offset* ,*denkmit-grasp-z-offset*) - :grasp-rot-matrix man-int:*y-across-z-grasp-rotation* - :pregrasp-offsets `(0.0 ,*denkmit-pregrasp-xy-offste* ,*lift-z-offset*) - :2nd-pregrasp-offsets `(0.0 ,*denkmit-pregrasp-xy-offste* 0.0) - :lift-offsets *default-lift-offsets* - :2nd-lift-offsets *default-lift-offsets*) - -(man-int:def-object-type-to-gripper-transforms :heitmann '(:left :right) :left-side - :grasp-translation `(0.0d0 ,*denkmit-grasp-xy-offset* ,*denkmit-grasp-z-offset*) - :grasp-rot-matrix man-int:*y-across-z-grasp-rotation* - :pregrasp-offsets `(0.0 ,*denkmit-pregrasp-xy-offste* ,*lift-z-offset*) - :2nd-pregrasp-offsets `(0.0 ,*denkmit-pregrasp-xy-offste* 0.0) - :lift-offsets *default-lift-offsets* - :2nd-lift-offsets *default-lift-offsets*) - -(man-int:def-object-type-to-gripper-transforms :somat '(:left :right) :left-side - :grasp-translation `(0.0d0 ,*denkmit-grasp-xy-offset* ,*denkmit-grasp-z-offset*) - :grasp-rot-matrix man-int:*y-across-z-grasp-rotation* - :pregrasp-offsets `(0.0 ,*denkmit-pregrasp-xy-offste* ,*lift-z-offset*) - :2nd-pregrasp-offsets `(0.0 ,*denkmit-pregrasp-xy-offste* 0.0) - :lift-offsets *default-lift-offsets* - :2nd-lift-offsets *default-lift-offsets*) - diff --git a/cram_pr2/cram_pr2_shopping_demo/src/plans.lisp b/cram_pr2/cram_pr2_shopping_demo/src/plans.lisp deleted file mode 100644 index f3a2c622e6..0000000000 --- a/cram_pr2/cram_pr2_shopping_demo/src/plans.lisp +++ /dev/null @@ -1,195 +0,0 @@ -;;; -;;; Copyright (c) 2019, Jonas Dech quaternion - (cl-transforms:make-3d-vector 0 0 1) (/ pi -2)))) - -(defparameter *pose-grasping-left* (cl-transforms-stamped:make-pose-stamped - "map" 0.0 - (cl-transforms:make-3d-vector -1 -0.35 0) - (cl-transforms:axis-angle->quaternion - (cl-transforms:make-3d-vector 0 0 1) (/ pi -2)))) - -(defparameter *pose-grasping-right* (cl-transforms-stamped:make-pose-stamped - "map" 0.0 - (cl-transforms:make-3d-vector -2 -0.35 0) - (cl-transforms:axis-angle->quaternion - (cl-transforms:make-3d-vector 0 0 1) (/ pi -2)))) - - -(defparameter *pose-near-table* (cl-transforms-stamped:make-pose-stamped - "map" 0.0 - (cl-transforms:make-3d-vector -2.45 0.5 0) - (cl-transforms:axis-angle->quaternion - (cl-transforms:make-3d-vector 0 0 1) (/ pi 1)))) - -(defparameter *looking-pose-mid* (cl-transforms-stamped:make-pose-stamped - "map" 0.0 - (cl-transforms:make-3d-vector -1.5 -1.05 1.15) - (cl-transforms:make-identity-rotation))) - -(defparameter *pose-detecting* (cl-transforms-stamped:make-pose-stamped - "map" 0.0 - (cl-transforms:make-3d-vector -1.5 1 0) - (cl-transforms:axis-angle->quaternion - (cl-transforms:make-3d-vector 0 0 1) (/ pi -2)))) - -(defun move-object (?object ?destination) - (let ((?grasping-arm :right) - (?grasp-pose *pose-grasping*) - (?grasp-pose-left *pose-grasping-left*) - (?grasp-pose-right *pose-grasping-right*) - (?pose-near-table *pose-near-table*) - ?newobject - ?newtransform) - - (exe:perform - (desig:a motion - (type moving-torso) - (joint-angle 0))) - - (exe:perform - (desig:an action - (type going) - (target (desig:a location - (pose ?grasp-pose))))) - - (exe:perform - (desig:an action - (type positioning-arm) - (left-configuration park) - (right-configuration park))) - - (setf ?newobject (exe:perform - (desig:a motion - (type world-state-detecting) - (object ?object)))) - - - (setf ?newtransform (man-int:get-object-transform ?newobject)) - - ;; selecting the grasping arm - (if (< (cl-transforms:y (cl-transforms:translation ?newtransform)) 0) - (setf ?grasping-arm :right) - (setf ?grasping-arm :left)) - - ;; if the object is to far left move to the left - (when (> (cl-transforms:y (cl-transforms:translation ?newtransform)) 0.8) - (setf ?grasping-arm :left) - (exe:perform (desig:a action - (type going) - (target (desig:a location - (pose ?grasp-pose-left)))))) - ;; if it is to far on the right move to the right - (when (< (cl-transforms:y (cl-transforms:translation ?newtransform)) -0.8) - (setf ?grasping-arm :right) - (exe:perform (desig:a action - (type going) - (target (desig:a location - (pose ?grasp-pose-right)))))) - - (print ?grasping-arm) - - (exe:perform (desig:an action - (type picking-up) - (arm ?grasping-arm) - (grasp left-side) - (object ?newobject))) - - (exe:perform (desig:an action - (type going) - (target (desig:a location - (pose ?pose-near-table))))) - - ;; If the object was on the top shelf and the torso was lifted - (exe:perform (desig:a motion - (type moving-torso) - (joint-angle 0))) - - (exe:perform (desig:an action - (type placing) - (arm ?grasping-arm) - (object ?object) - (target (desig:a location - (pose ?destination))))))) -(defun collect-article () - (urdf-proj:with-simulated-robot - (let ((objects '(:heitmann :dove :denkmit)) - (y 0.2) - object-desigs - destination) - (setf object-desigs (try-detecting objects)) - (loop for ?object in object-desigs - do (setf destination (cl-transforms-stamped:make-pose-stamped - "map" 0 - (cl-transforms:make-3d-vector -3.1 y 0.75) - (cl-transforms:make-identity-rotation))) - (move-object ?object destination) - (btr:simulate btr:*current-bullet-world* 100) - (setf y (+ y 0.15)))))) - -(defun try-detecting (articles) - (let ((?pose-detecting *pose-detecting*) - (?percived-objects '()) - (?pose-grasping *pose-grasping*)) - - (exe:perform (desig:an action - (type going) - (target (desig:a location - (pose ?pose-detecting))))) - - (exe:perform (desig:a motion - (type moving-torso) - (joint-angle 0))) - - ;; Tries to detect every object in articles - (loop for ?article in articles - do (push - (exe:perform (desig:a motion - (type detecting) - (object (desig:an object - (type ?article))))) - ?percived-objects)) - - (exe:perform (desig:an action - (type going) - (target (desig:a location - (pose ?pose-grasping))))) - - ?percived-objects)) diff --git a/cram_pr2/cram_pr2_cloud/CATKIN_IGNORE b/cram_pr2/cram_pr2_sim_process_modules/CATKIN_IGNORE similarity index 100% rename from cram_pr2/cram_pr2_cloud/CATKIN_IGNORE rename to cram_pr2/cram_pr2_sim_process_modules/CATKIN_IGNORE diff --git a/cram_pr2/cram_pr2_sim_process_modules/CMakeLists.txt b/cram_pr2/cram_pr2_sim_process_modules/CMakeLists.txt new file mode 100644 index 0000000000..6095548678 --- /dev/null +++ b/cram_pr2/cram_pr2_sim_process_modules/CMakeLists.txt @@ -0,0 +1,5 @@ +cmake_minimum_required(VERSION 2.8.3) +project(cram_pr2_sim_process_modules) +find_package(catkin REQUIRED) +catkin_package() + diff --git a/cram_pr2/cram_pr2_arm_kinematics/cram-pr2-arm-kinematics.asd b/cram_pr2/cram_pr2_sim_process_modules/cram-pr2-sim-process-modules.asd similarity index 80% rename from cram_pr2/cram_pr2_arm_kinematics/cram-pr2-arm-kinematics.asd rename to cram_pr2/cram_pr2_sim_process_modules/cram-pr2-sim-process-modules.asd index d05184bf35..a5478672f8 100644 --- a/cram_pr2/cram_pr2_arm_kinematics/cram-pr2-arm-kinematics.asd +++ b/cram_pr2/cram_pr2_sim_process_modules/cram-pr2-sim-process-modules.asd @@ -26,25 +26,25 @@ ;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE ;;; POSSIBILITY OF SUCH DAMAGE. -(defsystem cram-pr2-arm-kinematics +(defsystem cram-pr2-sim-process-modules :author "Gayane Kazhoyan" :maintainer "Gayane Kazhoyan" :license "BSD" - :depends-on (cram-robot-interfaces - cram-pr2-description - cram-tf - cl-transforms-stamped - cl-transforms - moveit_msgs-srv - moveit_msgs-msg + :depends-on (cram-process-modules cram-prolog - cram-utilities - roslisp) + cram-designators + cram-tf + cram-common-failures + cram-common-designators + cram-language ; for with-real-robot + cram-giskard + cram-urdf-projection) :components ((:module "src" :components ((:file "package") - (:file "ik" :depends-on ("package")) - (:file "fk" :depends-on ("package" "ik")))))) + (:file "giskard" :depends-on ("package")) + (:file "perception" :depends-on ("package")) + (:file "with-real-robot" :depends-on ("package" "giskard" "perception")))))) diff --git a/cram_boxy/cram_boxy_plans/package.xml b/cram_pr2/cram_pr2_sim_process_modules/package.xml similarity index 50% rename from cram_boxy/cram_boxy_plans/package.xml rename to cram_pr2/cram_pr2_sim_process_modules/package.xml index 919ef000bc..022102e759 100644 --- a/cram_boxy/cram_boxy_plans/package.xml +++ b/cram_pr2/cram_pr2_sim_process_modules/package.xml @@ -1,8 +1,8 @@ - cram_boxy_plans + cram_pr2_sim_process_modules 0.7.0 - CRAM plans for Boxy + cram_pr2_process_modules Gayane Kazhoyan Gayane Kazhoyan @@ -10,17 +10,13 @@ catkin - roslisp - cram_designators - cram_executive - cram_language + cram_process_modules cram_prolog - cram_occasions_events - cram_designator_specification + cram_designators + cram_tf cram_common_failures - cram_plan_occasions_events - cram_manipulation_interfaces - cram_object_knowledge - cl_transforms_stamped - cl_transforms + cram_common_designators + cram_language + cram_giskard + cram_urdf_projection diff --git a/cram_pr2/cram_pr2_sim_process_modules/src/giskard.lisp b/cram_pr2/cram_pr2_sim_process_modules/src/giskard.lisp new file mode 100644 index 0000000000..ceeb67ecc9 --- /dev/null +++ b/cram_pr2/cram_pr2_sim_process_modules/src/giskard.lisp @@ -0,0 +1,49 @@ +;;; +;;; Copyright (c) 2016, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :pr2-sim-pms) + +(prolog:def-fact-group giskard-pm (cpm:matching-process-module + cpm:available-process-module) + + (prolog:<- (cpm:matching-process-module ?motion-designator giskard:giskard-pm) + (or (desig:desig-prop ?motion-designator (:type :moving-tcp)) + (desig:desig-prop ?motion-designator (:type :moving-arm-joints)) + (desig:desig-prop ?motion-designator (:type :pulling)) + (desig:desig-prop ?motion-designator (:type :pushing)) + (desig:desig-prop ?motion-designator (:type :going)) + (desig:desig-prop ?motion-designator (:type :moving-torso)) + (desig:desig-prop ?motion-designator (:type :looking)) + (desig:desig-prop ?motion-designator (:type :gripping)) + (desig:desig-prop ?motion-designator (:type :opening-gripper)) + (desig:desig-prop ?motion-designator (:type :closing-gripper)) + (desig:desig-prop ?motion-designator (:type :moving-gripper-joint)))) + + (prolog:<- (cpm:available-process-module giskard:giskard-pm) + (prolog:not (cpm:projection-running ?_)))) diff --git a/cram_pr2/cram_pr2_sim_process_modules/src/package.lisp b/cram_pr2/cram_pr2_sim_process_modules/src/package.lisp new file mode 100644 index 0000000000..612bde0948 --- /dev/null +++ b/cram_pr2/cram_pr2_sim_process_modules/src/package.lisp @@ -0,0 +1,37 @@ +;;; +;;; Copyright (c) 2016, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :cl-user) + +(defpackage cram-pr2-sim-process-modules + (:nicknames :pr2-sim-pms) + (:use #:common-lisp #:cram-process-modules #:cram-prolog #:cram-designators) + (:export + ;; with-real-robot + #:with-real-robot)) diff --git a/cram_pr2/cram_pr2_sim_process_modules/src/perception.lisp b/cram_pr2/cram_pr2_sim_process_modules/src/perception.lisp new file mode 100644 index 0000000000..48e025b66a --- /dev/null +++ b/cram_pr2/cram_pr2_sim_process_modules/src/perception.lisp @@ -0,0 +1,49 @@ +;;; +;;; Copyright (c) 2020, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :pr2-sim-pms) + +(defun perceive (input-object-designator) + (urdf-proj::detect input-object-designator)) + +(cpm:def-process-module bullet-perception-pm (motion-designator) + (destructuring-bind (command argument-1) + (desig:reference motion-designator) + (ecase command + (cram-common-designators:detect + (perceive argument-1))))) + +(prolog:def-fact-group bullet-perception-pm (cpm:matching-process-module + cpm:available-process-module) + + (prolog:<- (cpm:matching-process-module ?motion-designator bullet-perception-pm) + (desig:desig-prop ?motion-designator (:type :detecting))) + + (prolog:<- (cpm:available-process-module bullet-perception-pm) + (prolog:not (cpm:projection-running ?_)))) diff --git a/cram_pr2/cram_pr2_sim_process_modules/src/with-real-robot.lisp b/cram_pr2/cram_pr2_sim_process_modules/src/with-real-robot.lisp new file mode 100644 index 0000000000..099feac250 --- /dev/null +++ b/cram_pr2/cram_pr2_sim_process_modules/src/with-real-robot.lisp @@ -0,0 +1,36 @@ +;;; +;;; Copyright (c) 2018, Gayane Kazhoyan +;;; All rights reserved. +;;; +;;; Redistribution and use in source and binary forms, with or without +;;; modification, are permitted provided that the following conditions are met: +;;; +;;; * Redistributions of source code must retain the above copyright +;;; notice, this list of conditions and the following disclaimer. +;;; * Redistributions in binary form must reproduce the above copyright +;;; notice, this list of conditions and the following disclaimer in the +;;; documentation and/or other materials provided with the distribution. +;;; * Neither the name of the Institute for Artificial Intelligence/ +;;; Universitaet Bremen nor the names of its contributors may be used to +;;; endorse or promote products derived from this software without +;;; specific prior written permission. +;;; +;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" +;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE +;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE +;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE +;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR +;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF +;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS +;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN +;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) +;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +;;; POSSIBILITY OF SUCH DAMAGE. + +(in-package :pr2-sim-pms) + +(defmacro with-real-robot (&body body) + `(cram-process-modules:with-process-modules-running + (giskard:giskard-pm bullet-perception-pm) + (cpl-impl::named-top-level (:name :top-level) + ,@body))) diff --git a/cram_pr2/cram_urdf_bringup/resource/blue_metal_plate.stl b/cram_pr2/cram_urdf_bringup/resource/blue_metal_plate.stl deleted file mode 100644 index 837155ce90..0000000000 Binary files a/cram_pr2/cram_urdf_bringup/resource/blue_metal_plate.stl and /dev/null differ diff --git a/cram_pr2/cram_urdf_bringup/resource/cup.dae b/cram_pr2/cram_urdf_bringup/resource/cup.dae deleted file mode 100644 index babfc1ecea..0000000000 --- a/cram_pr2/cram_urdf_bringup/resource/cup.dae +++ /dev/null @@ -1,1116 +0,0 @@ - - - - - Blender User - Blender 2.77.0 commit date:2016-04-05, commit time:18:12, hash:abf6f08 - - 2016-08-18T17:41:16 - 2016-08-18T17:41:16 - - Z_UP - - - - - - - 49.13434 - 1.777778 - 0.1 - 100 - - - - - - 0 - 0 - 0 - - - - - - - - 49.13434 - 1.777778 - 0.1 - 100 - - - - - - 0 - 0 - 0 - - - - - - - - 49.13434 - 1.777778 - 0.1 - 100 - - - - - - 0 - 0 - 0 - - - - - - - - 49.13434 - 1.777778 - 0.1 - 100 - - - - - - 0 - 0 - 0 - - - - - - - - 49.13434 - 1.777778 - 0.1 - 100 - - - - - - 0 - 0 - 0 - - - - - - - - 49.13434 - 1.777778 - 0.1 - 100 - - - - - - 0 - 0 - 0 - - - - - - - - - 1 1 1 - 1 - 0 - 0.00111109 - - - - - 0.000999987 - 1 - 0.1 - 0.1 - 1 - 1 - 1 - 2 - 0 - 1 - 1 - 1 - 1 - 1 - 0 - 2880 - 2 - 30.002 - 1.000799 - 0.04999995 - 29.99998 - 1 - 2 - 0 - 0 - 1 - 1 - 1 - 1 - 8192 - 1 - 1 - 0 - 1 - 1 - 1 - 3 - 0 - 0 - 0 - 0 - 0 - 1 - 1 - 1 - 3 - 0.15 - 75 - 1 - 1 - 0 - 1 - 1 - 0 - - - - - - - 1 1 1 - 1 - 0 - 0.00111109 - - - - - 9.99987e-4 - 1 - 0.1 - 0.1 - 1 - 1 - 1 - 2 - 0 - 1 - 1 - 1 - 1 - 1 - 0 - 2880 - 2 - 30.002 - 1.000799 - 0.04999995 - 29.99998 - 1 - 2 - 0 - 0 - 1 - 1 - 1 - 1 - 8192 - 1 - 1 - 0 - 1 - 1 - 1 - 3 - 0 - 0 - 0 - 0 - 0 - 1 - 1 - 1 - 3 - 0.15 - 75 - 1 - 1 - 0 - 1 - 1 - 0 - - - - - - - 1 1 1 - 1 - 0 - 0.00111109 - - - - - 9.99987e-4 - 1 - 0.1 - 0.1 - 1 - 1 - 1 - 2 - 0 - 1 - 1 - 1 - 1 - 1 - 0 - 2880 - 2 - 30.002 - 1.000799 - 0.04999995 - 29.99998 - 1 - 2 - 0 - 0 - 1 - 1 - 1 - 1 - 8192 - 1 - 1 - 0 - 1 - 1 - 1 - 3 - 0 - 0 - 0 - 0 - 0 - 1 - 1 - 1 - 3 - 0.15 - 75 - 1 - 1 - 0 - 1 - 1 - 0 - - - - - - - 1 1 1 - 1 - 0 - 0.00111109 - - - - - 9.99987e-4 - 1 - 0.1 - 0.1 - 1 - 1 - 1 - 2 - 0 - 1 - 1 - 1 - 1 - 1 - 0 - 2880 - 2 - 30.002 - 1.000799 - 0.04999995 - 29.99998 - 1 - 2 - 0 - 0 - 1 - 1 - 1 - 1 - 8192 - 1 - 1 - 0 - 1 - 1 - 1 - 3 - 0 - 0 - 0 - 0 - 0 - 1 - 1 - 1 - 3 - 0.15 - 75 - 1 - 1 - 0 - 1 - 1 - 0 - - - - - - - 1 1 1 - - - - - 9.99987e-4 - 0 - 0.1 - 0.1 - 0.1 - 1 - 1 - 2 - 0 - 1 - 1 - 1 - 1 - 1 - 0 - 512 - 2 - 40 - 0.5 - 0.04999995 - 25 - 1 - 2 - 0 - 0 - 1 - 1 - 1 - 1 - 1 - 1 - 1 - 0 - 1 - 1 - 1 - 3 - 0 - 0 - 0 - 0 - 2 - 1 - 1 - 1 - 3 - 0.15 - 45 - 1 - 1 - 0 - 1 - 1 - 3 - - - - - - - 1 1 1 - 1 - 0 - 0.00111109 - - - - - 9.99987e-4 - 1 - 0.1 - 0.1 - 1 - 1 - 1 - 2 - 0 - 1 - 1 - 1 - 1 - 1 - 0 - 2880 - 2 - 30.002 - 1.000799 - 0.04999995 - 29.99998 - 1 - 2 - 0 - 0 - 1 - 1 - 1 - 1 - 8192 - 1 - 1 - 0 - 1 - 1 - 1 - 3 - 0 - 0 - 0 - 0 - 0 - 1 - 1 - 1 - 3 - 0.15 - 75 - 1 - 1 - 0 - 1 - 1 - 0 - - - - - - - 1 1 1 - 1 - 0 - 0.00111109 - - - - - 9.99987e-4 - 1 - 0.1 - 0.1 - 1 - 1 - 1 - 2 - 0 - 1 - 1 - 1 - 1 - 1 - 0 - 2880 - 2 - 30.002 - 1.000799 - 0.04999995 - 29.99998 - 1 - 2 - 0 - 0 - 1 - 1 - 1 - 1 - 8192 - 1 - 1 - 0 - 1 - 1 - 1 - 3 - 0 - 0 - 0 - 0 - 0 - 1 - 1 - 1 - 3 - 0.15 - 75 - 1 - 1 - 0 - 1 - 1 - 0 - - - - - - - 1 1 1 - 1 - 0 - 0.00111109 - - - - - 9.99987e-4 - 1 - 0.1 - 0.1 - 1 - 1 - 1 - 2 - 0 - 1 - 1 - 1 - 1 - 1 - 0 - 2880 - 2 - 30.002 - 1.000799 - 0.04999995 - 29.99998 - 1 - 2 - 0 - 0 - 1 - 1 - 1 - 1 - 8192 - 1 - 1 - 0 - 1 - 1 - 1 - 3 - 0 - 0 - 0 - 0 - 0 - 1 - 1 - 1 - 3 - 0.15 - 75 - 1 - 1 - 0 - 1 - 1 - 0 - - - - - - - 1 1 1 - 1 - 0 - 0.00111109 - - - - - 9.99987e-4 - 1 - 0.1 - 0.1 - 1 - 1 - 1 - 2 - 0 - 1 - 1 - 1 - 1 - 1 - 0 - 2880 - 2 - 30.002 - 1.000799 - 0.04999995 - 29.99998 - 1 - 2 - 0 - 0 - 1 - 1 - 1 - 1 - 8192 - 1 - 1 - 0 - 1 - 1 - 1 - 3 - 0 - 0 - 0 - 0 - 0 - 1 - 1 - 1 - 3 - 0.15 - 75 - 1 - 1 - 0 - 1 - 1 - 0 - - - - - - - 1 1 1 - - - - - 9.99987e-4 - 0 - 0.1 - 0.1 - 0.1 - 1 - 1 - 2 - 0 - 1 - 1 - 1 - 1 - 1 - 0 - 512 - 2 - 40 - 0.5 - 0.04999995 - 25 - 1 - 2 - 0 - 0 - 1 - 1 - 1 - 1 - 1 - 1 - 1 - 0 - 1 - 1 - 1 - 3 - 0 - 0 - 0 - 0 - 2 - 1 - 1 - 1 - 3 - 0.15 - 45 - 1 - 1 - 0 - 1 - 1 - 3 - - - - - - - 1 1 1 - 1 - 0 - 0.00111109 - - - - - 9.99987e-4 - 1 - 0.1 - 0.1 - 1 - 1 - 1 - 2 - 0 - 1 - 1 - 1 - 1 - 1 - 0 - 2880 - 2 - 30.002 - 1.000799 - 0.04999995 - 29.99998 - 1 - 2 - 0 - 0 - 1 - 1 - 1 - 1 - 8192 - 1 - 1 - 0 - 1 - 1 - 1 - 3 - 0 - 0 - 0 - 0 - 0 - 1 - 1 - 1 - 3 - 0.15 - 75 - 1 - 1 - 0 - 1 - 1 - 0 - - - - - - - 1 1 1 - 1 - 0 - 0.00111109 - - - - - 9.99987e-4 - 1 - 0.1 - 0.1 - 1 - 1 - 1 - 2 - 0 - 1 - 1 - 1 - 1 - 1 - 0 - 2880 - 2 - 30.002 - 1.000799 - 0.04999995 - 29.99998 - 1 - 2 - 0 - 0 - 1 - 1 - 1 - 1 - 8192 - 1 - 1 - 0 - 1 - 1 - 1 - 3 - 0 - 0 - 0 - 0 - 0 - 1 - 1 - 1 - 3 - 0.15 - 75 - 1 - 1 - 0 - 1 - 1 - 0 - - - - - - - - - - - - 0 0 0 1 - - - 0 0 0 1 - - - 0.8 0.8 0.8 1 - - - 0.125 0.125 0.125 1 - - - 50 - - - 1 - - - - - - - - - - - - - - - - 0 0.03052425 -0.04993474 -0.01526206 0.0264346 -0.04993474 -0.02643471 0.01526188 -0.04993474 -0.03052437 -1.34419e-7 -0.04993474 -0.02643471 -0.01526218 -0.04993474 -0.01526206 -0.02643489 -0.04993474 0 -0.03052449 -0.04993474 0.01526206 -0.02643489 -0.04993474 0.02643471 -0.01526218 -0.04993474 0.03052437 -1.47276e-7 -0.04993474 0.02643477 0.01526188 -0.04993474 0.01526206 0.0264346 -0.04993474 0 0.03979593 0.03528404 -0.01989787 0.03446424 0.03528404 -0.03446429 0.01989775 0.03528404 -0.03979605 -1.33428e-7 0.03528404 -0.03446429 -0.01989817 0.03528404 -0.01989787 -0.03446441 0.03528404 0 -0.03979617 0.03528404 0.01989787 -0.03446441 0.03528404 0.03446429 -0.01989817 0.03528404 0.03979605 -1.50191e-7 0.03528404 0.03446429 0.01989775 0.03528404 0.01989793 0.03446424 0.03528404 0 0.03690409 0.03528404 -0.01845204 0.03195995 0.03528404 -0.03196007 0.01845192 0.03528404 -0.03690433 -1.33749e-7 0.03528404 -0.03196007 -0.01845216 0.03528404 -0.01845204 -0.03196012 0.03528404 0 -0.03690451 0.03528404 0.01845204 -0.03196012 0.03528404 0.03196007 -0.01845216 0.03528404 0.03690433 -1.49293e-7 0.03528404 0.03196007 0.01845192 0.03528404 0.0184521 0.03195995 0.03528404 0 0.02492946 -0.04787296 -0.01246476 0.02158939 -0.04787296 -0.02158951 0.01246464 -0.04787296 -0.02492958 -1.35176e-7 -0.04787296 -0.02158951 -0.01246494 -0.04787296 -0.01246476 -0.02158981 -0.04787296 0 -0.02492976 -0.04787296 0.01246482 -0.02158981 -0.04787296 0.02158969 -0.01246494 -0.04787296 0.02492964 -1.45676e-7 -0.04787296 0.02158969 0.01246464 -0.04787296 0.01246482 0.02158939 -0.04787296 0 0.002662241 -0.04787302 -0.001331031 0.002305448 -0.04787302 -0.002305686 0.001331031 -0.04787302 -0.002662301 -1.3769e-7 -0.04787302 -0.002305686 -0.001331329 -0.04787302 -0.001331031 -0.002305746 -0.04787302 0 -0.00266242 -0.04787302 0.001331031 -0.002305746 -0.04787302 0.002305686 -0.001331329 -0.04787302 0.002662301 -1.38812e-7 -0.04787302 0.002305686 0.001331031 -0.04787302 0.001331031 0.002305448 -0.04787302 0 -1.37836e-7 -0.04787302 0.003930926 0.002269268 -0.04993474 0.004538953 -1.38579e-7 -0.04993474 0.003930926 -0.002269566 -0.04993474 0.002269506 -0.003931045 -0.04993474 0 -0.004539132 -0.04993474 -0.002269506 -0.003931045 -0.04993474 -0.003930807 -0.002269566 -0.04993474 -0.004538953 -1.36667e-7 -0.04993474 -0.003930807 0.002269268 -0.04993474 -0.002269506 0.003930747 -0.04993474 0 0.004538834 -0.04993474 0.002269506 0.003930747 -0.04993474 0 -1.37292e-7 -0.04993474 -0.03237867 -1.34221e-7 -0.03289097 -0.03423303 -1.34023e-7 -0.0158472 -0.03608739 -1.33825e-7 0.001196444 -0.03794169 -1.33627e-7 0.01824027 -0.03285849 -0.01897096 0.01824027 -0.03125256 -0.01804381 0.001196444 -0.02964669 -0.01711666 -0.0158472 -0.02804064 -0.01618945 -0.03289097 0.02804064 0.01618909 -0.03289097 0.02964669 0.01711624 -0.0158472 0.03125262 0.01804339 0.001196444 0.03285849 0.0189706 0.01824027 0.01897078 0.03285831 0.01824027 0.01804357 0.03125244 0.001196444 0.01711642 0.02964651 -0.0158472 0.01618921 0.02804046 -0.03289097 0 0.03237855 -0.03289097 0 0.03423291 -0.0158472 0 0.03608727 0.001196444 0 0.03794157 0.01824027 -0.01897072 0.03285837 0.01824027 -0.01804357 0.03125244 0.001196444 -0.01711636 0.02964651 -0.0158472 -0.01618921 0.02804052 -0.03289097 0.01618921 -0.02804088 -0.03289097 0.01711636 -0.02964681 -0.0158472 0.01804357 -0.03125268 0.001196444 0.01897072 -0.03285861 0.01824027 0.03285849 -0.01897096 0.01824027 0.03125256 -0.01804381 0.001196444 0.02964669 -0.01711666 -0.0158472 0.02804064 -0.01618945 -0.03289097 -0.01897072 -0.03285861 0.01824027 -0.01804357 -0.03125268 0.001196444 -0.01711636 -0.02964681 -0.0158472 -0.01618921 -0.02804088 -0.03289097 -0.03285849 0.0189706 0.01824027 -0.03125256 0.01804339 0.001196444 -0.02964669 0.01711624 -0.0158472 -0.02804064 0.01618909 -0.03289097 0.03794169 -1.49608e-7 0.01824027 0.03608739 -1.49025e-7 0.001196444 0.03423303 -1.48442e-7 -0.0158472 0.03237867 -1.47859e-7 -0.03289097 0 -0.03794187 0.01824027 0 -0.03608751 0.001196444 0 -0.03423315 -0.0158472 0 -0.03237885 -0.03289097 0.01725471 0.02988576 0.01865249 0.01605725 0.02781176 0.002021193 0.01485967 0.0257377 -0.01461017 0.01366215 0.02366358 -0.03124159 0 0.02732431 -0.03124159 0 0.02971935 -0.01461017 0 0.0321142 0.002021193 0 0.0345093 0.01865249 -0.01725471 0.02988576 0.01865249 -0.01605719 0.02781182 0.002021193 -0.01485961 0.0257377 -0.01461017 -0.01366215 0.02366364 -0.03124159 -0.02366364 0.01366204 -0.03124159 -0.02573782 0.01485949 -0.01461017 -0.02781194 0.01605707 0.002021193 -0.02988588 0.01725459 0.01865249 0.02988588 -0.01725471 0.01865249 0.02781194 -0.01605737 0.002021193 0.02573782 -0.01485973 -0.01461017 0.02366364 -0.01366227 -0.03124159 0.02732443 -1.46399e-7 -0.03124159 0.02971953 -1.47123e-7 -0.01461017 0.03211432 -1.47846e-7 0.002021193 0.03450942 -1.4857e-7 0.01865249 -0.01725471 -0.02988612 0.01865249 -0.01605719 -0.02781206 0.002021193 -0.01485961 -0.025738 -0.01461017 -0.01366215 -0.02366375 -0.03124159 0 -0.02732467 -0.03124159 0 -0.02971965 -0.01461017 0 -0.03211462 0.002021193 0 -0.03450942 0.01865249 -0.02732443 -1.3489e-7 -0.03124159 -0.02971953 -1.34605e-7 -0.01461017 -0.03211432 -1.34319e-7 0.002021193 -0.03450942 -1.34034e-7 0.01865249 0.02366364 0.01366204 -0.03124159 0.02573788 0.01485949 -0.01461017 0.02781194 0.01605707 0.002021193 0.02988594 0.01725453 0.01865249 0.01366215 -0.02366375 -0.03124159 0.01485961 -0.025738 -0.01461017 0.01605719 -0.02781206 0.002021193 0.01725471 -0.02988612 0.01865249 -0.02366364 -0.01366227 -0.03124159 -0.02573782 -0.01485973 -0.01461017 -0.02781194 -0.01605737 0.002021193 -0.02988588 -0.01725471 0.01865249 0.02186256 -1.44377e-7 -0.04993474 0.0132007 -1.41478e-7 -0.04993474 -0.01893353 0.01093113 -0.04993474 -0.01143223 0.006600201 -0.04993474 -0.01093125 -0.01893365 -0.04993474 -0.00660032 -0.01143229 -0.04993474 0.00660032 -0.01143229 -0.04993474 0.01093125 -0.01893365 -0.04993474 0.01893353 -0.01093143 -0.04993474 0.01143223 -0.006600499 -0.04993474 0 0.01320064 -0.04993474 0 0.02186232 -0.04993474 -0.01093125 0.01893341 -0.04993474 -0.00660032 0.01143211 -0.04993474 0.01143223 0.006600201 -0.04993474 0.01893353 0.01093113 -0.04993474 0.01093131 0.01893341 -0.04993474 0.00660032 0.01143205 -0.04993474 -0.0132007 -1.35918e-7 -0.04993474 -0.02186256 -1.35168e-7 -0.04993474 -0.01893353 -0.01093143 -0.04993474 -0.01143223 -0.006600499 -0.04993474 0 -0.02186268 -0.04993474 0 -0.01320081 -0.04993474 -0.01516169 -0.008753716 -0.04787296 -0.008733689 -0.005042493 -0.04787296 -0.005042374 -0.008733808 -0.04787302 -0.008753597 -0.01516181 -0.04787296 0.008753597 0.01516151 -0.04787296 0.005042374 0.00873351 -0.04787296 0 0.0100845 -0.04787302 0 0.01750707 -0.04787296 -0.008753597 0.01516151 -0.04787296 -0.005042374 0.00873351 -0.04787296 -0.008733689 0.005042195 -0.04787302 -0.01516169 0.008753418 -0.04787296 0.01516169 -0.008753716 -0.04787296 0.008733689 -0.005042493 -0.04787296 0.01008468 -1.411e-7 -0.04787302 0.01750719 -1.43388e-7 -0.04787296 0 -0.0100848 -0.04787302 0 -0.01750731 -0.04787296 -0.01008462 -1.36852e-7 -0.04787302 -0.01750719 -1.36014e-7 -0.04787296 0.008733689 0.005042195 -0.04787302 0.01516169 0.008753418 -0.04787296 0.005042374 -0.008733808 -0.04787302 0.008753597 -0.01516181 -0.04787296 -0.01917511 0.03321212 0.03589069 -0.03321224 0.01917493 0.03589069 0.03321224 -0.01917523 0.03589069 0.03835022 -1.49742e-7 0.03589069 -0.01917511 -0.03321236 0.03589069 0 -0.03835034 0.03589069 -0.03835022 -1.33589e-7 0.03589069 0.03321224 0.01917493 0.03589069 0.01917511 -0.03321236 0.03589069 -0.03321224 -0.01917523 0.03589069 0.01917511 0.03321212 0.03589069 0 0.0383501 0.03589069 -0.03400576 0.01963311 0.03570884 0.03926634 -1.50029e-7 0.03570884 0 -0.03926646 0.03570884 -0.03926634 -1.3349e-7 0.03570884 0.03400576 0.01963305 0.03570884 0.01963323 -0.03400588 0.03570884 -0.03400576 -0.01963335 0.03570884 0.01963323 0.03400558 0.03570884 -0.01963323 0.03400564 0.03570884 0.03400576 -0.01963335 0.03570884 -0.01963323 -0.03400588 0.03570884 0 0.03926622 0.03570884 - - - - - - - - - - -0.9941335 0 -0.1081601 -0.8609457 -0.4970656 -0.1081599 -0.8087499 -0.4669386 0.35762 0.8609457 0.4970656 -0.1081599 0.4970656 0.8609457 -0.1081599 0.4669096 0.8087525 0.3576517 0 0.9941335 -0.1081601 -0.4970656 0.8609457 -0.1081599 -0.4669147 0.8087614 0.3576251 0.4970656 -0.8609457 -0.1081599 0.8609457 -0.4970656 -0.1081599 0.8087499 -0.4669386 0.35762 -0.4970656 -0.8609457 -0.1081599 -0.4669147 -0.8087614 0.3576251 0 0.9338545 0.3576535 -0.8609457 0.4970656 -0.1081599 -0.8087614 0.4669147 0.3576251 0.9941335 0 -0.1081601 0.9338545 0 0.3576535 0 -0.9941335 -0.1081601 0 -0.9338545 0.3576535 -0.9338545 0 0.3576535 0.8087614 0.4669147 0.3576251 0.4669147 -0.8087614 0.3576251 0.02594143 -0.04492443 0.9986535 0.04492443 -0.02594143 0.9986535 0.6549179 -0.3781061 0.6543076 -0.04492443 0.02594143 0.9986535 -0.0518828 0 0.9986532 -0.7562347 0 0.6543006 0.02594143 0.04492443 0.9986535 0 0.0518828 0.9986532 0 0.7562347 0.6543006 0.0518828 0 0.9986532 0.7562347 0 0.6543006 -0.04492443 -0.02594143 0.9986535 -0.6549179 -0.3781061 0.6543076 -0.02594143 0.04492443 0.9986535 -0.3780986 0.6549049 0.654325 0.04492443 0.02594143 0.9986535 0.6549049 0.3780986 0.654325 -0.02594143 -0.04492443 0.9986535 -0.3781061 -0.6549179 0.6543076 0.3780986 -0.6549049 0.654325 0 -0.7562065 0.6543332 -0.6549049 0.3780986 0.654325 0.3780986 0.6549049 0.654325 0 -0.0518524 0.9986547 -0.4948949 -0.857185 0.1425234 0 -0.9897914 0.1425236 0 -0.7088595 0.7053498 0.4948949 -0.857185 0.1425234 0.857185 -0.4948949 0.1425234 0.6138904 -0.3544175 0.7053559 -0.857185 0.4948949 0.1425234 -0.9897914 0 0.1425236 -0.7088595 0 0.7053498 0.4948949 0.857185 0.1425234 0 0.9897914 0.1425236 0 0.7088595 0.7053498 0.9897914 0 0.1425236 0.7088595 0 0.7053498 -0.857185 -0.4948949 0.1425234 -0.6138904 -0.3544175 0.7053559 -0.4948949 0.857185 0.1425234 -0.3544175 0.6138904 0.7053559 0.857185 0.4948949 0.1425234 0.6138904 0.3544175 0.7053559 -0.3544175 -0.6138904 0.7053559 0.3544175 -0.6138904 0.7053559 -0.6138904 0.3544175 0.7053559 0.3544175 0.6138904 0.7053559 0 0 1 -1.24422e-5 0 1 -6.22095e-6 -1.0237e-5 1 -3.67741e-7 1.18208e-5 1 1.89074e-7 0 1 2.5775e-6 0 1 1.17825e-5 2.15133e-6 1 -5.89081e-6 -5.87895e-6 1 1.84099e-6 -8.02988e-6 1 -1.16643e-5 -4.35835e-6 1 0 0 -1 -3.70134e-7 0 -1 7.4027e-7 0 -1 3.70132e-7 0 -1 -5.09058e-7 0 -1 -7.40244e-7 0 -1 5.09059e-7 0 -1 -2.90257e-7 0 -1 -4.10623e-6 0 1 4.10637e-6 0 1 -1.73161e-6 0 1 -1.61616e-7 0 1 -1.17621e-6 0 -1 -1.00385e-6 0 -1 1.41258e-6 0 -1 1.41271e-6 0 -1 1.41269e-6 0 -1 0 -0.7209914 -0.6929441 0.3604956 -0.6243972 -0.6929438 0.6243972 0.3604956 -0.6929438 -0.7209914 0 -0.6929441 0.6243972 -0.3604956 -0.6929438 0.7209914 0 -0.6929441 -0.3604956 0.6243972 -0.6929438 -0.6243972 0.3604956 -0.6929438 0 0.7209914 -0.6929441 -0.6243972 -0.3604956 -0.6929438 -0.3604956 -0.6243972 -0.6929438 0.3604956 0.6243972 -0.6929438 3.14782e-7 0 -1 4.38429e-7 0 -1 6.60466e-7 0 -1 -3.07377e-7 0 -1 -5.09057e-7 0 -1 -6.60471e-7 0 -1 -3.07381e-7 0 -1 7.63598e-7 0 -1 6.14758e-7 0 -1 -5.09055e-7 0 -1 -6.60471e-7 0 -1 -6.14755e-7 0 -1 -2.54533e-7 0 -1 -2.20157e-7 0 -1 -3.07378e-7 0 -1 -1.22951e-6 0 -1 1.01813e-6 0 -1 4.40308e-7 0 -1 6.14754e-7 0 -1 -3.14571e-7 0 1 8.95873e-7 0 1 4.47942e-7 0 1 1.01092e-5 5.91042e-6 1 1.08866e-5 -5.91033e-6 1 -8.95894e-7 0 1 -5.44344e-6 1.02372e-5 1 2.23969e-7 0 1 -2.33288e-6 8.03039e-6 1 -3.14572e-7 0 1 -8.06293e-6 -2.15172e-6 1 3.9106e-7 0 1 8.55383e-6 -2.15155e-6 1 -6.29142e-7 0 1 2.68762e-6 8.03032e-6 1 -1.48764e-7 0 1 -7.37885e-6 2.1517e-6 1 -3.14577e-7 0 1 6.71905e-6 -5.87862e-6 1 -2.6876e-6 -8.03025e-6 1 1.71075e-5 0 1 0.2268814 0.3929377 0.8911368 0 0.4536963 0.8911564 -0.2268787 -0.3929635 0.8911262 0.2268787 -0.3929635 0.8911262 0.3929662 -0.2268497 0.8911324 -0.2268787 0.3929635 0.8911262 -0.3929662 -0.2268497 0.8911324 0.3929635 0.2268787 0.8911262 -0.3929635 0.2268787 0.8911262 -0.4536963 0 0.8911564 0 -0.4536963 0.8911564 0.4536963 0 0.8911564 1.16643e-5 -4.35835e-6 1 -1.84099e-6 -8.02988e-6 1 5.89081e-6 -5.87895e-6 1 -1.03097e-5 2.15133e-6 1 -2.5775e-6 0 1 -1.47283e-6 0 1 -1.89074e-7 1.18208e-5 1 6.22095e-6 -1.0237e-5 1 1.24422e-5 0 1 3.70134e-7 0 -1 -1.01814e-6 0 -1 2.90259e-7 0 -1 -5.0905e-7 0 -1 7.40277e-7 0 -1 5.09063e-7 0 -1 -3.70129e-7 0 -1 -7.4024e-7 0 -1 2.22079e-6 0 -1 -6.14764e-7 0 -1 5.09052e-7 0 -1 3.07382e-7 0 -1 -7.63608e-7 0 -1 6.60471e-7 0 -1 5.09057e-7 0 -1 -6.60471e-7 0 -1 3.07376e-7 0 -1 1.22951e-6 0 -1 -4.40308e-7 0 -1 -6.14754e-7 0 -1 1.22951e-6 0 -1 -1.01813e-6 0 -1 2.20156e-7 0 -1 3.07378e-7 0 -1 2.54533e-7 0 -1 -1.71075e-5 0 1 2.6876e-6 -8.03025e-6 1 3.14572e-7 0 1 -6.71905e-6 -5.87862e-6 1 8.67232e-7 0 1 7.50596e-6 2.15169e-6 1 6.29139e-7 0 1 -2.68762e-6 8.03032e-6 1 -8.95876e-7 0 1 -8.55389e-6 -2.15166e-6 1 7.61499e-6 -2.15172e-6 1 -2.2397e-7 0 1 2.33288e-6 8.03039e-6 1 8.9588e-7 0 1 5.44341e-6 1.02372e-5 1 -1.08866e-5 -5.91033e-6 1 -4.47941e-7 0 1 -1.01092e-5 5.91042e-6 1 3.14576e-7 0 1 -8.95873e-7 0 1 - - - - - - - - - - 0.309128 0.09332841 0.309128 0.1494764 0.3565636 0.1494764 0.309128 0.5002416 0.309128 0.5589712 0.3565636 0.5589712 0.309128 0.6183514 0.309128 0.6805194 0.3565636 0.6805194 0.309128 0.3237048 0.309128 0.3825202 0.3565636 0.3825202 0.309128 0.1494764 0.309128 0.206981 0.3565636 0.206981 0.309128 0.6183514 0.3565636 0.6183514 0.3565636 0.5589712 0.309128 0.6805194 0.309128 0.7373139 0.3565636 0.7373139 0.309128 0.3825202 0.309128 0.4414118 0.3565636 0.4414118 0.309128 0.2651345 0.3565636 0.2651345 0.3565636 0.206981 0.309128 0.09332841 0.3565636 0.09332841 0.3565636 0.04071724 0.309128 0.5002416 0.3565636 0.5002416 0.3565636 0.4414118 0.309128 0.2651345 0.309128 0.3237048 0.3565636 0.3237048 0.3597577 0.6805194 0.3597577 0.7373139 0.3628495 0.7373139 0.3597577 0.3825202 0.3597577 0.4414118 0.3628495 0.4414118 0.3597577 0.206981 0.3597577 0.2651345 0.3628495 0.2651345 0.3597577 0.04071724 0.3597577 0.09332841 0.3628495 0.09332841 0.3597577 0.4414118 0.3597577 0.5002416 0.3628495 0.5002416 0.3597577 0.3237048 0.3628495 0.3237048 0.3628495 0.2651345 0.3597577 0.1494764 0.3628495 0.1494764 0.3628495 0.09332841 0.3597577 0.5589712 0.3628495 0.5589712 0.3628495 0.5002416 0.3597577 0.6805194 0.3628495 0.6805194 0.3628495 0.6183514 0.3597577 0.3237048 0.3597577 0.3825202 0.3628495 0.3825202 0.3597577 0.206981 0.3628495 0.206981 0.3628495 0.1494764 0.3597577 0.5589712 0.3597577 0.6183514 0.3628495 0.6183514 0.5043808 0.1944225 0.5043808 0.1393616 0.4474703 0.1393616 0.5043808 0.08552318 0.5043808 0.0332002 0.4474703 0.0332002 0.5043808 0.3639183 0.5043808 0.3070072 0.4474703 0.3070072 0.5043808 0.5334143 0.5043808 0.4774307 0.4474703 0.4774307 0.5043808 0.6946365 0.5043808 0.6423134 0.4474703 0.6423134 0.5043808 0.3070072 0.5043808 0.2504059 0.4474703 0.2504059 0.5043808 0.4208294 0.4474703 0.4208294 0.4474703 0.4774307 0.5043808 0.588475 0.4474703 0.588475 0.4474703 0.6423134 0.5043808 0.1944225 0.4474703 0.1944225 0.4474703 0.2504059 0.5043808 0.08552318 0.4474703 0.08552318 0.4474703 0.1393616 0.5043808 0.4208294 0.5043808 0.3639183 0.4474703 0.3639183 0.5043808 0.5334143 0.4474703 0.5334143 0.4474703 0.588475 0.8435339 0.512386 0.85037 0.5378988 0.8552742 0.5378988 0.8621103 0.5817143 0.878198 0.572426 0.8595213 0.5537493 0.8874862 0.5563383 0.8874862 0.5377618 0.8619734 0.544598 0.8181579 0.5563383 0.8274461 0.572426 0.8461228 0.5537493 0.8435339 0.512386 0.8274461 0.5216742 0.8461228 0.5403509 0.8874862 0.5377618 0.878198 0.5216742 0.8595213 0.5403509 0.8274461 0.572426 0.8435338 0.5817143 0.85037 0.5562015 0.8181579 0.5377618 0.8436707 0.544598 0.8461228 0.5403509 0.8621103 0.512386 0.8552742 0.5378988 0.8595213 0.5403509 0.8621103 0.5817143 0.8552742 0.5562015 0.85037 0.5562015 0.8874862 0.5563383 0.8619734 0.5495023 0.8595213 0.5537493 0.8181579 0.5377618 0.8181579 0.5563383 0.8436707 0.5495023 0.802546 0.8114552 0.802546 0.8357715 0.8323189 0.8277938 0.8357626 0.7782386 0.8437402 0.8080114 0.8521013 0.8080114 0.8811374 0.85683 0.8593421 0.8350347 0.8521013 0.8392152 0.8147042 0.85683 0.8364993 0.8350347 0.8323189 0.8277938 0.8357626 0.7782386 0.8147042 0.7903968 0.8364993 0.812192 0.8932954 0.8357715 0.8635227 0.8277938 0.8593421 0.8350347 0.8811373 0.7903968 0.8593421 0.812192 0.8635227 0.8194328 0.8147042 0.85683 0.8357626 0.868988 0.8437402 0.8392152 0.802546 0.8114552 0.8323189 0.8194327 0.8364993 0.812192 0.8932954 0.8357715 0.8932955 0.8114552 0.8635227 0.8194328 0.8811373 0.7903968 0.8600789 0.7782386 0.8521013 0.8080114 0.8357626 0.868988 0.8600789 0.868988 0.8521013 0.8392152 0.85037 0.5378988 0.8528221 0.5470501 0.8552742 0.5378988 0.8595213 0.5537493 0.8528221 0.5470501 0.8552742 0.5562015 0.8619734 0.544598 0.8528221 0.5470501 0.8619734 0.5495023 0.8461228 0.5537493 0.8528221 0.5470501 0.8436707 0.5495023 0.8461228 0.5403509 0.8528221 0.5470501 0.85037 0.5378988 0.8595213 0.5403509 0.8528221 0.5470501 0.8619734 0.544598 0.85037 0.5562015 0.8528221 0.5470501 0.8461228 0.5537493 0.8436707 0.544598 0.8528221 0.5470501 0.8461228 0.5403509 0.8552742 0.5378988 0.8528221 0.5470501 0.8595213 0.5403509 0.8552742 0.5562015 0.8528221 0.5470501 0.85037 0.5562015 0.8619734 0.5495023 0.8528221 0.5470501 0.8595213 0.5537493 0.8436707 0.5495023 0.8528221 0.5470501 0.8436707 0.544598 0.8364993 0.812192 0.8479208 0.8236134 0.8437402 0.8080114 0.8593421 0.8350347 0.8479208 0.8236134 0.8521013 0.8392152 0.8593421 0.812192 0.8479208 0.8236134 0.8635227 0.8194328 0.8364993 0.8350347 0.8479208 0.8236134 0.8323189 0.8277938 0.8635227 0.8277938 0.8479208 0.8236134 0.8593421 0.8350347 0.8521013 0.8080114 0.8479208 0.8236134 0.8593421 0.812192 0.8437402 0.8392152 0.8479208 0.8236134 0.8364993 0.8350347 0.8323189 0.8194327 0.8479208 0.8236134 0.8364993 0.812192 0.8635227 0.8194328 0.8479208 0.8236134 0.8635227 0.8277938 0.8437402 0.8080114 0.8479208 0.8236134 0.8521013 0.8080114 0.8521013 0.8392152 0.8479208 0.8236134 0.8437402 0.8392152 0.8323189 0.8277938 0.8479208 0.8236134 0.8323189 0.8194327 0.04086482 0.2651345 0.04086482 0.3237048 0.1119292 0.3237048 0.1119292 0.3237048 0.181787 0.3237048 0.181787 0.2651345 0.181787 0.3237048 0.2493008 0.3237048 0.2493008 0.2651345 0.2493008 0.2651345 0.2493008 0.3237048 0.309128 0.3237048 0.04086482 0.5002416 0.1119292 0.5002416 0.1119292 0.4414118 0.1119292 0.5002416 0.181787 0.5002416 0.181787 0.4414118 0.181787 0.5002416 0.2493008 0.5002416 0.2493008 0.4414118 0.2493008 0.5002416 0.309128 0.5002416 0.309128 0.4414118 0.04086482 0.09332841 0.1119292 0.09332841 0.1119292 0.04071724 0.1119292 0.09332841 0.181787 0.09332841 0.181787 0.04071724 0.181787 0.09332841 0.2493008 0.09332841 0.2493008 0.04071724 0.2493008 0.09332841 0.309128 0.09332841 0.309128 0.04071724 0.04086482 0.2651345 0.1119292 0.2651345 0.1119292 0.206981 0.1119292 0.206981 0.1119292 0.2651345 0.181787 0.2651345 0.181787 0.2651345 0.2493008 0.2651345 0.2493008 0.206981 0.2493008 0.2651345 0.309128 0.2651345 0.309128 0.206981 0.04086482 0.3825202 0.04086482 0.4414118 0.1119292 0.4414118 0.1119292 0.3825202 0.1119292 0.4414118 0.181787 0.4414118 0.181787 0.3825202 0.181787 0.4414118 0.2493008 0.4414118 0.2493008 0.3825202 0.2493008 0.4414118 0.309128 0.4414118 0.04086482 0.6805194 0.04086482 0.7373139 0.1119292 0.7373139 0.1119292 0.7373139 0.181787 0.7373139 0.181787 0.6805194 0.181787 0.7373139 0.2493008 0.7373139 0.2493008 0.6805194 0.2493008 0.7373139 0.309128 0.7373139 0.309128 0.6805194 0.04086482 0.6183514 0.1119292 0.6183514 0.1119292 0.5589712 0.1119292 0.6183514 0.181787 0.6183514 0.181787 0.5589712 0.181787 0.6183514 0.2493008 0.6183514 0.2493008 0.5589712 0.2493008 0.6183514 0.309128 0.6183514 0.309128 0.5589712 0.04086482 0.1494764 0.04086482 0.206981 0.1119292 0.206981 0.1119292 0.1494764 0.1119292 0.206981 0.181787 0.206981 0.181787 0.1494764 0.181787 0.206981 0.2493008 0.206981 0.2493008 0.1494764 0.2493008 0.206981 0.309128 0.206981 0.04086482 0.3237048 0.04086482 0.3825202 0.1119292 0.3825202 0.1119292 0.3237048 0.1119292 0.3825202 0.181787 0.3825202 0.181787 0.3237048 0.181787 0.3825202 0.2493008 0.3825202 0.2493008 0.3237048 0.2493008 0.3825202 0.309128 0.3825202 0.04086482 0.6183514 0.04086482 0.6805194 0.1119292 0.6805194 0.1119292 0.6183514 0.1119292 0.6805194 0.181787 0.6805194 0.181787 0.6183514 0.181787 0.6805194 0.2493008 0.6805194 0.2493008 0.6183514 0.2493008 0.6805194 0.309128 0.6805194 0.04086482 0.5002416 0.04086482 0.5589712 0.1119292 0.5589712 0.1119292 0.5002416 0.1119292 0.5589712 0.181787 0.5589712 0.181787 0.5002416 0.181787 0.5589712 0.2493008 0.5589712 0.2493008 0.5002416 0.2493008 0.5589712 0.309128 0.5589712 0.04086482 0.09332841 0.04086482 0.1494764 0.1119292 0.1494764 0.1119292 0.09332841 0.1119292 0.1494764 0.181787 0.1494764 0.181787 0.09332841 0.181787 0.1494764 0.2493008 0.1494764 0.2493008 0.09332841 0.2493008 0.1494764 0.309128 0.1494764 0.732023 0.5334143 0.6751124 0.5334143 0.6751124 0.588475 0.6751124 0.5334143 0.6182019 0.5334143 0.6182019 0.588475 0.6182019 0.5334143 0.5612913 0.5334143 0.5612913 0.588475 0.5612913 0.5334143 0.5043808 0.5334143 0.5043808 0.588475 0.732023 0.4208294 0.732023 0.3639183 0.6751124 0.3639183 0.6751124 0.4208294 0.6751124 0.3639183 0.6182019 0.3639183 0.6182019 0.4208294 0.6182019 0.3639183 0.5612913 0.3639183 0.5612913 0.4208294 0.5612913 0.3639183 0.5043808 0.3639183 0.732023 0.08552318 0.6751124 0.08552318 0.6751124 0.1393616 0.6751124 0.08552318 0.6182019 0.08552318 0.6182019 0.1393616 0.6182019 0.08552318 0.5612913 0.08552318 0.5612913 0.1393616 0.5612913 0.08552318 0.5043808 0.08552318 0.5043808 0.1393616 0.732023 0.2504059 0.732023 0.1944225 0.6751124 0.1944225 0.6751124 0.1944225 0.6182019 0.1944225 0.6182019 0.2504059 0.6182019 0.1944225 0.5612913 0.1944225 0.5612913 0.2504059 0.5612913 0.1944225 0.5043808 0.1944225 0.5043808 0.2504059 0.732023 0.6423134 0.732023 0.588475 0.6751124 0.588475 0.6751124 0.588475 0.6182019 0.588475 0.6182019 0.6423134 0.6182019 0.588475 0.5612913 0.588475 0.5612913 0.6423134 0.5612913 0.588475 0.5043808 0.588475 0.5043808 0.6423134 0.732023 0.4208294 0.6751124 0.4208294 0.6751124 0.4774307 0.6751124 0.4208294 0.6182019 0.4208294 0.6182019 0.4774307 0.6182019 0.4208294 0.5612913 0.4208294 0.5612913 0.4774307 0.5612913 0.4208294 0.5043808 0.4208294 0.5043808 0.4774307 0.732023 0.3070072 0.732023 0.2504059 0.6751124 0.2504059 0.6751124 0.3070072 0.6751124 0.2504059 0.6182019 0.2504059 0.6182019 0.3070072 0.6182019 0.2504059 0.5612913 0.2504059 0.5612913 0.3070072 0.5612913 0.2504059 0.5043808 0.2504059 0.732023 0.6946365 0.732023 0.6423134 0.6751124 0.6423134 0.6751124 0.6946365 0.6751124 0.6423134 0.6182019 0.6423134 0.6182019 0.6946365 0.6182019 0.6423134 0.5612913 0.6423134 0.5612913 0.6946365 0.5612913 0.6423134 0.5043808 0.6423134 0.732023 0.5334143 0.732023 0.4774307 0.6751124 0.4774307 0.6751124 0.5334143 0.6751124 0.4774307 0.6182019 0.4774307 0.6182019 0.5334143 0.6182019 0.4774307 0.5612913 0.4774307 0.5612913 0.5334143 0.5612913 0.4774307 0.5043808 0.4774307 0.732023 0.3639183 0.732023 0.3070072 0.6751124 0.3070072 0.6751124 0.3070072 0.6182019 0.3070072 0.6182019 0.3639183 0.6182019 0.3639183 0.6182019 0.3070072 0.5612913 0.3070072 0.5612913 0.3639183 0.5612913 0.3070072 0.5043808 0.3070072 0.732023 0.08552318 0.732023 0.0332002 0.6751124 0.0332002 0.6751124 0.08552318 0.6751124 0.0332002 0.6182019 0.0332002 0.6182019 0.08552318 0.6182019 0.0332002 0.5612913 0.0332002 0.5612913 0.08552318 0.5612913 0.0332002 0.5043808 0.0332002 0.732023 0.1944225 0.732023 0.1393616 0.6751124 0.1393616 0.6751124 0.1944225 0.6751124 0.1393616 0.6182019 0.1393616 0.6182019 0.1944225 0.6182019 0.1393616 0.5612913 0.1393616 0.5612913 0.1944225 0.5612913 0.1393616 0.5043808 0.1393616 0.8198075 0.9285337 0.8760342 0.9285336 0.8680565 0.8987609 0.827785 0.8987609 0.8680565 0.8987609 0.8600789 0.868988 0.9247277 0.7468063 0.8760342 0.7186929 0.8680565 0.7484658 0.9029325 0.7686015 0.8680565 0.7484658 0.8600789 0.7782386 0.9528411 0.8517267 0.9528412 0.7955 0.9230683 0.8034776 0.9230683 0.8437491 0.9230683 0.8034776 0.8932955 0.8114552 0.7430005 0.7955 0.7727733 0.8034776 0.7929089 0.7686015 0.7727733 0.8034776 0.802546 0.8114552 0.8147042 0.7903968 0.7711138 0.9004204 0.8198075 0.9285337 0.827785 0.8987609 0.792909 0.8786251 0.827785 0.8987609 0.8357626 0.868988 0.9247277 0.7468063 0.9029325 0.7686015 0.9230683 0.8034776 0.9029325 0.7686015 0.8811373 0.7903968 0.8932955 0.8114552 0.9528411 0.8517267 0.9230683 0.8437491 0.9029325 0.8786252 0.9230683 0.8437491 0.8932954 0.8357715 0.8811373 0.85683 0.8198074 0.718693 0.7711138 0.7468063 0.7929089 0.7686015 0.827785 0.7484658 0.7929089 0.7686015 0.8147042 0.7903968 0.7711138 0.9004204 0.792909 0.8786251 0.7727733 0.843749 0.792909 0.8786251 0.8147042 0.85683 0.802546 0.8357715 0.8760342 0.9285336 0.9247277 0.9004204 0.9029325 0.8786251 0.8680565 0.8987609 0.9029325 0.8786251 0.8811374 0.85683 0.8198074 0.718693 0.827785 0.7484658 0.8680565 0.7484658 0.827785 0.7484658 0.8357626 0.7782386 0.8600789 0.7782386 0.7430005 0.7955 0.7430004 0.8517267 0.7727733 0.843749 0.7727733 0.8034776 0.7727733 0.843749 0.802546 0.8357715 0.7671324 0.5240897 0.7671324 0.5700107 0.7926452 0.5631745 0.7926452 0.5309258 0.7926452 0.5631745 0.8181579 0.5563383 0.9385118 0.5700107 0.912999 0.5631745 0.8968746 0.5911026 0.912999 0.5631745 0.8874862 0.5563383 0.878198 0.572426 0.8757825 0.6327398 0.8689464 0.607227 0.8366977 0.607227 0.8689464 0.607227 0.8621103 0.5817143 0.8435338 0.5817143 0.8757826 0.4613603 0.8689464 0.4868732 0.8968746 0.5029975 0.8689464 0.4868732 0.8621103 0.512386 0.878198 0.5216742 0.7671324 0.5240897 0.7926452 0.5309258 0.8087695 0.5029975 0.7926452 0.5309258 0.8181579 0.5377618 0.8274461 0.5216742 0.7900929 0.6097792 0.8298615 0.6327398 0.8366977 0.607227 0.8087695 0.5911026 0.8366977 0.607227 0.8435338 0.5817143 0.9385119 0.5240897 0.9155513 0.4843208 0.8968746 0.5029975 0.8968746 0.5029975 0.878198 0.5216742 0.8874862 0.5377618 0.8298616 0.4613603 0.7900928 0.4843208 0.8087695 0.5029975 0.8366977 0.4868732 0.8087695 0.5029975 0.8274461 0.5216742 0.7671324 0.5700107 0.7900929 0.6097792 0.8087695 0.5911026 0.7926452 0.5631745 0.8087695 0.5911026 0.8274461 0.572426 0.9385118 0.5700107 0.9385119 0.5240896 0.912999 0.5309258 0.912999 0.5631745 0.912999 0.5309258 0.8874862 0.5377618 0.8757825 0.6327398 0.9155513 0.6097792 0.8968746 0.5911026 0.8689464 0.607227 0.8968746 0.5911026 0.878198 0.572426 0.8298616 0.4613603 0.8366977 0.4868732 0.8689464 0.4868732 0.8366977 0.4868732 0.8435339 0.512386 0.8621103 0.512386 0.357966 0.5589712 0.357966 0.6183514 0.3597577 0.6183514 0.357966 0.206981 0.3597577 0.206981 0.3597577 0.1494764 0.357966 0.3237048 0.357966 0.3825202 0.3597577 0.3825202 0.357966 0.6183514 0.357966 0.6805194 0.3597577 0.6805194 0.357966 0.5589712 0.3597577 0.5589712 0.3597577 0.5002416 0.357966 0.1494764 0.3597577 0.1494764 0.3597577 0.09332841 0.357966 0.3237048 0.3597577 0.3237048 0.3597577 0.2651345 0.357966 0.5002416 0.3597577 0.5002416 0.3597577 0.4414118 0.357966 0.04071724 0.357966 0.09332841 0.3597577 0.09332841 0.357966 0.2651345 0.3597577 0.2651345 0.3597577 0.206981 0.357966 0.3825202 0.357966 0.4414118 0.3597577 0.4414118 0.357966 0.6805194 0.357966 0.7373139 0.3597577 0.7373139 0.3565636 0.7373139 0.357966 0.7373139 0.357966 0.6805194 0.3565636 0.4414118 0.357966 0.4414118 0.357966 0.3825202 0.3565636 0.206981 0.3565636 0.2651345 0.357966 0.2651345 0.3565636 0.09332841 0.357966 0.09332841 0.357966 0.04071724 0.3565636 0.4414118 0.3565636 0.5002416 0.357966 0.5002416 0.3565636 0.2651345 0.3565636 0.3237048 0.357966 0.3237048 0.3565636 0.09332841 0.3565636 0.1494764 0.357966 0.1494764 0.3565636 0.5589712 0.357966 0.5589712 0.357966 0.5002416 0.3565636 0.6183514 0.3565636 0.6805194 0.357966 0.6805194 0.3565636 0.3825202 0.357966 0.3825202 0.357966 0.3237048 0.3565636 0.1494764 0.3565636 0.206981 0.357966 0.206981 0.3565636 0.5589712 0.3565636 0.6183514 0.357966 0.6183514 0.309128 0.09332841 0.3565636 0.1494764 0.3565636 0.09332841 0.309128 0.5002416 0.3565636 0.5589712 0.3565636 0.5002416 0.309128 0.6183514 0.3565636 0.6805194 0.3565636 0.6183514 0.309128 0.3237048 0.3565636 0.3825202 0.3565636 0.3237048 0.309128 0.1494764 0.3565636 0.206981 0.3565636 0.1494764 0.309128 0.6183514 0.3565636 0.5589712 0.309128 0.5589712 0.309128 0.6805194 0.3565636 0.7373139 0.3565636 0.6805194 0.309128 0.3825202 0.3565636 0.4414118 0.3565636 0.3825202 0.309128 0.2651345 0.3565636 0.206981 0.309128 0.206981 0.309128 0.09332841 0.3565636 0.04071724 0.309128 0.04071724 0.309128 0.5002416 0.3565636 0.4414118 0.309128 0.4414118 0.309128 0.2651345 0.3565636 0.3237048 0.3565636 0.2651345 0.3597577 0.6805194 0.3628495 0.7373139 0.3628495 0.6805194 0.3597577 0.3825202 0.3628495 0.4414118 0.3628495 0.3825202 0.3597577 0.206981 0.3628495 0.2651345 0.3628495 0.206981 0.3597577 0.04071724 0.3628495 0.09332841 0.3628495 0.04071724 0.3597577 0.4414118 0.3628495 0.5002416 0.3628495 0.4414118 0.3597577 0.3237048 0.3628495 0.2651345 0.3597577 0.2651345 0.3597577 0.1494764 0.3628495 0.09332841 0.3597577 0.09332841 0.3597577 0.5589712 0.3628495 0.5002416 0.3597577 0.5002416 0.3597577 0.6805194 0.3628495 0.6183514 0.3597577 0.6183514 0.3597577 0.3237048 0.3628495 0.3825202 0.3628495 0.3237048 0.3597577 0.206981 0.3628495 0.1494764 0.3597577 0.1494764 0.3597577 0.5589712 0.3628495 0.6183514 0.3628495 0.5589712 0.5043808 0.1944225 0.4474703 0.1393616 0.4474703 0.1944225 0.5043808 0.08552318 0.4474703 0.0332002 0.4474703 0.08552318 0.5043808 0.3639183 0.4474703 0.3070072 0.4474703 0.3639183 0.5043808 0.5334143 0.4474703 0.4774307 0.4474703 0.5334143 0.5043808 0.6946365 0.4474703 0.6423134 0.4474703 0.6946365 0.5043808 0.3070072 0.4474703 0.2504059 0.4474703 0.3070072 0.5043808 0.4208294 0.4474703 0.4774307 0.5043808 0.4774307 0.5043808 0.588475 0.4474703 0.6423134 0.5043808 0.6423134 0.5043808 0.1944225 0.4474703 0.2504059 0.5043808 0.2504059 0.5043808 0.08552318 0.4474703 0.1393616 0.5043808 0.1393616 0.5043808 0.4208294 0.4474703 0.3639183 0.4474703 0.4208294 0.5043808 0.5334143 0.4474703 0.588475 0.5043808 0.588475 0.8435339 0.512386 0.8552742 0.5378988 0.8621103 0.512386 0.8621103 0.5817143 0.8595213 0.5537493 0.8552742 0.5562015 0.8874862 0.5563383 0.8619734 0.544598 0.8619734 0.5495023 0.8181579 0.5563383 0.8461228 0.5537493 0.8436707 0.5495023 0.8435339 0.512386 0.8461228 0.5403509 0.85037 0.5378988 0.8874862 0.5377618 0.8595213 0.5403509 0.8619734 0.544598 0.8274461 0.572426 0.85037 0.5562015 0.8461228 0.5537493 0.8181579 0.5377618 0.8461228 0.5403509 0.8274461 0.5216742 0.8621103 0.512386 0.8595213 0.5403509 0.878198 0.5216742 0.8621103 0.5817143 0.85037 0.5562015 0.8435338 0.5817143 0.8874862 0.5563383 0.8595213 0.5537493 0.878198 0.572426 0.8181579 0.5377618 0.8436707 0.5495023 0.8436707 0.544598 0.802546 0.8114552 0.8323189 0.8277938 0.8323189 0.8194327 0.8357626 0.7782386 0.8521013 0.8080114 0.8600789 0.7782386 0.8811374 0.85683 0.8521013 0.8392152 0.8600789 0.868988 0.8147042 0.85683 0.8323189 0.8277938 0.802546 0.8357715 0.8357626 0.7782386 0.8364993 0.812192 0.8437402 0.8080114 0.8932954 0.8357715 0.8593421 0.8350347 0.8811373 0.85683 0.8811373 0.7903968 0.8635227 0.8194328 0.8932955 0.8114552 0.8147042 0.85683 0.8437402 0.8392152 0.8364993 0.8350347 0.802546 0.8114552 0.8364993 0.812192 0.8147042 0.7903968 0.8932954 0.8357715 0.8635227 0.8194328 0.8635227 0.8277938 0.8811373 0.7903968 0.8521013 0.8080114 0.8593421 0.812192 0.8357626 0.868988 0.8521013 0.8392152 0.8437402 0.8392152 0.04086482 0.2651345 0.1119292 0.3237048 0.1119292 0.2651345 0.1119292 0.3237048 0.181787 0.2651345 0.1119292 0.2651345 0.181787 0.3237048 0.2493008 0.2651345 0.181787 0.2651345 0.2493008 0.2651345 0.309128 0.3237048 0.309128 0.2651345 0.04086482 0.5002416 0.1119292 0.4414118 0.04086482 0.4414118 0.1119292 0.5002416 0.181787 0.4414118 0.1119292 0.4414118 0.181787 0.5002416 0.2493008 0.4414118 0.181787 0.4414118 0.2493008 0.5002416 0.309128 0.4414118 0.2493008 0.4414118 0.04086482 0.09332841 0.1119292 0.04071724 0.04086482 0.04071724 0.1119292 0.09332841 0.181787 0.04071724 0.1119292 0.04071724 0.181787 0.09332841 0.2493008 0.04071724 0.181787 0.04071724 0.2493008 0.09332841 0.309128 0.04071724 0.2493008 0.04071724 0.04086482 0.2651345 0.1119292 0.206981 0.04086482 0.206981 0.1119292 0.206981 0.181787 0.2651345 0.181787 0.206981 0.181787 0.2651345 0.2493008 0.206981 0.181787 0.206981 0.2493008 0.2651345 0.309128 0.206981 0.2493008 0.206981 0.04086482 0.3825202 0.1119292 0.4414118 0.1119292 0.3825202 0.1119292 0.3825202 0.181787 0.4414118 0.181787 0.3825202 0.181787 0.3825202 0.2493008 0.4414118 0.2493008 0.3825202 0.2493008 0.3825202 0.309128 0.4414118 0.309128 0.3825202 0.04086482 0.6805194 0.1119292 0.7373139 0.1119292 0.6805194 0.1119292 0.7373139 0.181787 0.6805194 0.1119292 0.6805194 0.181787 0.7373139 0.2493008 0.6805194 0.181787 0.6805194 0.2493008 0.7373139 0.309128 0.6805194 0.2493008 0.6805194 0.04086482 0.6183514 0.1119292 0.5589712 0.04086482 0.5589712 0.1119292 0.6183514 0.181787 0.5589712 0.1119292 0.5589712 0.181787 0.6183514 0.2493008 0.5589712 0.181787 0.5589712 0.2493008 0.6183514 0.309128 0.5589712 0.2493008 0.5589712 0.04086482 0.1494764 0.1119292 0.206981 0.1119292 0.1494764 0.1119292 0.1494764 0.181787 0.206981 0.181787 0.1494764 0.181787 0.1494764 0.2493008 0.206981 0.2493008 0.1494764 0.2493008 0.1494764 0.309128 0.206981 0.309128 0.1494764 0.04086482 0.3237048 0.1119292 0.3825202 0.1119292 0.3237048 0.1119292 0.3237048 0.181787 0.3825202 0.181787 0.3237048 0.181787 0.3237048 0.2493008 0.3825202 0.2493008 0.3237048 0.2493008 0.3237048 0.309128 0.3825202 0.309128 0.3237048 0.04086482 0.6183514 0.1119292 0.6805194 0.1119292 0.6183514 0.1119292 0.6183514 0.181787 0.6805194 0.181787 0.6183514 0.181787 0.6183514 0.2493008 0.6805194 0.2493008 0.6183514 0.2493008 0.6183514 0.309128 0.6805194 0.309128 0.6183514 0.04086482 0.5002416 0.1119292 0.5589712 0.1119292 0.5002416 0.1119292 0.5002416 0.181787 0.5589712 0.181787 0.5002416 0.181787 0.5002416 0.2493008 0.5589712 0.2493008 0.5002416 0.2493008 0.5002416 0.309128 0.5589712 0.309128 0.5002416 0.04086482 0.09332841 0.1119292 0.1494764 0.1119292 0.09332841 0.1119292 0.09332841 0.181787 0.1494764 0.181787 0.09332841 0.181787 0.09332841 0.2493008 0.1494764 0.2493008 0.09332841 0.2493008 0.09332841 0.309128 0.1494764 0.309128 0.09332841 0.732023 0.5334143 0.6751124 0.588475 0.732023 0.588475 0.6751124 0.5334143 0.6182019 0.588475 0.6751124 0.588475 0.6182019 0.5334143 0.5612913 0.588475 0.6182019 0.588475 0.5612913 0.5334143 0.5043808 0.588475 0.5612913 0.588475 0.732023 0.4208294 0.6751124 0.3639183 0.6751124 0.4208294 0.6751124 0.4208294 0.6182019 0.3639183 0.6182019 0.4208294 0.6182019 0.4208294 0.5612913 0.3639183 0.5612913 0.4208294 0.5612913 0.4208294 0.5043808 0.3639183 0.5043808 0.4208294 0.732023 0.08552318 0.6751124 0.1393616 0.732023 0.1393616 0.6751124 0.08552318 0.6182019 0.1393616 0.6751124 0.1393616 0.6182019 0.08552318 0.5612913 0.1393616 0.6182019 0.1393616 0.5612913 0.08552318 0.5043808 0.1393616 0.5612913 0.1393616 0.732023 0.2504059 0.6751124 0.1944225 0.6751124 0.2504059 0.6751124 0.1944225 0.6182019 0.2504059 0.6751124 0.2504059 0.6182019 0.1944225 0.5612913 0.2504059 0.6182019 0.2504059 0.5612913 0.1944225 0.5043808 0.2504059 0.5612913 0.2504059 0.732023 0.6423134 0.6751124 0.588475 0.6751124 0.6423134 0.6751124 0.588475 0.6182019 0.6423134 0.6751124 0.6423134 0.6182019 0.588475 0.5612913 0.6423134 0.6182019 0.6423134 0.5612913 0.588475 0.5043808 0.6423134 0.5612913 0.6423134 0.732023 0.4208294 0.6751124 0.4774307 0.732023 0.4774307 0.6751124 0.4208294 0.6182019 0.4774307 0.6751124 0.4774307 0.6182019 0.4208294 0.5612913 0.4774307 0.6182019 0.4774307 0.5612913 0.4208294 0.5043808 0.4774307 0.5612913 0.4774307 0.732023 0.3070072 0.6751124 0.2504059 0.6751124 0.3070072 0.6751124 0.3070072 0.6182019 0.2504059 0.6182019 0.3070072 0.6182019 0.3070072 0.5612913 0.2504059 0.5612913 0.3070072 0.5612913 0.3070072 0.5043808 0.2504059 0.5043808 0.3070072 0.732023 0.6946365 0.6751124 0.6423134 0.6751124 0.6946365 0.6751124 0.6946365 0.6182019 0.6423134 0.6182019 0.6946365 0.6182019 0.6946365 0.5612913 0.6423134 0.5612913 0.6946365 0.5612913 0.6946365 0.5043808 0.6423134 0.5043808 0.6946365 0.732023 0.5334143 0.6751124 0.4774307 0.6751124 0.5334143 0.6751124 0.5334143 0.6182019 0.4774307 0.6182019 0.5334143 0.6182019 0.5334143 0.5612913 0.4774307 0.5612913 0.5334143 0.5612913 0.5334143 0.5043808 0.4774307 0.5043808 0.5334143 0.732023 0.3639183 0.6751124 0.3070072 0.6751124 0.3639183 0.6751124 0.3070072 0.6182019 0.3639183 0.6751124 0.3639183 0.6182019 0.3639183 0.5612913 0.3070072 0.5612913 0.3639183 0.5612913 0.3639183 0.5043808 0.3070072 0.5043808 0.3639183 0.732023 0.08552318 0.6751124 0.0332002 0.6751124 0.08552318 0.6751124 0.08552318 0.6182019 0.0332002 0.6182019 0.08552318 0.6182019 0.08552318 0.5612913 0.0332002 0.5612913 0.08552318 0.5612913 0.08552318 0.5043808 0.0332002 0.5043808 0.08552318 0.732023 0.1944225 0.6751124 0.1393616 0.6751124 0.1944225 0.6751124 0.1944225 0.6182019 0.1393616 0.6182019 0.1944225 0.6182019 0.1944225 0.5612913 0.1393616 0.5612913 0.1944225 0.5612913 0.1944225 0.5043808 0.1393616 0.5043808 0.1944225 0.8198075 0.9285337 0.8680565 0.8987609 0.827785 0.8987609 0.827785 0.8987609 0.8600789 0.868988 0.8357626 0.868988 0.9247277 0.7468063 0.8680565 0.7484658 0.9029325 0.7686015 0.9029325 0.7686015 0.8600789 0.7782386 0.8811373 0.7903968 0.9528411 0.8517267 0.9230683 0.8034776 0.9230683 0.8437491 0.9230683 0.8437491 0.8932955 0.8114552 0.8932954 0.8357715 0.7430005 0.7955 0.7929089 0.7686015 0.7711138 0.7468063 0.7727733 0.8034776 0.8147042 0.7903968 0.7929089 0.7686015 0.7711138 0.9004204 0.827785 0.8987609 0.792909 0.8786251 0.792909 0.8786251 0.8357626 0.868988 0.8147042 0.85683 0.9247277 0.7468063 0.9230683 0.8034776 0.9528412 0.7955 0.9029325 0.7686015 0.8932955 0.8114552 0.9230683 0.8034776 0.9528411 0.8517267 0.9029325 0.8786252 0.9247277 0.9004204 0.9230683 0.8437491 0.8811373 0.85683 0.9029325 0.8786252 0.8198074 0.718693 0.7929089 0.7686015 0.827785 0.7484658 0.827785 0.7484658 0.8147042 0.7903968 0.8357626 0.7782386 0.7711138 0.9004204 0.7727733 0.843749 0.7430004 0.8517267 0.792909 0.8786251 0.802546 0.8357715 0.7727733 0.843749 0.8760342 0.9285336 0.9029325 0.8786251 0.8680565 0.8987609 0.8680565 0.8987609 0.8811374 0.85683 0.8600789 0.868988 0.8198074 0.718693 0.8680565 0.7484658 0.8760342 0.7186929 0.827785 0.7484658 0.8600789 0.7782386 0.8680565 0.7484658 0.7430005 0.7955 0.7727733 0.843749 0.7727733 0.8034776 0.7727733 0.8034776 0.802546 0.8357715 0.802546 0.8114552 0.7671324 0.5240897 0.7926452 0.5631745 0.7926452 0.5309258 0.7926452 0.5309258 0.8181579 0.5563383 0.8181579 0.5377618 0.9385118 0.5700107 0.8968746 0.5911026 0.9155513 0.6097792 0.912999 0.5631745 0.878198 0.572426 0.8968746 0.5911026 0.8757825 0.6327398 0.8366977 0.607227 0.8298615 0.6327398 0.8689464 0.607227 0.8435338 0.5817143 0.8366977 0.607227 0.8757826 0.4613603 0.8968746 0.5029975 0.9155513 0.4843208 0.8689464 0.4868732 0.878198 0.5216742 0.8968746 0.5029975 0.7671324 0.5240897 0.8087695 0.5029975 0.7900928 0.4843208 0.7926452 0.5309258 0.8274461 0.5216742 0.8087695 0.5029975 0.7900929 0.6097792 0.8366977 0.607227 0.8087695 0.5911026 0.8087695 0.5911026 0.8435338 0.5817143 0.8274461 0.572426 0.9385119 0.5240897 0.8968746 0.5029975 0.912999 0.5309258 0.8968746 0.5029975 0.8874862 0.5377618 0.912999 0.5309258 0.8298616 0.4613603 0.8087695 0.5029975 0.8366977 0.4868732 0.8366977 0.4868732 0.8274461 0.5216742 0.8435339 0.512386 0.7671324 0.5700107 0.8087695 0.5911026 0.7926452 0.5631745 0.7926452 0.5631745 0.8274461 0.572426 0.8181579 0.5563383 0.9385118 0.5700107 0.912999 0.5309258 0.912999 0.5631745 0.912999 0.5631745 0.8874862 0.5377618 0.8874862 0.5563383 0.8757825 0.6327398 0.8968746 0.5911026 0.8689464 0.607227 0.8689464 0.607227 0.878198 0.572426 0.8621103 0.5817143 0.8298616 0.4613603 0.8689464 0.4868732 0.8757826 0.4613603 0.8366977 0.4868732 0.8621103 0.512386 0.8689464 0.4868732 0.357966 0.5589712 0.3597577 0.6183514 0.3597577 0.5589712 0.357966 0.206981 0.3597577 0.1494764 0.357966 0.1494764 0.357966 0.3237048 0.3597577 0.3825202 0.3597577 0.3237048 0.357966 0.6183514 0.3597577 0.6805194 0.3597577 0.6183514 0.357966 0.5589712 0.3597577 0.5002416 0.357966 0.5002416 0.357966 0.1494764 0.3597577 0.09332841 0.357966 0.09332841 0.357966 0.3237048 0.3597577 0.2651345 0.357966 0.2651345 0.357966 0.5002416 0.3597577 0.4414118 0.357966 0.4414118 0.357966 0.04071724 0.3597577 0.09332841 0.3597577 0.04071724 0.357966 0.2651345 0.3597577 0.206981 0.357966 0.206981 0.357966 0.3825202 0.3597577 0.4414118 0.3597577 0.3825202 0.357966 0.6805194 0.3597577 0.7373139 0.3597577 0.6805194 0.3565636 0.7373139 0.357966 0.6805194 0.3565636 0.6805194 0.3565636 0.4414118 0.357966 0.3825202 0.3565636 0.3825202 0.3565636 0.206981 0.357966 0.2651345 0.357966 0.206981 0.3565636 0.09332841 0.357966 0.04071724 0.3565636 0.04071724 0.3565636 0.4414118 0.357966 0.5002416 0.357966 0.4414118 0.3565636 0.2651345 0.357966 0.3237048 0.357966 0.2651345 0.3565636 0.09332841 0.357966 0.1494764 0.357966 0.09332841 0.3565636 0.5589712 0.357966 0.5002416 0.3565636 0.5002416 0.3565636 0.6183514 0.357966 0.6805194 0.357966 0.6183514 0.3565636 0.3825202 0.357966 0.3237048 0.3565636 0.3237048 0.3565636 0.1494764 0.357966 0.206981 0.357966 0.1494764 0.3565636 0.5589712 0.357966 0.6183514 0.357966 0.5589712 - - - - - - - - - - - - - - - 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 3 -

77 0 0 78 1 1 16 2 2 85 3 3 86 4 4 23 5 5 93 6 6 94 7 7 13 8 8 101 9 9 102 10 10 20 11 11 78 1 12 106 12 13 17 13 14 93 6 15 12 14 16 23 5 17 94 7 18 110 15 19 14 16 20 102 10 21 114 17 22 21 18 23 118 19 24 18 20 25 17 13 26 77 0 27 15 21 28 14 16 29 85 3 30 22 22 31 21 18 32 118 19 33 101 9 34 19 23 35 218 24 36 219 25 37 26 26 38 220 27 39 221 28 40 33 29 41 222 30 42 223 31 43 30 32 44 219 25 45 224 33 46 27 34 47 221 28 48 225 35 49 34 36 50 226 37 51 31 38 52 30 32 53 227 39 54 28 40 55 27 34 56 228 41 57 35 42 58 34 36 59 218 24 60 25 43 61 24 44 62 226 37 63 220 27 64 32 45 65 222 30 66 29 46 67 28 40 68 228 41 69 229 47 70 24 44 71 125 48 72 126 49 73 36 50 74 133 51 75 134 52 76 38 53 77 141 54 78 142 55 79 45 56 80 149 57 81 150 58 82 42 59 83 134 52 84 154 60 85 39 61 86 142 55 87 158 62 88 46 63 89 162 64 90 43 65 91 42 59 92 166 66 93 40 67 94 39 61 95 125 48 96 47 68 97 46 63 98 133 51 99 37 69 100 36 50 101 162 64 102 141 54 103 44 70 104 149 57 105 41 71 106 40 67 107 196 72 108 53 72 109 52 72 110 199 73 111 200 73 112 48 73 113 203 74 114 204 74 115 50 74 116 207 75 117 208 75 118 57 75 119 196 72 120 210 72 121 54 72 122 204 76 123 212 76 124 51 76 125 208 72 126 214 72 127 58 72 128 216 77 129 55 77 130 54 77 131 195 78 132 52 78 133 51 78 134 199 79 135 59 79 136 58 79 137 203 80 138 49 80 139 48 80 140 216 81 141 207 81 142 56 81 143 176 82 144 193 82 145 65 82 146 171 82 147 62 82 148 61 82 149 173 82 150 69 82 151 68 82 152 175 83 153 66 83 154 65 83 155 171 82 156 179 82 157 63 82 158 183 84 159 70 84 160 69 84 161 187 85 162 72 85 163 71 85 164 175 86 165 191 86 166 67 86 167 176 87 168 64 87 169 63 87 170 183 82 171 180 82 172 71 82 173 187 88 174 184 88 175 61 88 176 191 89 177 188 89 178 68 89 179 53 72 180 60 72 181 52 72 182 48 90 183 60 90 184 59 90 185 50 72 186 60 72 187 49 72 188 57 72 189 60 72 190 56 72 191 54 91 192 60 91 193 53 91 194 51 72 195 60 72 196 50 72 197 58 92 198 60 92 199 57 92 200 55 72 201 60 72 202 54 72 203 52 93 204 60 93 205 51 93 206 59 72 207 60 72 208 58 72 209 49 72 210 60 72 211 48 72 212 56 72 213 60 72 214 55 72 215 63 94 216 73 94 217 62 94 218 69 95 219 73 95 220 68 95 221 72 82 222 73 82 223 71 82 224 66 82 225 73 82 226 65 82 227 70 82 228 73 82 229 69 82 230 61 82 231 73 82 232 72 82 233 67 82 234 73 82 235 66 82 236 64 96 237 73 96 238 63 96 239 71 82 240 73 82 241 70 82 242 62 97 243 73 97 244 61 97 245 68 98 246 73 98 247 67 98 248 65 82 249 73 82 250 64 82 251 6 99 252 7 100 253 98 9 254 98 9 255 99 9 256 120 19 257 99 9 258 100 9 259 119 19 260 119 19 261 100 9 262 101 9 263 10 101 264 82 3 265 117 17 266 82 3 267 83 3 268 116 17 269 83 3 270 84 3 271 115 17 272 84 3 273 85 3 274 114 17 275 3 102 276 74 0 277 113 15 278 74 0 279 75 0 280 112 15 281 75 0 282 76 0 283 111 15 284 76 0 285 77 0 286 110 15 287 6 99 288 121 19 289 109 12 290 109 12 291 121 19 292 120 19 293 120 19 294 119 19 295 107 12 296 119 19 297 118 19 298 106 12 299 8 103 300 9 104 301 117 17 302 105 10 303 117 17 304 116 17 305 104 10 306 116 17 307 115 17 308 103 10 309 115 17 310 114 17 311 1 105 312 2 106 313 113 15 314 113 15 315 112 15 316 96 7 317 112 15 318 111 15 319 95 7 320 111 15 321 110 15 322 94 7 323 0 107 324 90 6 325 89 4 326 90 6 327 91 6 328 88 4 329 91 6 330 92 6 331 87 4 332 92 6 333 93 6 334 86 4 335 4 108 336 5 109 337 109 12 338 81 1 339 109 12 340 108 12 341 80 1 342 108 12 343 107 12 344 79 1 345 107 12 346 106 12 347 7 100 348 8 103 349 105 10 350 98 9 351 105 10 352 104 10 353 99 9 354 104 10 355 103 10 356 100 9 357 103 10 358 102 10 359 0 107 360 1 105 361 97 7 362 90 6 363 97 7 364 96 7 365 91 6 366 96 7 367 95 7 368 92 6 369 95 7 370 94 7 371 10 101 372 11 110 373 89 4 374 82 3 375 89 4 376 88 4 377 83 3 378 88 4 379 87 4 380 84 3 381 87 4 382 86 4 383 3 102 384 4 108 385 81 1 386 74 0 387 81 1 388 80 1 389 75 0 390 80 1 391 79 1 392 76 0 393 79 1 394 78 1 395 29 46 396 146 57 397 169 66 398 146 57 399 147 57 400 168 66 401 147 57 402 148 57 403 167 66 404 148 57 405 149 57 406 166 66 407 31 38 408 32 45 409 138 54 410 165 64 411 138 54 412 139 54 413 164 64 414 139 54 415 140 54 416 163 64 417 140 54 418 141 54 419 25 43 420 130 51 421 129 49 422 130 51 423 131 51 424 128 49 425 131 51 426 132 51 427 127 49 428 132 51 429 133 51 430 126 49 431 34 36 432 35 42 433 122 48 434 122 48 435 123 48 436 160 62 437 123 48 438 124 48 439 159 62 440 124 48 441 125 48 442 158 62 443 27 34 444 28 40 445 169 66 446 169 66 447 168 66 448 156 60 449 168 66 450 167 66 451 155 60 452 167 66 453 166 66 454 154 60 455 31 38 456 165 64 457 153 58 458 165 64 459 164 64 460 152 58 461 164 64 462 163 64 463 151 58 464 163 64 465 162 64 466 150 58 467 33 29 468 34 36 469 161 62 470 145 55 471 161 62 472 160 62 473 144 55 474 160 62 475 159 62 476 143 55 477 159 62 478 158 62 479 26 26 480 27 34 481 157 60 482 137 52 483 157 60 484 156 60 485 136 52 486 156 60 487 155 60 488 135 52 489 155 60 490 154 60 491 29 46 492 30 32 493 153 58 494 146 57 495 153 58 496 152 58 497 147 57 498 152 58 499 151 58 500 148 57 501 151 58 502 150 58 503 32 45 504 33 29 505 145 55 506 145 55 507 144 55 508 139 54 509 139 54 510 144 55 511 143 55 512 140 54 513 143 55 514 142 55 515 25 43 516 26 26 517 137 52 518 130 51 519 137 52 520 136 52 521 131 51 522 136 52 523 135 52 524 132 51 525 135 52 526 134 52 527 35 42 528 24 44 529 129 49 530 122 48 531 129 49 532 128 49 533 123 48 534 128 49 535 127 49 536 124 48 537 127 49 538 126 49 539 4 111 540 3 111 541 189 111 542 190 112 543 189 112 544 188 112 545 11 113 546 10 113 547 185 113 548 186 114 549 185 114 550 184 114 551 1 82 552 0 82 553 181 82 554 182 82 555 181 82 556 180 82 557 7 82 558 177 82 559 178 82 560 177 115 561 176 115 562 179 115 563 5 116 564 4 116 565 190 116 566 174 82 567 190 82 568 191 82 569 11 117 570 186 117 571 181 117 572 186 118 573 187 118 574 180 118 575 1 119 576 182 119 577 172 119 578 182 120 579 183 120 580 173 120 581 9 121 582 8 121 583 178 121 584 170 122 585 178 122 586 179 122 587 5 82 588 174 82 589 192 82 590 174 123 591 175 123 592 193 123 593 3 124 594 2 124 595 172 124 596 189 125 597 172 125 598 173 125 599 9 126 600 170 126 601 185 126 602 170 127 603 171 127 604 184 127 605 7 128 606 6 128 607 192 128 608 177 129 609 192 129 610 193 129 611 43 130 612 44 130 613 206 130 614 217 131 615 206 131 616 207 131 617 37 132 618 202 132 619 201 132 620 202 133 621 203 133 622 200 133 623 47 72 624 198 72 625 215 72 626 198 134 627 199 134 628 214 134 629 40 135 630 194 135 631 213 135 632 194 136 633 195 136 634 212 136 635 43 137 636 217 137 637 211 137 638 217 138 639 216 138 640 210 138 641 45 139 642 46 139 643 215 139 644 209 140 645 215 140 646 214 140 647 38 141 648 39 141 649 213 141 650 213 142 651 212 142 652 204 142 653 41 143 654 42 143 655 211 143 656 197 144 657 211 144 658 210 144 659 44 145 660 45 145 661 209 145 662 206 146 663 209 146 664 208 146 665 37 147 666 38 147 667 205 147 668 202 148 669 205 148 670 204 148 671 47 72 672 36 72 673 201 72 674 198 149 675 201 149 676 200 149 677 41 72 678 197 72 679 194 72 680 197 150 681 196 150 682 195 150 683 237 151 684 241 152 685 229 47 686 240 153 687 222 30 688 227 39 689 235 154 690 239 155 691 220 27 692 241 152 693 238 156 694 218 24 695 237 151 696 228 41 697 225 35 698 236 157 699 227 39 700 224 33 701 235 154 702 226 37 703 223 31 704 234 158 705 225 35 706 221 28 707 230 159 708 233 160 709 224 33 710 232 161 711 223 31 712 222 30 713 239 155 714 231 162 715 221 28 716 238 156 717 230 159 718 219 25 719 14 16 720 230 159 721 238 156 722 21 18 723 231 162 724 239 155 725 17 13 726 18 20 727 232 161 728 15 21 729 233 160 730 230 159 731 21 18 732 22 22 733 234 158 734 18 20 735 19 23 736 235 154 737 15 21 738 16 2 739 236 157 740 23 5 741 237 151 742 234 158 743 12 14 744 13 8 745 238 156 746 20 11 747 239 155 748 235 154 749 16 2 750 17 13 751 240 153 752 23 5 753 12 14 754 241 152 755 77 0 756 16 2 757 15 21 758 85 3 759 23 5 760 22 22 761 93 6 762 13 8 763 12 14 764 101 9 765 20 11 766 19 23 767 78 1 768 17 13 769 16 2 770 93 6 771 23 5 772 86 4 773 94 7 774 14 16 775 13 8 776 102 10 777 21 18 778 20 11 779 118 19 780 17 13 781 106 12 782 77 0 783 14 16 784 110 15 785 85 3 786 21 18 787 114 17 788 118 19 789 19 23 790 18 20 791 218 24 792 26 26 793 25 43 794 220 27 795 33 29 796 32 45 797 222 30 798 30 32 799 29 46 800 219 25 801 27 34 802 26 26 803 221 28 804 34 36 805 33 29 806 226 37 807 30 32 808 223 31 809 227 39 810 27 34 811 224 33 812 228 41 813 34 36 814 225 35 815 218 24 816 24 44 817 229 47 818 226 37 819 32 45 820 31 38 821 222 30 822 28 40 823 227 39 824 228 41 825 24 44 826 35 42 827 125 48 828 36 50 829 47 68 830 133 51 831 38 53 832 37 69 833 141 54 834 45 56 835 44 70 836 149 57 837 42 59 838 41 71 839 134 52 840 39 61 841 38 53 842 142 55 843 46 63 844 45 56 845 162 64 846 42 59 847 150 58 848 166 66 849 39 61 850 154 60 851 125 48 852 46 63 853 158 62 854 133 51 855 36 50 856 126 49 857 162 64 858 44 70 859 43 65 860 149 57 861 40 67 862 166 66 863 196 163 864 52 163 865 195 163 866 199 164 867 48 164 868 59 164 869 203 165 870 50 165 871 49 165 872 207 166 873 57 166 874 56 166 875 196 167 876 54 167 877 53 167 878 204 168 879 51 168 880 50 168 881 208 72 882 58 72 883 57 72 884 216 72 885 54 72 886 210 72 887 195 169 888 51 169 889 212 169 890 199 170 891 58 170 892 214 170 893 203 171 894 48 171 895 200 171 896 216 72 897 56 72 898 55 72 899 176 172 900 65 172 901 64 172 902 171 173 903 61 173 904 184 173 905 173 174 906 68 174 907 188 174 908 175 82 909 65 82 910 193 82 911 171 82 912 63 82 913 62 82 914 183 175 915 69 175 916 173 175 917 187 82 918 71 82 919 180 82 920 175 176 921 67 176 922 66 176 923 176 177 924 63 177 925 179 177 926 183 178 927 71 178 928 70 178 929 187 179 930 61 179 931 72 179 932 191 180 933 68 180 934 67 180 935 6 99 936 98 9 937 121 19 938 98 9 939 120 19 940 121 19 941 99 9 942 119 19 943 120 19 944 119 19 945 101 9 946 118 19 947 10 101 948 117 17 949 9 104 950 82 3 951 116 17 952 117 17 953 83 3 954 115 17 955 116 17 956 84 3 957 114 17 958 115 17 959 3 102 960 113 15 961 2 106 962 74 0 963 112 15 964 113 15 965 75 0 966 111 15 967 112 15 968 76 0 969 110 15 970 111 15 971 6 99 972 109 12 973 5 109 974 109 12 975 120 19 976 108 12 977 120 19 978 107 12 979 108 12 980 119 19 981 106 12 982 107 12 983 8 103 984 117 17 985 105 10 986 105 10 987 116 17 988 104 10 989 104 10 990 115 17 991 103 10 992 103 10 993 114 17 994 102 10 995 1 105 996 113 15 997 97 7 998 113 15 999 96 7 1000 97 7 1001 112 15 1002 95 7 1003 96 7 1004 111 15 1005 94 7 1006 95 7 1007 0 107 1008 89 4 1009 11 110 1010 90 6 1011 88 4 1012 89 4 1013 91 6 1014 87 4 1015 88 4 1016 92 6 1017 86 4 1018 87 4 1019 4 108 1020 109 12 1021 81 1 1022 81 1 1023 108 12 1024 80 1 1025 80 1 1026 107 12 1027 79 1 1028 79 1 1029 106 12 1030 78 1 1031 7 100 1032 105 10 1033 98 9 1034 98 9 1035 104 10 1036 99 9 1037 99 9 1038 103 10 1039 100 9 1040 100 9 1041 102 10 1042 101 9 1043 0 107 1044 97 7 1045 90 6 1046 90 6 1047 96 7 1048 91 6 1049 91 6 1050 95 7 1051 92 6 1052 92 6 1053 94 7 1054 93 6 1055 10 101 1056 89 4 1057 82 3 1058 82 3 1059 88 4 1060 83 3 1061 83 3 1062 87 4 1063 84 3 1064 84 3 1065 86 4 1066 85 3 1067 3 102 1068 81 1 1069 74 0 1070 74 0 1071 80 1 1072 75 0 1073 75 0 1074 79 1 1075 76 0 1076 76 0 1077 78 1 1078 77 0 1079 29 46 1080 169 66 1081 28 40 1082 146 57 1083 168 66 1084 169 66 1085 147 57 1086 167 66 1087 168 66 1088 148 57 1089 166 66 1090 167 66 1091 31 38 1092 138 54 1093 165 64 1094 165 64 1095 139 54 1096 164 64 1097 164 64 1098 140 54 1099 163 64 1100 163 64 1101 141 54 1102 162 64 1103 25 43 1104 129 49 1105 24 44 1106 130 51 1107 128 49 1108 129 49 1109 131 51 1110 127 49 1111 128 49 1112 132 51 1113 126 49 1114 127 49 1115 34 36 1116 122 48 1117 161 62 1118 122 48 1119 160 62 1120 161 62 1121 123 48 1122 159 62 1123 160 62 1124 124 48 1125 158 62 1126 159 62 1127 27 34 1128 169 66 1129 157 60 1130 169 66 1131 156 60 1132 157 60 1133 168 66 1134 155 60 1135 156 60 1136 167 66 1137 154 60 1138 155 60 1139 31 38 1140 153 58 1141 30 32 1142 165 64 1143 152 58 1144 153 58 1145 164 64 1146 151 58 1147 152 58 1148 163 64 1149 150 58 1150 151 58 1151 33 29 1152 161 62 1153 145 55 1154 145 55 1155 160 62 1156 144 55 1157 144 55 1158 159 62 1159 143 55 1160 143 55 1161 158 62 1162 142 55 1163 26 26 1164 157 60 1165 137 52 1166 137 52 1167 156 60 1168 136 52 1169 136 52 1170 155 60 1171 135 52 1172 135 52 1173 154 60 1174 134 52 1175 29 46 1176 153 58 1177 146 57 1178 146 57 1179 152 58 1180 147 57 1181 147 57 1182 151 58 1183 148 57 1184 148 57 1185 150 58 1186 149 57 1187 32 45 1188 145 55 1189 138 54 1190 145 55 1191 139 54 1192 138 54 1193 139 54 1194 143 55 1195 140 54 1196 140 54 1197 142 55 1198 141 54 1199 25 43 1200 137 52 1201 130 51 1202 130 51 1203 136 52 1204 131 51 1205 131 51 1206 135 52 1207 132 51 1208 132 51 1209 134 52 1210 133 51 1211 35 42 1212 129 49 1213 122 48 1214 122 48 1215 128 49 1216 123 48 1217 123 48 1218 127 49 1219 124 48 1220 124 48 1221 126 49 1222 125 48 1223 4 82 1224 189 82 1225 190 82 1226 190 82 1227 188 82 1228 191 82 1229 11 181 1230 185 181 1231 186 181 1232 186 182 1233 184 182 1234 187 182 1235 1 183 1236 181 183 1237 182 183 1238 182 184 1239 180 184 1240 183 184 1241 7 185 1242 178 185 1243 8 185 1244 177 82 1245 179 82 1246 178 82 1247 5 82 1248 190 82 1249 174 82 1250 174 186 1251 191 186 1252 175 186 1253 11 82 1254 181 82 1255 0 82 1256 186 82 1257 180 82 1258 181 82 1259 1 187 1260 172 187 1261 2 187 1262 182 188 1263 173 188 1264 172 188 1265 9 189 1266 178 189 1267 170 189 1268 170 82 1269 179 82 1270 171 82 1271 5 190 1272 192 190 1273 6 190 1274 174 191 1275 193 191 1276 192 191 1277 3 192 1278 172 192 1279 189 192 1280 189 193 1281 173 193 1282 188 193 1283 9 194 1284 185 194 1285 10 194 1286 170 195 1287 184 195 1288 185 195 1289 7 82 1290 192 82 1291 177 82 1292 177 196 1293 193 196 1294 176 196 1295 43 72 1296 206 72 1297 217 72 1298 217 197 1299 207 197 1300 216 197 1301 37 72 1302 201 72 1303 36 72 1304 202 198 1305 200 198 1306 201 198 1307 47 199 1308 215 199 1309 46 199 1310 198 200 1311 214 200 1312 215 200 1313 40 201 1314 213 201 1315 39 201 1316 194 202 1317 212 202 1318 213 202 1319 43 203 1320 211 203 1321 42 203 1322 217 204 1323 210 204 1324 211 204 1325 45 205 1326 215 205 1327 209 205 1328 209 206 1329 214 206 1330 208 206 1331 38 72 1332 213 72 1333 205 72 1334 213 207 1335 204 207 1336 205 207 1337 41 208 1338 211 208 1339 197 208 1340 197 209 1341 210 209 1342 196 209 1343 44 210 1344 209 210 1345 206 210 1346 206 211 1347 208 211 1348 207 211 1349 37 72 1350 205 72 1351 202 72 1352 202 212 1353 204 212 1354 203 212 1355 47 213 1356 201 213 1357 198 213 1358 198 214 1359 200 214 1360 199 214 1361 41 215 1362 194 215 1363 40 215 1364 197 216 1365 195 216 1366 194 216 1367 237 151 1368 229 47 1369 228 41 1370 240 153 1371 227 39 1372 236 157 1373 235 154 1374 220 27 1375 226 37 1376 241 152 1377 218 24 1378 229 47 1379 237 151 1380 225 35 1381 234 158 1382 236 157 1383 224 33 1384 233 160 1385 235 154 1386 223 31 1387 232 161 1388 234 158 1389 221 28 1390 231 162 1391 230 159 1392 224 33 1393 219 25 1394 232 161 1395 222 30 1396 240 153 1397 239 155 1398 221 28 1399 220 27 1400 238 156 1401 219 25 1402 218 24 1403 14 16 1404 238 156 1405 13 8 1406 21 18 1407 239 155 1408 20 11 1409 17 13 1410 232 161 1411 240 153 1412 15 21 1413 230 159 1414 14 16 1415 21 18 1416 234 158 1417 231 162 1418 18 20 1419 235 154 1420 232 161 1421 15 21 1422 236 157 1423 233 160 1424 23 5 1425 234 158 1426 22 22 1427 12 14 1428 238 156 1429 241 152 1430 20 11 1431 235 154 1432 19 23 1433 16 2 1434 240 153 1435 236 157 1436 23 5 1437 241 152 1438 237 151 1439

-
-
-
-
- - - - - 0.6858805 -0.3173701 0.6548619 7.481132 0.7276338 0.3124686 -0.6106656 -6.50764 -0.01081678 0.8953432 0.4452454 5.343665 0 0 0 1 - - - - -0.2908646 -0.7711008 0.5663932 4.076245 0.9551712 -0.1998834 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 - - - - 0.6858805 -0.3173701 0.6548619 7.481132 0.7276337 0.3124686 -0.6106656 -6.50764 -0.01081678 0.8953431 0.4452454 5.343665 0 0 0 1 - - - - -0.2908646 -0.7711008 0.5663933 4.076245 0.9551712 -0.1998833 0.2183912 1.005454 -0.05518906 0.6045247 0.7946723 5.903862 0 0 0 1 - - - - 0.6858804 -0.31737 0.654862 7.481132 0.7276337 0.3124685 -0.6106656 -6.50764 -0.01081676 0.8953431 0.4452453 5.343665 0 0 0 1 - - - - -0.2908646 -0.7711008 0.5663933 4.076245 0.9551712 -0.1998833 0.2183912 1.005454 -0.0551891 0.6045247 0.7946723 5.903862 0 0 0 1 - - - - 0.6858804 -0.3173699 0.654862 7.481132 0.7276337 0.3124684 -0.6106656 -6.50764 -0.01081676 0.8953431 0.4452451 5.343665 0 0 0 1 - - - - -0.290865 -0.7711005 0.5663934 4.076245 0.955171 -0.1998835 0.2183915 1.005454 -0.05518908 0.6045249 0.7946721 5.903862 0 0 0 1 - - - - 0.001 0 0 0 0 -4.37114e-11 -0.001 0 0 0.001 -4.37114e-11 0 0 0 0 1 - - - 1 0 0 0.7041132 0 1 0 -0.179476 0 0 1 1.00003 0 0 0 1 - - - - -0.2908646 -0.7711008 0.5663933 -3.806205 0.9551712 -0.1998833 0.2183912 -2.774845 -0.0551891 0.6045247 0.7946723 0.2407236 0 0 0 1 - - - - -0.2908646 -0.7711008 0.5663933 -3.648487 0.9551712 -0.1998833 0.2183912 3.463097 -0.0551891 0.6045247 0.7946723 0.2519307 0 0 0 1 - - - - 0.6858804 -0.31737 0.654862 7.481132 0.7276337 0.3124685 -0.6106656 -6.50764 -0.01081676 0.8953431 0.4452453 5.343665 0 0 0 1 - - - - -0.2908646 -0.7711008 0.5663933 4.076245 0.9551712 -0.1998833 0.2183912 1.005454 -0.0551891 0.6045247 0.7946723 5.903862 0 0 0 1 - - - - 0.6858804 -0.3173699 0.654862 7.481132 0.7276337 0.3124684 -0.6106656 -6.50764 -0.01081676 0.8953431 0.4452451 5.343665 0 0 0 1 - - - - -0.290865 -0.7711005 0.5663934 4.076245 0.955171 -0.1998835 0.2183915 1.005454 -0.05518908 0.6045249 0.7946721 5.903862 0 0 0 1 - - - - 0.001 0 0 0 0 -4.37114e-11 -0.001 0 0 0.001 -4.37114e-11 0 0 0 0 1 - - - 1 0 0 0.7041132 0 1 0 -0.179476 0 0 1 1.00003 0 0 0 1 - - - - 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 - - - - - - - - - - -0.2908646 -0.7711008 0.5663933 -3.806205 0.9551712 -0.1998833 0.2183912 -2.774845 -0.0551891 0.6045247 0.7946723 0.2407236 0 0 0 1 - - - - -0.2908646 -0.7711008 0.5663933 -3.648487 0.9551712 -0.1998833 0.2183912 3.463097 -0.0551891 0.6045247 0.7946723 0.2519307 0 0 0 1 - - - - - - - -
\ No newline at end of file diff --git a/cram_pr2/cram_urdf_bringup/resource/red_metal_plate.stl b/cram_pr2/cram_urdf_bringup/resource/red_metal_plate.stl deleted file mode 100644 index 2c01c91899..0000000000 Binary files a/cram_pr2/cram_urdf_bringup/resource/red_metal_plate.stl and /dev/null differ diff --git a/cram_pr2/cram_urdf_bringup/src/setup-urdf.lisp b/cram_pr2/cram_urdf_bringup/src/setup-urdf.lisp deleted file mode 100644 index 8b5abdc67e..0000000000 --- a/cram_pr2/cram_urdf_bringup/src/setup-urdf.lisp +++ /dev/null @@ -1,98 +0,0 @@ -;;; -;;; Copyright (c) 2019, Vanessa Hassouna -;;; Gayane Kazhoyan -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software -;;; without specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :demo) - - -(defparameter *robot-parameter* "robot_description") - -;;the collision-box for base_footprint, since the urdf does not provide it -(defparameter *collision-box* - "> - - - - - - - ") - -;;the tool-frame for the hsrb, since the urdf does not provide one -(defparameter *tool-frame* - " - - - - - ") - - -;;call this function in your demo seutp.lisp it also takes care of the parameter in rob-int e.g -;; -;; (defun setup-bullet-world () -;; (setf btr:*current-bullet-world* (make-instance 'btr:bt-reasoning-world)) -;; (let* ((robot (hsrb-proj::get-urdf)) -;; (kitchen (or *kitchen-urdf* ..... -(defun get-urdf-hsrb () - (let* ((robi (substitute #\SPACE #\` - (roslisp:get-param *robot-parameter*))) - (robot (setf rob-int:*robot-urdf* - (cl-urdf:parse-urdf - (concatenate 'string - ;;plus 15 because of base_footprint" - (subseq robi 0 (+ 15 (search "base_footprint" robi))) - *collision-box* - ;;plus 17 because of base_footprint"/> - (subseq robi (+ 17 (search "base_footprint" robi)) - (search " -;;; All rights reserved. -;;; -;;; Redistribution and use in source and binary forms, with or without -;;; modification, are permitted provided that the following conditions are met: -;;; -;;; * Redistributions of source code must retain the above copyright -;;; notice, this list of conditions and the following disclaimer. -;;; * Redistributions in binary form must reproduce the above copyright -;;; notice, this list of conditions and the following disclaimer in the -;;; documentation and/or other materials provided with the distribution. -;;; * Neither the name of the Intelligent Autonomous Systems Group/ -;;; Technische Universitaet Muenchen nor the names of its contributors -;;; may be used to endorse or promote products derived from this software -;;; without specific prior written permission. -;;; -;;; THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" -;;; AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE -;;; IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE -;;; ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE -;;; LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR -;;; CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF -;;; SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS -;;; INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN -;;; CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) -;;; ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE -;;; POSSIBILITY OF SUCH DAMAGE. - -(in-package :demo) - -(defvar *kitchen-urdf* nil) -(defparameter *robot-parameter* "robot_description") -(defparameter *kitchen-parameter* "kitchen_description") - -(defun setup-bullet-world () - (setf btr:*current-bullet-world* (make-instance 'btr:bt-reasoning-world)) - - (let* ((robot-urdf (substitute #\SPACE #\` (roslisp:get-param *robot-parameter*))) - (robot (or rob-int:*robot-urdf* - (setf rob-int:*robot-urdf* - (cl-urdf:parse-urdf robot-urdf)))) - (kitchen (or *kitchen-urdf* - (let ((kitchen-urdf-string - (roslisp:get-param *kitchen-parameter* nil))) - (when kitchen-urdf-string - (setf *kitchen-urdf* (cl-urdf:parse-urdf - kitchen-urdf-string))))))) - - (if (search "hsrb" robot-urdf) - (setf robot (get-urdf-hsrb)) - (when (search "boxy" robot-urdf ) - (get-setup-boxy))) - - (assert - (cut:force-ll - (prolog `(and - (btr:bullet-world ?w) - (btr:debug-window ?w) - (btr:assert ?w (btr:object :static-plane :floor ((0 0 0) (0 0 0 1)) - :normal (0 0 1) :constant 0)) - (btr:assert ?w (btr:object :urdf :kitchen ((0 0 0) (0 0 0 1)) - :collision-group :static-filter - :collision-mask (:default-filter - :character-filter) - :urdf ,kitchen - :compound T)) - (-> (cram-robot-interfaces:robot ?robot) - (btr:assert ?w (btr:object :urdf ?robot ((0 0 0) (0 0 0 1)) :urdf ,robot)) - (warn "ROBOT was not defined. Have you loaded a robot package?"))))))) - - - (let ((robot-object (btr:get-robot-object))) - (if robot-object - (btr:set-robot-state-from-tf cram-tf:*transformer* robot-object) - (warn "ROBOT was not defined. Have you loaded a robot package?")))) - -(defun init-projection () - (def-fact-group costmap-metadata () - (<- (location-costmap:costmap-size 12 12)) - (<- (location-costmap:costmap-origin -6 -6)) - (<- (location-costmap:costmap-resolution 0.05)) - - (<- (location-costmap:costmap-padding 0.5)) - (<- (location-costmap:costmap-manipulation-padding 0.2)) - (<- (location-costmap:costmap-in-reach-distance 0.7)) - (<- (location-costmap:costmap-reach-minimal-distance 0.2)) - (<- (location-costmap:visibility-costmap-size 2.5))) - - (setf cram-tf:*tf-broadcasting-enabled* t) - - (setf cram-tf:*transformer* (make-instance 'cl-tf2:buffer-client)) - - (setup-bullet-world) - - (setf cram-tf:*tf-default-timeout* 2.0) - - (setf prolog:*break-on-lisp-errors* t) - - (cram-bullet-reasoning:clear-costmap-vis-object)) -(roslisp-utilities:register-ros-init-function init-projection) diff --git a/cram_tutorials/cram_bullet_world_tutorial/src/setup.lisp b/cram_tutorials/cram_bullet_world_tutorial/src/setup.lisp index 9d4568dce5..c3ee407b35 100644 --- a/cram_tutorials/cram_bullet_world_tutorial/src/setup.lisp +++ b/cram_tutorials/cram_bullet_world_tutorial/src/setup.lisp @@ -34,19 +34,14 @@ (defun init-projection () (def-fact-group costmap-metadata () - (<- (location-costmap:costmap-size 12 12)) - (<- (location-costmap:costmap-origin -6 -6)) - (<- (location-costmap:costmap-resolution 0.05)) - - (<- (location-costmap:costmap-padding 0.2)) - (<- (location-costmap:costmap-manipulation-padding 0.2)) - (<- (location-costmap:costmap-in-reach-distance 0.6)) - (<- (location-costmap:costmap-reach-minimal-distance 0.2))) - - (setf cram-bullet-reasoning-belief-state:*robot-parameter* "robot_description") - (setf cram-bullet-reasoning-belief-state:*kitchen-parameter* "kitchen_description") - - ;; (sem-map:get-semantic-map) + (<- (costmap:costmap-size :iai-kitchen 12 12)) + (<- (costmap:costmap-origin :iai-kitchen -6 -6)) + (<- (costmap:costmap-resolution :iai-kitchen 0.05)) + + (<- (costmap:costmap-padding :pr2 0.2)) + (<- (costmap:costmap-manipulation-padding :pr2 0.2)) + (<- (costmap:costmap-in-reach-distance :pr2 0.6)) + (<- (costmap:costmap-reach-minimal-distance :pr2 0.2))) (cram-occasions-events:clear-belief) diff --git a/cram_tutorials/cram_bullet_world_tutorial/src/tutorial.lisp b/cram_tutorials/cram_bullet_world_tutorial/src/tutorial.lisp index e3368729cc..c248f34ff0 100644 --- a/cram_tutorials/cram_bullet_world_tutorial/src/tutorial.lisp +++ b/cram_tutorials/cram_bullet_world_tutorial/src/tutorial.lisp @@ -32,14 +32,14 @@ (defun get-kitchen-urdf () (slot-value - (btr:object btr:*current-bullet-world* :kitchen) + (btr:get-environment-object) 'cram-bullet-reasoning:urdf)) (defun move-kitchen-joint (&key (joint-name "iai_fridge_door_joint") - (joint-angle 0.2d0) (kitchen-name :kitchen)) + (joint-angle 0.2d0)) (btr:set-robot-state-from-joints `((,joint-name ,joint-angle)) - (btr:object btr:*current-bullet-world* kitchen-name))) + (btr:get-environment-object))) (defun add-objects-to-mesh-list (&optional (ros-package "cram_bullet_world_tutorial")) (mapcar (lambda (object-filename-and-object-extension) @@ -73,10 +73,10 @@ (cl-transforms:make-identity-rotation))) (defparameter *pose-meal-table* - (cl-tf:make-pose-stamped + (cl-transforms-stamped:make-pose-stamped "map" 0.0 - (cl-tf:make-3d-vector -0.15 2.0 0) - (cl-tf:make-quaternion 0.0d0 0.0d0 -1.0d0 0.0d0))) + (cl-transforms:make-3d-vector -0.15 2.0 0) + (cl-transforms:make-quaternion 0.0d0 0.0d0 -1.0d0 0.0d0))) (defparameter *pose-counter* (cl-transforms-stamped:make-pose-stamped @@ -144,9 +144,7 @@ (desig:a motion (type moving-torso) (joint-angle 0.3))) (exe:perform (desig:an action - (type positioning-arm) - (left-configuration park) - (right-configuration park))) + (type parking-arms))) (navigate-to ?navigation-goal)) (look-at ?ptu-goal)) ;; Pick up bottle-1 with right arm. @@ -154,8 +152,8 @@ (pick-up ?perceived-bottle-1 :right) (exe:perform (desig:an action - (type positioning-arm) - (right-configuration park))) + (type parking-arms) + (arms (:right)))) ;; Move to the meal table (let ((?pose *pose-meal-table*)) (navigate-to ?pose)) @@ -165,17 +163,17 @@ ;; Move left arm out of sight (exe:perform (desig:an action - (type positioning-arm) - (left-configuration park))) + (type parking-arms) + (arms (:left)))) ;; Place bottle-1 on second table (let ((?drop-pose *pose-bottle-2*)) (place-down ?drop-pose ?perceived-bottle-1 :right)) ;; Move right arm out of sight (exe:perform (desig:an action - (type positioning-arm) - (right-configuration park))) - ;; Move to the counter table + (type parking-arms) + (arms (:right)))) + ;; Move to the counter table (let ((?navigation-goal *pose-counter*)) (navigate-to ?navigation-goal)) ;; Place bottle-2 on the counter @@ -183,6 +181,4 @@ (place-down ?drop-pose ?perceived-bottle-2 :left)) (exe:perform (desig:an action - (type positioning-arm) - (left-configuration park) - (right-configuration park)))))))) + (type parking-arms)))))))) diff --git a/cram_tutorials/cram_pick_place_tutorial/src/setup.lisp b/cram_tutorials/cram_pick_place_tutorial/src/setup.lisp index 4ad1be18f2..8f66faafd2 100644 --- a/cram_tutorials/cram_pick_place_tutorial/src/setup.lisp +++ b/cram_tutorials/cram_pick_place_tutorial/src/setup.lisp @@ -35,19 +35,14 @@ (defun init-projection () (def-fact-group costmap-metadata () - (<- (location-costmap:costmap-size 12 12)) - (<- (location-costmap:costmap-origin -6 -6)) - (<- (location-costmap:costmap-resolution 0.05)) - - (<- (location-costmap:costmap-padding 0.2)) - (<- (location-costmap:costmap-manipulation-padding 0.2)) - (<- (location-costmap:costmap-in-reach-distance 0.6)) - (<- (location-costmap:costmap-reach-minimal-distance 0.2))) - - (setf cram-bullet-reasoning-belief-state:*robot-parameter* "robot_description") - (setf cram-bullet-reasoning-belief-state:*kitchen-parameter* "kitchen_description") - - ;; (sem-map:get-semantic-map) + (<- (costmap:costmap-size :iai-kitchen 12 12)) + (<- (costmap:costmap-origin :iai-kitchen -6 -6)) + (<- (costmap:costmap-resolution :iai-kitchen 0.05)) + + (<- (costmap:costmap-padding :pr2 0.2)) + (<- (costmap:costmap-manipulation-padding :pr2 0.2)) + (<- (costmap:costmap-in-reach-distance :pr2 0.6)) + (<- (costmap:costmap-reach-minimal-distance :pr2 0.2))) (cram-occasions-events:clear-belief) diff --git a/cram_tutorials/cram_pick_place_tutorial/src/tutorial.lisp b/cram_tutorials/cram_pick_place_tutorial/src/tutorial.lisp index 87134a2bf6..03824c94d9 100644 --- a/cram_tutorials/cram_pick_place_tutorial/src/tutorial.lisp +++ b/cram_tutorials/cram_pick_place_tutorial/src/tutorial.lisp @@ -32,15 +32,13 @@ (in-package :pp-tut) (defun get-kitchen-urdf () - (slot-value - (btr:object btr:*current-bullet-world* :kitchen) - 'cram-bullet-reasoning:urdf)) + (slot-value (btr:get-environment-object) 'btr:urdf)) (defun move-kitchen-joint (&key (joint-name "iai_fridge_door_joint") - (joint-angle 0.2d0) (kitchen-name :kitchen)) + (joint-angle 0.2d0)) (btr:set-robot-state-from-joints `((,joint-name ,joint-angle)) - (btr:object btr:*current-bullet-world* kitchen-name))) + (btr:get-environment-object))) (defun spawn-object (spawn-pose &optional (obj-type :bottle) (obj-name 'bottle-1) (obj-color '(1 0 0))) (unless (assoc obj-type btr::*mesh-files*) @@ -86,16 +84,18 @@ (etypecase object-or-pose (symbol (if (btr:object btr:*current-bullet-world* object-or-pose) - (btr:add-vis-axis-object object-or-pose size) + (btr:add-vis-axis-object object-or-pose :length size) (if (find-object-of-type object-or-pose) - (btr:add-vis-axis-object (btr:name (find-object-of-type object-or-pose)) size) + (btr:add-vis-axis-object + (btr:name (find-object-of-type object-or-pose)) + :length size) (warn "Unknown object, please either give an object name or object type.")))) (cl-transforms-stamped:pose-stamped (when (equalp (cl-transforms-stamped:frame-id object-or-pose) "base_footprint") (warn "Pose is not in MAP frame. It is visualized with respect to the MAP though.")) - (btr:add-vis-axis-object object-or-pose size)) + (btr:add-vis-axis-object object-or-pose :length size)) (cl-transforms:pose - (btr:add-vis-axis-object object-or-pose size))))) + (btr:add-vis-axis-object object-or-pose :length size))))) (defmethod print-object ((pose cl-transforms-stamped:pose-stamped) stream)